diff --git a/CMakeLists.txt b/CMakeLists.txt index 664f1ea..f08f890 100644 --- a/CMakeLists.txt +++ b/CMakeLists.txt @@ -1,3 +1,3 @@ -idf_component_register(SRC_DIRS "source" - INCLUDE_DIRS "include" +idf_component_register(SRC_DIRS "source" "SH2" + INCLUDE_DIRS "include" "SH2" REQUIRES driver esp_timer cmock) diff --git a/SH2/sh2.c b/SH2/sh2.c new file mode 100644 index 0000000..d2f00f0 --- /dev/null +++ b/SH2/sh2.c @@ -0,0 +1,2331 @@ +/* + * Copyright 2015-2018 Hillcrest Laboratories, Inc. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License and + * any applicable agreements you may have with Hillcrest Laboratories, Inc. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file sh2.c + * @author David Wheeler + * @date 22 Sept 2015 + * @brief API Definition for Hillcrest SH-2 Sensor Hub. + * + * The sh2 API provides functions for opening a session with + * the sensor hub and performing all supported operations with it. + * This includes enabling sensors and reading events as well as + * other housekeeping functions. + * + */ + +#include "sh2.h" +#include "sh2_err.h" +#include "shtp.h" +#include "sh2_util.h" + +#include + +// ------------------------------------------------------------------------ +// Private type definitions + +#define GUID_EXECUTABLE (1) +#define GUID_SENSORHUB (2) + +// executable/device channel responses +#define EXECUTABLE_DEVICE_CMD_RESET (1) +#define EXECUTABLE_DEVICE_CMD_ON (2) +#define EXECUTABLE_DEVICE_CMD_SLEEP (3) + +// executable/device channel responses +#define EXECUTABLE_DEVICE_RESP_RESET_COMPLETE (1) + +// Tags for sensorhub app advertisements. +#define TAG_SH2_VERSION (0x80) +#define TAG_SH2_REPORT_LENGTHS (0x81) + +// Max length of sensorhub version string. +#define MAX_VER_LEN (16) + +// Max number of report ids supported +#define SH2_MAX_REPORT_IDS (64) + +#if defined(_MSC_VER) +#define PACKED_STRUCT struct +#pragma pack(push, 1) +#elif defined(__GNUC__) +#define PACKED_STRUCT struct __attribute__((packed)) +#else +#define PACKED_STRUCT __packed struct +#endif + +#define ADVERT_TIMEOUT_US (200000) + +// Command and Subcommand values +#define SH2_CMD_ERRORS 1 +#define SH2_CMD_COUNTS 2 +#define SH2_COUNTS_GET_COUNTS 0 +#define SH2_COUNTS_CLEAR_COUNTS 1 +#define SH2_CMD_TARE 3 +#define SH2_TARE_TARE_NOW 0 +#define SH2_TARE_PERSIST_TARE 1 +#define SH2_TARE_SET_REORIENTATION 2 +#define SH2_CMD_INITIALIZE 4 +#define SH2_INIT_SYSTEM 1 +#define SH2_INIT_UNSOLICITED 0x80 +// #define SH2_CMD_FRS 5 /* Depreciated */ +#define SH2_CMD_DCD 6 +#define SH2_CMD_ME_CAL 7 +#define SH2_CMD_DCD_SAVE 9 +#define SH2_CMD_GET_OSC_TYPE 0x0A +#define SH2_CMD_CLEAR_DCD_AND_RESET 0x0B +#define SH2_CMD_CAL 0x0C +#define SH2_CAL_START 0 +#define SH2_CAL_FINISH 1 +#define SH2_CMD_BOOTLOADER 0x0D /* SH-2 Reference Manual 6.4.12 */ +#define SH2_BL_MODE_REQ 0 +#define SH2_BL_STATUS_REQ 1 +#define SH2_CMD_INTERACTIVE_ZRO 0x0E /* SH-2 Reference Manual 6.4.13 */ + +// SENSORHUB_COMMAND_REQ +#define SENSORHUB_COMMAND_REQ (0xF2) +#define COMMAND_PARAMS (9) +typedef PACKED_STRUCT { + uint8_t reportId; + uint8_t seq; + uint8_t command; + uint8_t p[COMMAND_PARAMS]; +} CommandReq_t; + +// SENSORHUB_COMMAND_RESP +#define SENSORHUB_COMMAND_RESP (0xF1) +#define RESPONSE_VALUES (11) +typedef PACKED_STRUCT { + uint8_t reportId; + uint8_t seq; + uint8_t command; + uint8_t commandSeq; + uint8_t respSeq; + uint8_t r[RESPONSE_VALUES]; +} CommandResp_t; + +// SENSORHUB_PROD_ID_REQ +#define SENSORHUB_PROD_ID_REQ (0xF9) +typedef PACKED_STRUCT { + uint8_t reportId; + uint8_t reserved; +} ProdIdReq_t; + +// SENSORHUB_PROD_ID_RESP +#define SENSORHUB_PROD_ID_RESP (0xF8) +typedef PACKED_STRUCT { + uint8_t reportId; + uint8_t resetCause; + uint8_t swVerMajor; + uint8_t swVerMinor; + uint32_t swPartNumber; + uint32_t swBuildNumber; + uint16_t swVerPatch; + uint8_t reserved0; + uint8_t reserved1; +} ProdIdResp_t; + +// Report definitions +// Bit fields for Feature Report flags +#define FEAT_CHANGE_SENSITIVITY_RELATIVE (1) +#define FEAT_CHANGE_SENSITIVITY_ABSOLUTE (0) +#define FEAT_CHANGE_SENSITIVITY_ENABLED (2) +#define FEAT_CHANGE_SENSITIVITY_DISABLED (0) +#define FEAT_WAKE_ENABLED (4) +#define FEAT_WAKE_DISABLED (0) +#define FEAT_ALWAYS_ON_ENABLED (8) +#define FEAT_ALWAYS_ON_DISABLED (0) + +// GET_FEATURE_REQ +#define SENSORHUB_GET_FEATURE_REQ (0xFE) +typedef PACKED_STRUCT{ + uint8_t reportId; + uint8_t featureReportId; +} GetFeatureReq_t; + +// SENSORHUB_GET_FEATURE_RESP +#define SENSORHUB_GET_FEATURE_RESP (0xFC) +typedef PACKED_STRUCT{ + uint8_t reportId; + uint8_t featureReportId; // sensor id + uint8_t flags; // FEAT_... values + uint16_t changeSensitivity; + uint32_t reportInterval_uS; + uint32_t batchInterval_uS; + uint32_t sensorSpecific; +} GetFeatureResp_t; + + +typedef struct sh2_s sh2_t; + +typedef int (sh2_OpStart_t)(sh2_t *pSh2); +typedef void (sh2_OpRx_t)(sh2_t *pSh2, const uint8_t *payload, uint16_t len); + +typedef struct sh2_Op_s { + uint32_t timeout_us; + sh2_OpStart_t *start; + sh2_OpRx_t *rx; +} sh2_Op_t; + +// Parameters and state information for the operation in progress +typedef union { + struct { + CommandReq_t req; + } sendCmd; + struct { + sh2_ProductIds_t *pProdIds; + uint8_t nextEntry; + uint8_t expectedEntries; + } getProdIds; + struct { + sh2_SensorConfig_t *pConfig; + sh2_SensorId_t sensorId; + } getSensorConfig; + struct { + const sh2_SensorConfig_t *pConfig; + sh2_SensorId_t sensorId; + } setSensorConfig; + struct { + uint16_t frsType; + uint32_t *pData; + uint16_t *pWords; + uint16_t nextOffset; + } getFrs; + struct { + uint16_t frsType; + uint32_t *pData; + uint16_t words; + uint16_t offset; + } setFrs; + struct { + uint8_t severity; + sh2_ErrorRecord_t *pErrors; + uint16_t *pNumErrors; + uint16_t errsRead; + } getErrors; + struct { + sh2_SensorId_t sensorId; + sh2_Counts_t *pCounts; + } getCounts; + struct { + uint8_t sensors; + } calConfig; + struct { + uint8_t *pSensors; + } getCalConfig; + struct { + sh2_SensorId_t sensorId; + } forceFlush; + struct { + sh2_OscType_t *pOscType; + } getOscType; + struct { + uint32_t interval_us; + } startCal; + struct { + sh2_CalStatus_t status; + } finishCal; +} sh2_OpData_t; + +// Max length of an FRS record, words. +#define MAX_FRS_WORDS (72) + +struct sh2_s { + // Pointer to the SHTP HAL + sh2_Hal_t *pHal; + + // associated SHTP instance + void *pShtp; + + volatile bool resetComplete; + bool advertDone; + uint8_t executableChan; + uint8_t controlChan; + char version[MAX_VER_LEN+1]; + + // Report lengths + struct { + uint8_t id; + uint8_t len; + } report[SH2_MAX_REPORT_IDS]; + + // Multi-step operation support + const sh2_Op_t *pOp; + int opStatus; + sh2_OpData_t opData; + uint8_t lastCmdId; + uint8_t cmdSeq; + uint8_t nextCmdSeq; + + // Event callback and it's cookie + sh2_EventCallback_t *eventCallback; + void * eventCookie; + + // Sensor callback and it's cookie + sh2_SensorCallback_t *sensorCallback; + void * sensorCookie; + + // Storage space for reading sensor metadata + uint32_t frsData[MAX_FRS_WORDS]; + uint16_t frsDataLen; + + // Stats + uint32_t execBadPayload; + uint32_t emptyPayloads; + uint32_t unknownReportIds; + +}; + +#define SENSORHUB_BASE_TIMESTAMP_REF (0xFB) +typedef PACKED_STRUCT { + uint8_t reportId; + uint32_t timebase; +} BaseTimestampRef_t; + +#define SENSORHUB_TIMESTAMP_REBASE (0xFA) +typedef PACKED_STRUCT { + uint8_t reportId; + int32_t timebase; +} TimestampRebase_t; + +// SENSORHUB_FORCE_SENSOR_FLUSH +#define SENSORHUB_FORCE_SENSOR_FLUSH (0xF0) +typedef PACKED_STRUCT { + uint8_t reportId; + uint8_t sensorId; +} ForceFlushReq_t; + +// SENSORHUB_FLUSH_COMPLETED +#define SENSORHUB_FLUSH_COMPLETED (0xEF) +typedef PACKED_STRUCT { + uint8_t reportId; + uint8_t sensorId; +} ForceFlushResp_t; + +// ------------------------------------------------------------------------ +// Private data + +// SH2 state +sh2_t _sh2; + +// SH2 Async Event Message +static sh2_AsyncEvent_t sh2AsyncEvent; + +// ------------------------------------------------------------------------ +// Private functions + +// SH-2 transaction phases +static int opStart(sh2_t *pSh2, const sh2_Op_t *pOp) +{ + // return error if another operation already in progress + if (pSh2->pOp) return SH2_ERR_OP_IN_PROGRESS; + + // Establish this operation as the new operation in progress + pSh2->pOp = pOp; + pSh2->opStatus = SH2_OK; + int rc = pOp->start(pSh2); // Call start method + if (rc != SH2_OK) { + // Unregister this operation + pSh2->opStatus = rc; + pSh2->pOp = 0; + } + + return rc; +} + +static void opRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + if ((pSh2->pOp != 0) && // An operation is in progress + (pSh2->pOp->rx != 0)) { // and it has an rx method + pSh2->pOp->rx(pSh2, payload, len); // Call receive method + } +} + +static void sensorhubAdvertHdlr(void *cookie, uint8_t tag, uint8_t len, uint8_t *value) +{ + sh2_t *pSh2 = (sh2_t *)cookie; + + switch (tag) { + case TAG_SH2_VERSION: + strcpy(pSh2->version, (const char *)value); + break; + + case TAG_SH2_REPORT_LENGTHS: + { + uint8_t reports = len/2; + if (reports > SH2_MAX_REPORT_IDS) { + // Hub gave us more report lengths than we can store! + reports = SH2_MAX_REPORT_IDS; + } + + for (int n = 0; n < reports; n++) { + pSh2->report[n].id = value[n*2]; + pSh2->report[n].len = value[n*2 + 1]; + } + break; + } + + case 0: + { + // 0 tag indicates end of advertisements for this app + // At this time, the SHTP layer can give us our channel numbers + pSh2->executableChan = shtp_chanNo(pSh2->pShtp, "executable", "device"); + pSh2->controlChan = shtp_chanNo(pSh2->pShtp, "sensorhub", "control"); + + pSh2->advertDone = true; + break; + } + + default: + break; + } +} + +static void sensorhubControlHdlr(void *cookie, uint8_t *payload, uint16_t len, uint32_t timestamp) +{ + sh2_t *pSh2 = (sh2_t *)cookie; + + uint16_t cursor = 0; + uint32_t count = 0; + CommandResp_t * pResp = 0; + + if (len == 0) { + pSh2->emptyPayloads++; + return; + } + + while (cursor < len) { + // Get next report id + count++; + uint8_t reportId = payload[cursor]; + + // Determine report length + uint8_t reportLen = 0; + for (int n = 0; n < SH2_MAX_REPORT_IDS; n++) { + if (pSh2->report[n].id == reportId) { + reportLen = pSh2->report[n].len; + break; + } + } + if (reportLen == 0) { + // An unrecognized report id + pSh2->unknownReportIds++; + return; + } + else { + // Check for unsolicited initialize response + if (reportId == SENSORHUB_COMMAND_RESP) { + pResp = (CommandResp_t *)(payload+cursor); + if ((pResp->command == (SH2_CMD_INITIALIZE | SH2_INIT_UNSOLICITED)) && + (pResp->r[1] == SH2_INIT_SYSTEM)) { + // This is an unsolicited INIT message. + // Is it time to call reset callback? + } + + } // Check for Get Feature Response + else if (reportId == SENSORHUB_GET_FEATURE_RESP) { + if (pSh2->eventCallback) { + GetFeatureResp_t * pGetFeatureResp; + pGetFeatureResp = (GetFeatureResp_t *)(payload + cursor); + + sh2AsyncEvent.eventId = SH2_GET_FEATURE_RESP; + sh2AsyncEvent.sh2SensorConfigResp.sensorId = pGetFeatureResp->featureReportId; + sh2AsyncEvent.sh2SensorConfigResp.sensorConfig.changeSensitivityEnabled = ((pGetFeatureResp->flags & FEAT_CHANGE_SENSITIVITY_ENABLED) != 0); + sh2AsyncEvent.sh2SensorConfigResp.sensorConfig.changeSensitivityRelative = ((pGetFeatureResp->flags & FEAT_CHANGE_SENSITIVITY_RELATIVE) != 0); + sh2AsyncEvent.sh2SensorConfigResp.sensorConfig.wakeupEnabled = ((pGetFeatureResp->flags & FEAT_WAKE_ENABLED) != 0); + sh2AsyncEvent.sh2SensorConfigResp.sensorConfig.alwaysOnEnabled = ((pGetFeatureResp->flags & FEAT_ALWAYS_ON_ENABLED) != 0); + sh2AsyncEvent.sh2SensorConfigResp.sensorConfig.changeSensitivity = pGetFeatureResp->changeSensitivity; + sh2AsyncEvent.sh2SensorConfigResp.sensorConfig.reportInterval_us = pGetFeatureResp->reportInterval_uS; + sh2AsyncEvent.sh2SensorConfigResp.sensorConfig.batchInterval_us = pGetFeatureResp->batchInterval_uS; + sh2AsyncEvent.sh2SensorConfigResp.sensorConfig.sensorSpecific = pGetFeatureResp->sensorSpecific; + + pSh2->eventCallback(pSh2->eventCookie, &sh2AsyncEvent); + } + } + + // Hand off to operation in progress, if any + opRx(pSh2, payload+cursor, reportLen); + cursor += reportLen; + } + } +} + +static int opCompleted(sh2_t *pSh2, int status) +{ + // Record status + pSh2->opStatus = status; + + // Signal that op is done. + pSh2->pOp = 0; + + return SH2_OK; +} + +static int opProcess(sh2_t *pSh2, const sh2_Op_t *pOp) +{ + int status = SH2_OK; + uint32_t start_us = 0; + + start_us = pSh2->pHal->getTimeUs(pSh2->pHal); + + status = opStart(&_sh2, pOp); + if (status != SH2_OK) { + return status; + } + + uint32_t now_us = start_us; + + // While op not complete and not timed out. + while ((pSh2->pOp != 0) && + ((pOp->timeout_us == 0) || + ((now_us-start_us) < pOp->timeout_us))) { + // Service SHTP to poll the device. + shtp_service(pSh2->pShtp); + + // Update the time + now_us = pSh2->pHal->getTimeUs(pSh2->pHal); + } + + if (pSh2->pOp != 0) { + // Operation has timed out. Clean up. + pSh2->pOp = 0; + pSh2->opStatus = SH2_ERR_TIMEOUT; + } + + return pSh2->opStatus; +} + +static uint8_t getReportLen(sh2_t *pSh2, uint8_t reportId) +{ + for (int n = 0; n < SH2_MAX_REPORT_IDS; n++) { + if (pSh2->report[n].id == reportId) { + return pSh2->report[n].len; + } + } + + return 0; +} + +// Produce 64-bit microsecond timestamp for a sensor event +static uint64_t touSTimestamp(uint32_t hostInt, int32_t referenceDelta, uint16_t delay) +{ + static uint32_t lastHostInt = 0; + static uint32_t rollovers = 0; + uint64_t timestamp; + + // Count times hostInt timestamps rolled over to produce upper bits + if (hostInt < lastHostInt) { + rollovers++; + } + lastHostInt = hostInt; + + timestamp = ((uint64_t)rollovers << 32); + timestamp += hostInt + (referenceDelta + delay) * 100; + + return timestamp; +} + +static void sensorhubInputHdlr(sh2_t *pSh2, uint8_t *payload, uint16_t len, uint32_t timestamp) +{ + sh2_SensorEvent_t event; + uint16_t cursor = 0; + + uint32_t referenceDelta; + + referenceDelta = 0; + + while (cursor < len) { + // Get next report id + uint8_t reportId = payload[cursor]; + + // Determine report length + uint8_t reportLen = getReportLen(pSh2, reportId); + if (reportLen == 0) { + // An unrecognized report id + pSh2->unknownReportIds++; + return; + } + else { + if (reportId == SENSORHUB_BASE_TIMESTAMP_REF) { + const BaseTimestampRef_t *rpt = (const BaseTimestampRef_t *)(payload+cursor); + + // store base timestamp reference + referenceDelta = -rpt->timebase; + } + else if (reportId == SENSORHUB_TIMESTAMP_REBASE) { + const TimestampRebase_t *rpt = (const TimestampRebase_t *)(payload+cursor); + + referenceDelta += rpt->timebase; + } + else if (reportId == SENSORHUB_FLUSH_COMPLETED) { + // Route this as if it arrived on command channel. + opRx(pSh2, payload+cursor, reportLen); + } + else { + uint8_t *pReport = payload+cursor; + uint16_t delay = ((pReport[2] & 0xFC) << 6) + pReport[3]; + event.timestamp_uS = touSTimestamp(timestamp, referenceDelta, delay); + event.reportId = reportId; + memcpy(event.report, pReport, reportLen); + event.len = reportLen; + if (pSh2->sensorCallback != 0) { + pSh2->sensorCallback(pSh2->sensorCookie, &event); + } + } + cursor += reportLen; + } + } +} + +static void sensorhubInputNormalHdlr(void *cookie, uint8_t *payload, uint16_t len, uint32_t timestamp) +{ + sh2_t *pSh2 = (sh2_t *)cookie; + + sensorhubInputHdlr(pSh2, payload, len, timestamp); +} + +static void sensorhubInputWakeHdlr(void *cookie, uint8_t *payload, uint16_t len, uint32_t timestamp) +{ + sh2_t *pSh2 = (sh2_t *)cookie; + + sensorhubInputHdlr(pSh2, payload, len, timestamp); +} + +static void sensorhubInputGyroRvHdlr(void *cookie, uint8_t *payload, uint16_t len, uint32_t timestamp) +{ + sh2_t *pSh2 = (sh2_t *)cookie; + sh2_SensorEvent_t event; + uint16_t cursor = 0; + + uint8_t reportId = SH2_GYRO_INTEGRATED_RV; + uint8_t reportLen = getReportLen(pSh2, reportId); + + while (cursor < len) { + event.timestamp_uS = timestamp; + event.reportId = reportId; + memcpy(event.report, payload+cursor, reportLen); + event.len = reportLen; + + if (pSh2->sensorCallback != 0) { + pSh2->sensorCallback(pSh2->sensorCookie, &event); + } + + cursor += reportLen; + } +} + +static void executableAdvertHdlr(void *cookie, uint8_t tag, uint8_t len, uint8_t *value) +{ + // Ignore. No known TLV tags for this app. +} + +static void executableDeviceHdlr(void *cookie, uint8_t *payload, uint16_t len, uint32_t timestamp) +{ + sh2_t *pSh2 = (sh2_t *)cookie; + + // Discard if length is bad + if (len != 1) { + pSh2->execBadPayload++; + return; + } + + switch (payload[0]) { + case EXECUTABLE_DEVICE_RESP_RESET_COMPLETE: + // reset process is now done. + pSh2->resetComplete = true; + + // Notify client that reset is complete. + sh2AsyncEvent.eventId = SH2_RESET; + if (pSh2->eventCallback) { + pSh2->eventCallback(pSh2->eventCookie, &sh2AsyncEvent); + } + break; + default: + pSh2->execBadPayload++; + break; + } +} + +static int sendExecutable(sh2_t *pSh2, uint8_t cmd) +{ + return shtp_send(pSh2->pShtp, pSh2->executableChan, &cmd, 1); +} + +static int sendCtrl(sh2_t *pSh2, const uint8_t *data, uint16_t len) +{ + return shtp_send(pSh2->pShtp, pSh2->controlChan, data, len); +} + +static int16_t toQ14(double x) +{ + int16_t retval = (int16_t)(x * (1<<14)); + + return retval; +} + +// ------------------------------------------------------------------------ +// Get Product ID support + +// Get Product ID Op handler +static int getProdIdStart(sh2_t *pSh2) +{ + int rc = SH2_OK; + ProdIdReq_t req; + + pSh2->opData.getProdIds.nextEntry = 0; + pSh2->opData.getProdIds.expectedEntries = 4; // Most products supply 4 product ids. + // When the first arrives, we'll know if + // we need to adjust this. + + // Set up request to issue + memset(&req, 0, sizeof(req)); + req.reportId = SENSORHUB_PROD_ID_REQ; + rc = sendCtrl(pSh2, (uint8_t *)&req, sizeof(req)); + + return rc; +} + +static void getProdIdRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + ProdIdResp_t *resp = (ProdIdResp_t *)payload; + + // skip this if it isn't the product id response. + if (resp->reportId != SENSORHUB_PROD_ID_RESP) return; + + // Store this product id, if we can + sh2_ProductIds_t *pProdIds = pSh2->opData.getProdIds.pProdIds; + + if (pProdIds) { + // Store the product id response + if (pSh2->opData.getProdIds.nextEntry < pSh2->opData.getProdIds.expectedEntries) { + sh2_ProductId_t *pProdId = &pProdIds->entry[pSh2->opData.getProdIds.nextEntry]; + + pProdId->resetCause = resp->resetCause; + pProdId->swVersionMajor = resp->swVerMajor; + pProdId->swVersionMinor = resp->swVerMinor; + pProdId->swPartNumber = resp->swPartNumber; + pProdId->swBuildNumber = resp->swBuildNumber; + pProdId->swVersionPatch = resp->swVerPatch; + pProdId->reserved0 = resp->reserved0; + pProdId->reserved1 = resp->reserved1; + + if (pProdId->swPartNumber == 10004095) { + // FSP200 has 5 product id entries + pSh2->opData.getProdIds.expectedEntries = 5; + } + + + pSh2->opData.getProdIds.nextEntry++; + } + } + + // Complete this operation if there is no storage for more product ids + if ((pSh2->opData.getProdIds.pProdIds == 0) || + (pSh2->opData.getProdIds.nextEntry >= pSh2->opData.getProdIds.expectedEntries)) { + + pSh2->opData.getProdIds.pProdIds->numEntries = pSh2->opData.getProdIds.nextEntry; + opCompleted(pSh2, SH2_OK); + } + + return; +} + +const sh2_Op_t getProdIdOp = { + .start = getProdIdStart, + .rx = getProdIdRx, +}; + +// ------------------------------------------------------------------------ +// Set Sensor Config + +static int getSensorConfigStart(sh2_t *pSh2) +{ + int rc = SH2_OK; + GetFeatureReq_t req; + + // set up request to issue + memset(&req, 0, sizeof(req)); + req.reportId = SENSORHUB_GET_FEATURE_REQ; + req.featureReportId = pSh2->opData.getSensorConfig.sensorId; + rc = sendCtrl(pSh2, (uint8_t *)&req, sizeof(req)); + + return rc; +} + +static void getSensorConfigRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + GetFeatureResp_t *resp = (GetFeatureResp_t *)payload; + sh2_SensorConfig_t *pConfig; + + // skip this if it isn't the response we're waiting for. + if (resp->reportId != SENSORHUB_GET_FEATURE_RESP) return; + if (resp->featureReportId != pSh2->opData.getSensorConfig.sensorId) return; + + // Copy out data + pConfig = pSh2->opData.getSensorConfig.pConfig; + + pConfig->changeSensitivityEnabled = ((resp->flags & FEAT_CHANGE_SENSITIVITY_ENABLED) != 0); + pConfig->changeSensitivityRelative = ((resp->flags & FEAT_CHANGE_SENSITIVITY_RELATIVE) != 0); + pConfig->wakeupEnabled = ((resp->flags & FEAT_WAKE_ENABLED) != 0); + pConfig->alwaysOnEnabled = ((resp->flags & FEAT_ALWAYS_ON_ENABLED) != 0); + pConfig->changeSensitivity = resp->changeSensitivity; + pConfig->reportInterval_us = resp->reportInterval_uS; + pConfig->batchInterval_us = resp->batchInterval_uS; + pConfig->sensorSpecific = resp->sensorSpecific; + + // Complete this operation + opCompleted(pSh2, SH2_OK); + + return; +} + +const sh2_Op_t getSensorConfigOp = { + .start = getSensorConfigStart, + .rx = getSensorConfigRx, +}; + +// ------------------------------------------------------------------------ +// Set Sensor Config + +// SENSORHUB_SET_FEATURE_CMD +#define SENSORHUB_SET_FEATURE_CMD (0xFD) +typedef PACKED_STRUCT { + uint8_t reportId; // 0xFD + uint8_t featureReportId; // sensor id + uint8_t flags; // FEAT_... values + uint16_t changeSensitivity; + uint32_t reportInterval_uS; + uint32_t batchInterval_uS; + uint32_t sensorSpecific; +} SetFeatureReport_t; + +static int setSensorConfigStart(sh2_t *pSh2) +{ + SetFeatureReport_t req; + uint8_t flags = 0; + int rc; + sh2_SensorConfig_t *pConfig = pSh2->opData.getSensorConfig.pConfig; + + if (pConfig->changeSensitivityEnabled) flags |= FEAT_CHANGE_SENSITIVITY_ENABLED; + if (pConfig->changeSensitivityRelative) flags |= FEAT_CHANGE_SENSITIVITY_RELATIVE; + if (pConfig->wakeupEnabled) flags |= FEAT_WAKE_ENABLED; + if (pConfig->alwaysOnEnabled) flags |= FEAT_ALWAYS_ON_ENABLED; + + memset(&req, 0, sizeof(req)); + req.reportId = SENSORHUB_SET_FEATURE_CMD; + req.featureReportId = pSh2->opData.setSensorConfig.sensorId; + req.flags = flags; + req.changeSensitivity = pConfig->changeSensitivity; + req.reportInterval_uS = pConfig->reportInterval_us; + req.batchInterval_uS = pConfig->batchInterval_us; + req.sensorSpecific = pConfig->sensorSpecific; + + rc = sendCtrl(pSh2, (uint8_t *)&req, sizeof(req)); + opCompleted(pSh2, rc); + + return rc; +} + +const sh2_Op_t setSensorConfigOp = { + .start = setSensorConfigStart, +}; + +// ------------------------------------------------------------------------ +// Get FRS. + +// SENSORHUB_FRS_WRITE_REQ +#define SENSORHUB_FRS_WRITE_REQ (0xF7) +typedef PACKED_STRUCT { + uint8_t reportId; + uint8_t reserved; + uint16_t length; + uint16_t frsType; +} FrsWriteReq_t; + +// SENSORHUB_FRS_WRITE_DATA_REQ +#define SENSORHUB_FRS_WRITE_DATA_REQ (0xF6) +typedef PACKED_STRUCT { + uint8_t reportId; + uint8_t reserved; + uint16_t offset; + uint32_t data0; + uint32_t data1; +} FrsWriteDataReq_t; + +// FRS write status values +#define FRS_WRITE_STATUS_RECEIVED (0) +#define FRS_WRITE_STATUS_UNRECOGNIZED_FRS_TYPE (1) +#define FRS_WRITE_STATUS_BUSY (2) +#define FRS_WRITE_STATUS_WRITE_COMPLETED (3) +#define FRS_WRITE_STATUS_READY (4) +#define FRS_WRITE_STATUS_FAILED (5) +#define FRS_WRITE_STATUS_NOT_READY (6) // data received when not in write mode +#define FRS_WRITE_STATUS_INVALID_LENGTH (7) +#define FRS_WRITE_STATUS_RECORD_VALID (8) +#define FRS_WRITE_STATUS_INVALID_RECORD (9) +#define FRS_WRITE_STATUS_DEVICE_ERROR (10) +#define FRS_WRITE_STATUS_READ_ONLY (11) + +// SENSORHUB_FRS_WRITE_RESP +#define SENSORHUB_FRS_WRITE_RESP (0xF5) +typedef PACKED_STRUCT { + uint8_t reportId; + uint8_t status; + uint16_t wordOffset; +} FrsWriteResp_t; + +// RESP_FRS_READ_REQ +#define SENSORHUB_FRS_READ_REQ (0xF4) +typedef PACKED_STRUCT { + uint8_t reportId; + uint8_t reserved; + uint16_t readOffset; + uint16_t frsType; + uint16_t blockSize; +} FrsReadReq_t; + +// Get Datalen portion of len_status field +#define FRS_READ_DATALEN(x) ((x >> 4) & 0x0F) + +// Get status portion of len_status field +#define FRS_READ_STATUS(x) ((x) & 0x0F) + +// Status values +#define FRS_READ_STATUS_NO_ERROR 0 +#define FRS_READ_STATUS_UNRECOGNIZED_FRS_TYPE 1 +#define FRS_READ_STATUS_BUSY 2 +#define FRS_READ_STATUS_READ_RECORD_COMPLETED 3 +#define FRS_READ_STATUS_OFFSET_OUT_OF_RANGE 4 +#define FRS_READ_STATUS_RECORD_EMPTY 5 +#define FRS_READ_STATUS_READ_BLOCK_COMPLETED 6 +#define FRS_READ_STATUS_READ_BLOCK_AND_RECORD_COMPLETED 7 +#define FRS_READ_STATUS_DEVICE_ERROR 8 + +// SENSORHUB_FRS_READ_RESP +#define SENSORHUB_FRS_READ_RESP (0xF3) +typedef PACKED_STRUCT { + uint8_t reportId; + uint8_t len_status; // See FRS_READ... macros above + uint16_t wordOffset; + uint32_t data0; + uint32_t data1; + uint16_t frsType; + uint8_t reserved0; + uint8_t reserved1; +} FrsReadResp_t; + +static int getFrsStart(sh2_t *pSh2) +{ + int rc = SH2_OK; + FrsReadReq_t req; + + pSh2->opData.getFrs.nextOffset = 0; + + // set up request to issue + memset(&req, 0, sizeof(req)); + req.reportId = SENSORHUB_FRS_READ_REQ; + req.reserved = 0; + req.readOffset = 0; // read from start + req.frsType = pSh2->opData.getFrs.frsType; + req.blockSize = 0; // read all avail data + + rc = sendCtrl(pSh2, (uint8_t *)&req, sizeof(req)); + + return rc; +} + +static void getFrsRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + FrsReadResp_t *resp = (FrsReadResp_t *)payload; + uint8_t status; + + // skip this if it isn't the response we're looking for + if (resp->reportId != SENSORHUB_FRS_READ_RESP) return; + + // Check for errors: Unrecognized FRS type, Busy, Out of range, Device error + status = FRS_READ_STATUS(resp->len_status); + if ((status == FRS_READ_STATUS_UNRECOGNIZED_FRS_TYPE) || + (status == FRS_READ_STATUS_BUSY) || + (status == FRS_READ_STATUS_OFFSET_OUT_OF_RANGE) || + (status == FRS_READ_STATUS_DEVICE_ERROR) + ) { + // Operation failed + opCompleted(pSh2, SH2_ERR_HUB); + return; + } + + if (status == FRS_READ_STATUS_RECORD_EMPTY) { + // Empty record, return zero length. + *(pSh2->opData.getFrs.pWords) = 0; + opCompleted(pSh2, SH2_OK); + } + + // Store the contents from this response + uint16_t offset = resp->wordOffset; + + // check for missed offsets, resulting in error. + if (offset != pSh2->opData.getFrs.nextOffset) { + // Some data was dropped. + *(pSh2->opData.getFrs.pWords) = 0; + opCompleted(pSh2, SH2_ERR_IO); + } + + // store first word, if we have room + if ((*(pSh2->opData.getFrs.pWords) == 0) || + (offset <= *(pSh2->opData.getFrs.pWords))) { + pSh2->opData.getFrs.pData[offset] = resp->data0; + pSh2->opData.getFrs.nextOffset = offset+1; + } + + // store second word if there is one and we have room + if ((FRS_READ_DATALEN(resp->len_status) == 2) && + ((*(pSh2->opData.getFrs.pWords) == 0) || + (offset <= *(pSh2->opData.getFrs.pWords)))) { + pSh2->opData.getFrs.pData[offset+1] = resp->data1; + pSh2->opData.getFrs.nextOffset = offset+2; + } + + // If read is done, complete the operation + if ((status == FRS_READ_STATUS_READ_RECORD_COMPLETED) || + (status == FRS_READ_STATUS_READ_BLOCK_COMPLETED) || + (status == FRS_READ_STATUS_READ_BLOCK_AND_RECORD_COMPLETED)) { + *(pSh2->opData.getFrs.pWords) = pSh2->opData.getFrs.nextOffset; + + opCompleted(pSh2, SH2_OK); + } + + return; +} + +const sh2_Op_t getFrsOp = { + .start = getFrsStart, + .rx = getFrsRx, +}; + +// ------------------------------------------------------------------------ +// Support for sh2_getMetadata + +const static struct { + sh2_SensorId_t sensorId; + uint16_t recordId; +} sensorToRecordMap[] = { + { SH2_RAW_ACCELEROMETER, FRS_ID_META_RAW_ACCELEROMETER }, + { SH2_ACCELEROMETER, FRS_ID_META_ACCELEROMETER }, + { SH2_LINEAR_ACCELERATION, FRS_ID_META_LINEAR_ACCELERATION }, + { SH2_GRAVITY, FRS_ID_META_GRAVITY }, + { SH2_RAW_GYROSCOPE, FRS_ID_META_RAW_GYROSCOPE }, + { SH2_GYROSCOPE_CALIBRATED, FRS_ID_META_GYROSCOPE_CALIBRATED }, + { SH2_GYROSCOPE_UNCALIBRATED, FRS_ID_META_GYROSCOPE_UNCALIBRATED }, + { SH2_RAW_MAGNETOMETER, FRS_ID_META_RAW_MAGNETOMETER }, + { SH2_MAGNETIC_FIELD_CALIBRATED, FRS_ID_META_MAGNETIC_FIELD_CALIBRATED }, + { SH2_MAGNETIC_FIELD_UNCALIBRATED, FRS_ID_META_MAGNETIC_FIELD_UNCALIBRATED }, + { SH2_ROTATION_VECTOR, FRS_ID_META_ROTATION_VECTOR }, + { SH2_GAME_ROTATION_VECTOR, FRS_ID_META_GAME_ROTATION_VECTOR }, + { SH2_GEOMAGNETIC_ROTATION_VECTOR, FRS_ID_META_GEOMAGNETIC_ROTATION_VECTOR }, + { SH2_PRESSURE, FRS_ID_META_PRESSURE }, + { SH2_AMBIENT_LIGHT, FRS_ID_META_AMBIENT_LIGHT }, + { SH2_HUMIDITY, FRS_ID_META_HUMIDITY }, + { SH2_PROXIMITY, FRS_ID_META_PROXIMITY }, + { SH2_TEMPERATURE, FRS_ID_META_TEMPERATURE }, + { SH2_TAP_DETECTOR, FRS_ID_META_TAP_DETECTOR }, + { SH2_STEP_DETECTOR, FRS_ID_META_STEP_DETECTOR }, + { SH2_STEP_COUNTER, FRS_ID_META_STEP_COUNTER }, + { SH2_SIGNIFICANT_MOTION, FRS_ID_META_SIGNIFICANT_MOTION }, + { SH2_STABILITY_CLASSIFIER, FRS_ID_META_STABILITY_CLASSIFIER }, + { SH2_SHAKE_DETECTOR, FRS_ID_META_SHAKE_DETECTOR }, + { SH2_FLIP_DETECTOR, FRS_ID_META_FLIP_DETECTOR }, + { SH2_PICKUP_DETECTOR, FRS_ID_META_PICKUP_DETECTOR }, + { SH2_STABILITY_DETECTOR, FRS_ID_META_STABILITY_DETECTOR }, + { SH2_PERSONAL_ACTIVITY_CLASSIFIER, FRS_ID_META_PERSONAL_ACTIVITY_CLASSIFIER }, + { SH2_SLEEP_DETECTOR, FRS_ID_META_SLEEP_DETECTOR }, + { SH2_TILT_DETECTOR, FRS_ID_META_TILT_DETECTOR }, + { SH2_POCKET_DETECTOR, FRS_ID_META_POCKET_DETECTOR }, + { SH2_CIRCLE_DETECTOR, FRS_ID_META_CIRCLE_DETECTOR }, +}; + +static void stuffMetadata(sh2_SensorMetadata_t *pData, uint32_t *frsData) +{ + // Populate the sensorMetadata structure with results + pData->meVersion = (frsData[0] >> 0) & 0xFF; + pData->mhVersion = (frsData[0] >> 8) & 0xFF; + pData->shVersion = (frsData[0] >> 16) & 0xFF; + pData->range = frsData[1]; + pData->resolution = frsData[2]; + pData->power_mA = (frsData[3] >> 0) & 0xFFFF; // 16.10 format + pData->revision = (frsData[3] >> 16) & 0xFFFF; + pData->minPeriod_uS = frsData[4]; + pData->maxPeriod_uS = 0; // ...unless reading format 4 metadata below + pData->fifoMax = (frsData[5] >> 0) & 0xFFFF; + pData->fifoReserved = (frsData[5] >> 16) & 0xFFFF; + pData->batchBufferBytes = (frsData[6] >> 0) & 0xFFFF;; + pData->vendorIdLen = (frsData[6] >> 16) & 0xFFFF; + + // Init fields that may not be present, depending on metadata revision + pData->qPoint1 = 0; + pData->qPoint2 = 0; + pData->qPoint3 = 0; + pData->sensorSpecificLen = 0; + strcpy(pData->vendorId, ""); // init with empty string in case vendorIdLen == 0 + + int vendorIdOffset = 8; + // Get revision-specific fields + if (pData->revision == 0) { + // No fixed fields, vendor id copied after if-else block + } + else if (pData->revision == 1) { + pData->qPoint1 = (frsData[7] >> 0) & 0xFFFF; + pData->qPoint2 = (frsData[7] >> 16) & 0xFFFF; + } + else if (pData->revision == 2) { + pData->qPoint1 = (frsData[7] >> 0) & 0xFFFF; + pData->qPoint2 = (frsData[7] >> 16) & 0xFFFF; + pData->sensorSpecificLen = (frsData[8] >> 0) & 0xFFFF; + memcpy(pData->sensorSpecific, (uint8_t *)&frsData[9], pData->sensorSpecificLen); + vendorIdOffset = 9 + ((pData->sensorSpecificLen+3)/4); // 9 + one word for every 4 bytes of SS data + } + else if (pData->revision == 3) { + pData->qPoint1 = (frsData[7] >> 0) & 0xFFFF; + pData->qPoint2 = (frsData[7] >> 16) & 0xFFFF; + pData->sensorSpecificLen = (frsData[8] >> 0) & 0xFFFF; + pData->qPoint3 = (frsData[8] >> 16) & 0xFFFF; + memcpy(pData->sensorSpecific, (uint8_t *)&frsData[9], pData->sensorSpecificLen); + vendorIdOffset = 9 + ((pData->sensorSpecificLen+3)/4); // 9 + one word for every 4 bytes of SS data + } + else if (pData->revision == 4) { + pData->qPoint1 = (frsData[7] >> 0) & 0xFFFF; + pData->qPoint2 = (frsData[7] >> 16) & 0xFFFF; + pData->sensorSpecificLen = (frsData[8] >> 0) & 0xFFFF; + pData->qPoint3 = (frsData[8] >> 16) & 0xFFFF; + pData->maxPeriod_uS = frsData[9]; + memcpy(pData->sensorSpecific, (uint8_t *)&frsData[10], pData->sensorSpecificLen); + vendorIdOffset = 10 + ((pData->sensorSpecificLen+3)/4); // 9 + one word for every 4 bytes of SS data + } + else { + // Unrecognized revision! + } + + // Copy vendor id + memcpy(pData->vendorId, (uint8_t *)&frsData[vendorIdOffset], + pData->vendorIdLen); +} + +// ------------------------------------------------------------------------ +// Set FRS. + +static int setFrsStart(sh2_t *pSh2) +{ + int rc = SH2_OK; + FrsWriteReq_t req; + + pSh2->opData.setFrs.offset = 0; + + // set up request to issue + memset(&req, 0, sizeof(req)); + req.reportId = SENSORHUB_FRS_WRITE_REQ; + req.reserved = 0; + req.length = pSh2->opData.setFrs.words; + req.frsType = pSh2->opData.getFrs.frsType; + + rc = sendCtrl(pSh2, (uint8_t *)&req, sizeof(req)); + + return rc; +} + +static void setFrsRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + FrsWriteResp_t *resp = (FrsWriteResp_t *)payload; + FrsWriteDataReq_t req; + uint8_t status; + bool sendMoreData = false; + bool completed = false; + int rc = SH2_OK; + + // skip this if it isn't the response we're looking for. + if (resp->reportId != SENSORHUB_FRS_WRITE_RESP) return; + + // Check for errors: Unrecognized FRS type, Busy, Out of range, Device error + status = resp->status; + switch(status) { + case FRS_WRITE_STATUS_RECEIVED: + case FRS_WRITE_STATUS_READY: + sendMoreData = true; + break; + case FRS_WRITE_STATUS_UNRECOGNIZED_FRS_TYPE: + case FRS_WRITE_STATUS_BUSY: + case FRS_WRITE_STATUS_FAILED: + case FRS_WRITE_STATUS_NOT_READY: + case FRS_WRITE_STATUS_INVALID_LENGTH: + case FRS_WRITE_STATUS_INVALID_RECORD: + case FRS_WRITE_STATUS_DEVICE_ERROR: + case FRS_WRITE_STATUS_READ_ONLY: + rc = SH2_ERR_HUB; + completed = true; + break; + case FRS_WRITE_STATUS_WRITE_COMPLETED: + // Successful completion + rc = SH2_OK; + completed = true; + break; + case FRS_WRITE_STATUS_RECORD_VALID: + // That's nice, keep waiting + break; + } + + // if we should send more data, do it. + if (sendMoreData && + (pSh2->opData.setFrs.offset < pSh2->opData.setFrs.words)) { + uint16_t offset = pSh2->opData.setFrs.offset; + + memset(&req, 0, sizeof(req)); + req.reportId = SENSORHUB_FRS_WRITE_DATA_REQ; + req.reserved = 0; + req.offset = offset; + req.data0 = pSh2->opData.setFrs.pData[offset++]; + if (offset < pSh2->opData.setFrs.words) { + req.data1 = pSh2->opData.setFrs.pData[offset++]; + } else { + req.data1 = 0; + } + pSh2->opData.setFrs.offset = offset; + + rc = sendCtrl(pSh2, (uint8_t *)&req, sizeof(req)); + } + + // if the operation is done or has to be aborted, complete it + if (completed) { + opCompleted(pSh2, rc); + } + + return; +} + +const sh2_Op_t setFrsOp = { + .start = setFrsStart, + .rx = setFrsRx, +}; + +// ------------------------------------------------------------------------ +// Support for sending commands + +static int sendCmd(sh2_t *pSh2, uint8_t cmd, uint8_t p[COMMAND_PARAMS]) +{ + int rc = SH2_OK; + CommandReq_t req; + + // Clear request structure + memset(&req, 0, sizeof(req)); + + // Create a command sequence number for this command + pSh2->lastCmdId = cmd; + pSh2->cmdSeq = pSh2->nextCmdSeq++; + + // set up request to issue + req.reportId = SENSORHUB_COMMAND_REQ; + req.seq = pSh2->cmdSeq; + req.command = cmd; + for (int n = 0; n < COMMAND_PARAMS; n++) { + req.p[n] = p[n]; + } + + rc = sendCtrl(pSh2, (uint8_t *)&req, sizeof(req)); + + return rc; +} + +// Send a command with 0 parameters +static int sendCmd0(sh2_t *pSh2, uint8_t cmd) +{ + uint8_t p[COMMAND_PARAMS]; + + memset(p, 0, COMMAND_PARAMS); + + return sendCmd(pSh2, cmd, p); +} + +// Send a command with 1 parameter +static int sendCmd1(sh2_t *pSh2, uint8_t cmd, uint8_t p0) +{ + uint8_t p[COMMAND_PARAMS]; + + memset(p, 0, COMMAND_PARAMS); + + p[0] = p0; + return sendCmd(pSh2, cmd, p); +} + +// Send a command with 2 parameters +static int sendCmd2(sh2_t *pSh2, uint8_t cmd, uint8_t p0, uint8_t p1) +{ + uint8_t p[COMMAND_PARAMS]; + + memset(p, 0, COMMAND_PARAMS); + + p[0] = p0; + p[1] = p1; + return sendCmd(pSh2, cmd, p); +} + +static bool wrongResponse(sh2_t *pSh2, CommandResp_t *resp) +{ + if (resp->reportId != SENSORHUB_COMMAND_RESP) return true; + if (resp->command != pSh2->lastCmdId) return true; + if (resp->commandSeq != pSh2->cmdSeq) return true; + + return false; +} + +// ------------------------------------------------------------------------ +// Get Errors + +static int getErrorsStart(sh2_t *pSh2) +{ + // Initialize state + pSh2->opData.getErrors.errsRead = 0; + + return sendCmd1(pSh2, SH2_CMD_ERRORS, pSh2->opData.getErrors.severity); +} + +static void getErrorsRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + CommandResp_t *resp = (CommandResp_t *)payload; + + // skip this if it isn't the right response + if (wrongResponse(pSh2, resp)) return; + + if (resp->r[2] == 255) { + // No error to report, operation is complete + *(pSh2->opData.getErrors.pNumErrors) = pSh2->opData.getErrors.errsRead; + opCompleted(pSh2, SH2_OK); + } else { + // Copy data for invoker. + unsigned int index = pSh2->opData.getErrors.errsRead; + if (index < *(pSh2->opData.getErrors.pNumErrors)) { + // We have room for this one. + pSh2->opData.getErrors.pErrors[index].severity = resp->r[0]; + pSh2->opData.getErrors.pErrors[index].sequence = resp->r[1]; + pSh2->opData.getErrors.pErrors[index].source = resp->r[2]; + pSh2->opData.getErrors.pErrors[index].error = resp->r[3]; + pSh2->opData.getErrors.pErrors[index].module = resp->r[4]; + pSh2->opData.getErrors.pErrors[index].code = resp->r[5]; + + pSh2->opData.getErrors.errsRead++; + } + } + + return; +} + +const sh2_Op_t getErrorsOp = { + .start = getErrorsStart, + .rx = getErrorsRx, +}; + +// ------------------------------------------------------------------------ +// Get Counts + +static int getCountsStart(sh2_t *pSh2) +{ + return sendCmd2(pSh2, SH2_CMD_COUNTS, SH2_COUNTS_GET_COUNTS, pSh2->opData.getCounts.sensorId); +} + +static void getCountsRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + CommandResp_t *resp = (CommandResp_t *)payload; + + if (wrongResponse(pSh2, resp)) return; + + // Store results + if (resp->respSeq == 0) { + pSh2->opData.getCounts.pCounts->offered = readu32(&resp->r[3]); + pSh2->opData.getCounts.pCounts->accepted = readu32(&resp->r[7]); + } + else { + pSh2->opData.getCounts.pCounts->on = readu32(&resp->r[3]); + pSh2->opData.getCounts.pCounts->attempted = readu32(&resp->r[7]); + } + + // Complete this operation if we've received last response + if (resp->respSeq == 1) { + opCompleted(pSh2, SH2_OK); + } + + return; +} + +const sh2_Op_t getCountsOp = { + .start = getCountsStart, + .rx = getCountsRx, +}; + +// ------------------------------------------------------------------------ +// Generic Send Command + +static int sendCmdStart(sh2_t *pSh2) +{ + int status = sendCmd(pSh2, pSh2->opData.sendCmd.req.command, + pSh2->opData.sendCmd.req.p); + + opCompleted(pSh2, status); + + return status; +} + +const sh2_Op_t sendCmdOp = { + .start = sendCmdStart, +}; + +// ------------------------------------------------------------------------ +// Reinit + +static int reinitStart(sh2_t *pSh2) +{ + int status = sendCmd1(pSh2, SH2_CMD_INITIALIZE, SH2_INIT_SYSTEM); + + return status; +} + +static void reinitRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + CommandResp_t *resp = (CommandResp_t *)payload; + + // Ignore message if it doesn't pertain to this operation + if (wrongResponse(pSh2, resp)) return; + + // Get return status + int status = SH2_OK; + if (resp->r[0] != 0) { + status = SH2_ERR_HUB; + } + + opCompleted(pSh2, status); +} + +const sh2_Op_t reinitOp = { + .start = reinitStart, + .rx = reinitRx, +}; + +// ------------------------------------------------------------------------ +// Save DCD Now + +static int saveDcdNowStart(sh2_t *pSh2) +{ + int status = sendCmd0(pSh2, SH2_CMD_DCD); + + return status; +} + +static void saveDcdNowRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + CommandResp_t *resp = (CommandResp_t *)payload; + + // Ignore message if it doesn't pertain to this operation + if (wrongResponse(pSh2, resp)) return; + + // Get return status + int status = SH2_OK; + if (resp->r[0] != 0) { + status = SH2_ERR_HUB; + } + + opCompleted(pSh2, status); +} + +const sh2_Op_t saveDcdNowOp = { + .start = saveDcdNowStart, + .rx = saveDcdNowRx, +}; + +// ------------------------------------------------------------------------ +// Get Osc Type + +static int getOscTypeStart(sh2_t *pSh2) +{ + return sendCmd0(pSh2, SH2_CMD_GET_OSC_TYPE); +} + +static void getOscTypeRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + CommandResp_t *resp = (CommandResp_t *)payload; + sh2_OscType_t *pOscType; + + // Ignore message if it doesn't pertain to this operation + if (wrongResponse(pSh2, resp)) return; + + // Read out data + pOscType = pSh2->opData.getOscType.pOscType; + *pOscType = (sh2_OscType_t)resp->r[0]; + + // Complete this operation + opCompleted(pSh2, SH2_OK); +} + +const sh2_Op_t getOscTypeOp = { + .start = getOscTypeStart, + .rx = getOscTypeRx, +}; + +// ------------------------------------------------------------------------ +// Set Cal Config + +static int setCalConfigStart(sh2_t *pSh2) +{ + uint8_t p[COMMAND_PARAMS]; + + // Clear p. (Importantly, set subcommand in p[3] to 0, CONFIGURE) + memset(p, 0, COMMAND_PARAMS); + + // Which cal processes to enable/disable + p[0] = (pSh2->opData.calConfig.sensors & SH2_CAL_ACCEL) ? 1 : 0; // accel cal + p[1] = (pSh2->opData.calConfig.sensors & SH2_CAL_GYRO) ? 1 : 0; // gyro cal + p[2] = (pSh2->opData.calConfig.sensors & SH2_CAL_MAG) ? 1 : 0; // mag cal + p[4] = (pSh2->opData.calConfig.sensors & SH2_CAL_PLANAR) ? 1 : 0; // planar cal + + return sendCmd(pSh2, SH2_CMD_ME_CAL, p); +} + +static void setCalConfigRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + CommandResp_t *resp = (CommandResp_t *)payload; + + // Ignore message if it doesn't pertain to this operation + if (wrongResponse(pSh2, resp)) return; + + // Read out data + int status = SH2_OK; + if (resp->r[0] != 0) { + status = SH2_ERR_HUB; + } + + // Complete this operation + opCompleted(pSh2, status); +} + +const sh2_Op_t setCalConfigOp = { + .start = setCalConfigStart, + .rx = setCalConfigRx, +}; + +// ------------------------------------------------------------------------ +// Get Cal Config + +static int getCalConfigStart(sh2_t *pSh2) +{ + uint8_t p[COMMAND_PARAMS]; + + // Clear p. (Importantly, set subcommand in p[3] to 0, CONFIGURE) + memset(p, 0, COMMAND_PARAMS); + + // Subcommand: Get ME Calibration + p[3] = 0x01; + + return sendCmd(pSh2, SH2_CMD_ME_CAL, p); +} + +static void getCalConfigRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + CommandResp_t *resp = (CommandResp_t *)payload; + + // Ignore message if it doesn't pertain to this operation + if (wrongResponse(pSh2, resp)) return; + + // Read out data + int status = SH2_OK; + if (resp->r[0] != 0) { + status = SH2_ERR_HUB; + } + else { + // Unload results into pSensors + uint8_t sensors = 0; + if (resp->r[1]) sensors |= SH2_CAL_ACCEL; + if (resp->r[2]) sensors |= SH2_CAL_GYRO; + if (resp->r[3]) sensors |= SH2_CAL_MAG; + if (resp->r[4]) sensors |= SH2_CAL_PLANAR; + *(pSh2->opData.getCalConfig.pSensors) = sensors; + } + + // Complete this operation + opCompleted(pSh2, status); +} + + +const sh2_Op_t getCalConfigOp = { + .start = getCalConfigStart, + .rx = getCalConfigRx, +}; + +// ------------------------------------------------------------------------ +// Force Flush + +static int forceFlushStart(sh2_t *pSh2) +{ + ForceFlushReq_t req; + + memset(&req, 0, sizeof(req)); + req.reportId = SENSORHUB_FORCE_SENSOR_FLUSH; + req.sensorId = pSh2->opData.forceFlush.sensorId; + + return sendCtrl(pSh2, (uint8_t *)&req, sizeof(req)); +} + +static void forceFlushRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + ForceFlushResp_t *resp = (ForceFlushResp_t *)payload; + + // Ignore message if it doesn't pertain to this operation + if (resp->reportId != SENSORHUB_FLUSH_COMPLETED) return; + if (resp->sensorId != pSh2->opData.forceFlush.sensorId) return; + + // Complete this operation + opCompleted(pSh2, SH2_OK); +} + +const sh2_Op_t forceFlushOp = { + .start = forceFlushStart, + .rx = forceFlushRx, +}; + +// ------------------------------------------------------------------------ +// Start Cal + +static int startCalStart(sh2_t *pSh2) +{ + uint8_t p[COMMAND_PARAMS]; + + // Clear p. (Importantly, set subcommand in p[3] to 0, CONFIGURE) + memset(p, 0, COMMAND_PARAMS); + + // Subcommand: Get ME Calibration + p[0] = SH2_CAL_START; + p[1] = pSh2->opData.startCal.interval_us & 0xFF; // LSB + p[2] = (pSh2->opData.startCal.interval_us >> 8) & 0xFF; + p[3] = (pSh2->opData.startCal.interval_us >> 16) & 0xFF; + p[4] = (pSh2->opData.startCal.interval_us >> 24) & 0xFF; // MSB + + return sendCmd(pSh2, SH2_CMD_CAL, p); +} + +static void startCalRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + CommandResp_t *resp = (CommandResp_t *)payload; + + // Ignore message if it doesn't pertain to this operation + if (wrongResponse(pSh2, resp)) return; + + // Complete this operation + opCompleted(pSh2, SH2_OK); +} + +const sh2_Op_t startCalOp = { + .start = startCalStart, + .rx = startCalRx, +}; + +// ------------------------------------------------------------------------ +// Start Cal + +static int finishCalStart(sh2_t *pSh2) +{ + return sendCmd1(pSh2, SH2_CMD_CAL, SH2_CAL_FINISH); +} + +static void finishCalRx(sh2_t *pSh2, const uint8_t *payload, uint16_t len) +{ + CommandResp_t *resp = (CommandResp_t *)payload; + + // Ignore message if it doesn't pertain to this operation + if (wrongResponse(pSh2, resp)) return; + + pSh2->opData.finishCal.status = (sh2_CalStatus_t)resp->r[1]; + + // Complete this operation + if (pSh2->opData.finishCal.status == SH2_CAL_SUCCESS) { + opCompleted(pSh2, SH2_OK); + } + else { + opCompleted(pSh2, SH2_ERR_HUB); + } +} + +const sh2_Op_t finishCalOp = { + .start = finishCalStart, + .rx = finishCalRx, +}; + + +// ------------------------------------------------------------------------ +// SHTP Event Callback + +static void shtpEventCallback(void *cookie, shtp_Event_t shtpEvent) { + sh2_t *pSh2 = &_sh2; + + sh2AsyncEvent.eventId = SH2_SHTP_EVENT; + sh2AsyncEvent.shtpEvent = shtpEvent; + if (pSh2->eventCallback) { + pSh2->eventCallback(pSh2->eventCookie, &sh2AsyncEvent); + } +} + +// ------------------------------------------------------------------------ +// Public functions + +/** + * @brief Open a session with a sensor hub. + * + * This function should be called before others in this API. + * An instance of an SH2 HAL should be passed in. + * This call will result in the open() function of the HAL being called. + * + * As part of the initialization process, a callback function is registered that will + * be invoked when the device generates certain events. (See sh2_AsyncEventId) + * + * @param pHal Pointer to an SH2 HAL instance, provided by the target system. + * @param eventCallback Will be called when events, such as reset complete, occur. + * @param eventCookie Will be passed to eventCallback. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_open(sh2_Hal_t *pHal, + sh2_EventCallback_t *eventCallback, void *eventCookie) +{ + sh2_t *pSh2 = &_sh2; + + // Validate parameters + if (pHal == 0) return SH2_ERR_BAD_PARAM; + + // Clear everything in sh2 structure. + memset(&_sh2, 0, sizeof(_sh2)); + + pSh2->resetComplete = false; // will go true after reset response from SH. + pSh2->controlChan = 0xFF; // An invalid value since we don't know yet. + + // Store reference to HAL for future use. + pSh2->pHal = pHal; + pSh2->eventCallback = eventCallback; + pSh2->eventCookie = eventCookie; + pSh2->sensorCallback = 0; + pSh2->sensorCookie = 0; + + // Open SHTP layer + pSh2->pShtp = shtp_open(pSh2->pHal); + if (pSh2->pShtp == 0) { + // Error opening SHTP + return SH2_ERR; + } + + // Register SHTP event callback + shtp_setEventCallback(pSh2->pShtp, shtpEventCallback, &_sh2); + + // Register with SHTP + // Register SH2 handlers + shtp_listenAdvert(pSh2->pShtp, GUID_SENSORHUB, sensorhubAdvertHdlr, &_sh2); + shtp_listenChan(pSh2->pShtp, GUID_SENSORHUB, "control", sensorhubControlHdlr, &_sh2); + shtp_listenChan(pSh2->pShtp, GUID_SENSORHUB, "inputNormal", sensorhubInputNormalHdlr, &_sh2); + shtp_listenChan(pSh2->pShtp, GUID_SENSORHUB, "inputWake", sensorhubInputWakeHdlr, &_sh2); + shtp_listenChan(pSh2->pShtp, GUID_SENSORHUB, "inputGyroRv", sensorhubInputGyroRvHdlr, &_sh2); + + // Register EXECUTABLE handlers + shtp_listenAdvert(pSh2->pShtp, GUID_EXECUTABLE, executableAdvertHdlr, &_sh2); + shtp_listenChan(pSh2->pShtp, GUID_EXECUTABLE, "device", executableDeviceHdlr, &_sh2); + + // Wait for reset notifications to arrive. + // The client can't talk to the sensor hub until that happens. + uint32_t start_us = pSh2->pHal->getTimeUs(pSh2->pHal); + uint32_t now_us = start_us; + while (((now_us - start_us) < ADVERT_TIMEOUT_US) && + (!pSh2->resetComplete)) + { + shtp_service(pSh2->pShtp); + now_us = pSh2->pHal->getTimeUs(pSh2->pHal); + } + + // No errors. + return SH2_OK; +} + +/** + * @brief Close a session with a sensor hub. + * + * This should be called at the end of a sensor hub session. + * The underlying SHTP and HAL instances will be closed. + */ +void sh2_close(void) +{ + sh2_t *pSh2 = &_sh2; + + shtp_close(pSh2->pShtp); + + // Clear everything in sh2 structure. + memset(pSh2, 0, sizeof(sh2_t)); +} + +/** + * @brief Service the SH2 device, reading any data that is available and dispatching callbacks. + * + * This function should be called periodically by the host system to service an open sensor hub. + */ +void sh2_service(void) +{ + sh2_t *pSh2 = &_sh2; + + shtp_service(pSh2->pShtp); +} + +/** + * @brief Register a function to receive sensor events. + * + * @param callback A function that will be called each time a sensor event is received. + * @param cookie A value that will be passed to the sensor callback function. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setSensorCallback(sh2_SensorCallback_t *callback, void *cookie) +{ + sh2_t *pSh2 = &_sh2; + + pSh2->sensorCallback = callback; + pSh2->sensorCookie = cookie; + + return SH2_OK; +} + +/** + * @brief Reset the sensor hub device by sending RESET (1) command on "device" channel. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_devReset(void) +{ + sh2_t *pSh2 = &_sh2; + + return sendExecutable(pSh2, EXECUTABLE_DEVICE_CMD_RESET); +} + +/** + * @brief Turn sensor hub on by sending RESET (1) command on "device" channel. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_devOn(void) +{ + sh2_t *pSh2 = &_sh2; + + return sendExecutable(pSh2, EXECUTABLE_DEVICE_CMD_ON); +} + +/** + * @brief Put sensor hub in sleep state by sending SLEEP (2) command on "device" channel. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_devSleep(void) +{ + sh2_t *pSh2 = &_sh2; + + return sendExecutable(pSh2, EXECUTABLE_DEVICE_CMD_SLEEP); +} + +/** + * @brief Get Product ID information from Sensorhub. + * + * @param prodIds Pointer to structure that will receive results. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getProdIds(sh2_ProductIds_t *prodIds) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + pSh2->opData.getProdIds.pProdIds = prodIds; + + return opProcess(pSh2, &getProdIdOp); +} + +/** + * @brief Get sensor configuration. + * + * @param sensorId Which sensor to query. + * @param config SensorConfig structure to store results. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getSensorConfig(sh2_SensorId_t sensorId, sh2_SensorConfig_t *pConfig) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + // Set up operation + pSh2->opData.getSensorConfig.sensorId = sensorId; + pSh2->opData.getSensorConfig.pConfig = pConfig; + + return opProcess(pSh2, &getSensorConfigOp); +} + +/** + * @brief Set sensor configuration. (e.g enable a sensor at a particular rate.) + * + * @param sensorId Which sensor to configure. + * @param pConfig Pointer to structure holding sensor configuration. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setSensorConfig(sh2_SensorId_t sensorId, const sh2_SensorConfig_t *pConfig) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + // Set up operation + pSh2->opData.setSensorConfig.sensorId = sensorId; + pSh2->opData.setSensorConfig.pConfig = pConfig; + + return opProcess(pSh2, &setSensorConfigOp); +} + +/** + * @brief Get metadata related to a sensor. + * + * @param sensorId Which sensor to query. + * @param pData Pointer to structure to receive the results. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getMetadata(sh2_SensorId_t sensorId, sh2_SensorMetadata_t *pData) +{ + sh2_t *pSh2 = &_sh2; + + // pData must be non-null + if (pData == 0) return SH2_ERR_BAD_PARAM; + + // Convert sensorId to metadata recordId + int i; + for (i = 0; i < ARRAY_LEN(sensorToRecordMap); i++) { + if (sensorToRecordMap[i].sensorId == sensorId) { + break; + } + } + if (i >= ARRAY_LEN(sensorToRecordMap)) { + // no match was found + return SH2_ERR_BAD_PARAM; + } + uint16_t recordId = sensorToRecordMap[i].recordId; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + // Set up an FRS read operation + pSh2->opData.getFrs.frsType = recordId; + pSh2->opData.getFrs.pData = pSh2->frsData; + pSh2->frsDataLen = ARRAY_LEN(pSh2->frsData); + pSh2->opData.getFrs.pWords = &pSh2->frsDataLen; + + // Read an FRS record + int status = opProcess(pSh2, &getFrsOp); + + // Copy the results into pData + if (status == SH2_OK) { + stuffMetadata(pData, pSh2->frsData); + } + + return status; +} + +/** + * @brief Get an FRS record. + * + * @param recordId Which FRS Record to retrieve. + * @param pData pointer to buffer to receive the results + * @param[in] words Size of pData buffer, in 32-bit words. + * @param[out] words Number of 32-bit words retrieved. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getFrs(uint16_t recordId, uint32_t *pData, uint16_t *words) +{ + sh2_t *pSh2 = &_sh2; + + if ((pData == 0) || (words == 0)) { + return SH2_ERR_BAD_PARAM; + } + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + // Store params for this op + pSh2->opData.getFrs.frsType = recordId; + pSh2->opData.getFrs.pData = pData; + pSh2->opData.getFrs.pWords = words; + + return opProcess(pSh2, &getFrsOp); +} + +/** + * @brief Set an FRS record + * + * @param recordId Which FRS Record to set. + * @param pData pointer to buffer containing the new data. + * @param words number of 32-bit words to write. (0 to delete record.) + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setFrs(uint16_t recordId, uint32_t *pData, uint16_t words) +{ + sh2_t *pSh2 = &_sh2; + + if ((pData == 0) && (words != 0)) { + return SH2_ERR_BAD_PARAM; + } + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + pSh2->opData.setFrs.frsType = recordId; + pSh2->opData.setFrs.pData = pData; + pSh2->opData.setFrs.words = words; + + return opProcess(pSh2, &setFrsOp); +} + +/** + * @brief Get error counts. + * + * @param severity Only errors of this severity or greater are returned. + * @param pErrors Buffer to receive error codes. + * @param numErrors size of pErrors array + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getErrors(uint8_t severity, sh2_ErrorRecord_t *pErrors, uint16_t *numErrors) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + pSh2->opData.getErrors.severity = severity; + pSh2->opData.getErrors.pErrors = pErrors; + pSh2->opData.getErrors.pNumErrors = numErrors; + + return opProcess(pSh2, &getErrorsOp); +} + +/** + * @brief Read counters related to a sensor. + * + * @param sensorId Which sensor to operate on. + * @param pCounts Pointer to Counts structure that will receive data. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getCounts(sh2_SensorId_t sensorId, sh2_Counts_t *pCounts) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + pSh2->opData.getCounts.sensorId = sensorId; + pSh2->opData.getCounts.pCounts = pCounts; + + return opProcess(pSh2, &getCountsOp); +} + +/** + * @brief Clear counters related to a sensor. + * + * @param sensorId which sensor to operate on. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_clearCounts(sh2_SensorId_t sensorId) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + + pSh2->opData.sendCmd.req.command = SH2_CMD_COUNTS; + pSh2->opData.sendCmd.req.p[0] = SH2_COUNTS_CLEAR_COUNTS; + pSh2->opData.sendCmd.req.p[1] = sensorId; + + return opProcess(pSh2, &sendCmdOp); +} + +/** + * @brief Perform a tare operation on one or more axes. + * + * @param axes Bit mask specifying which axes should be tared. + * @param basis Which rotation vector to use as the basis for Tare adjustment. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setTareNow(uint8_t axes, // SH2_TARE_X | SH2_TARE_Y | SH2_TARE_Z + sh2_TareBasis_t basis) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + + pSh2->opData.sendCmd.req.command = SH2_CMD_TARE; + pSh2->opData.sendCmd.req.p[0] = SH2_TARE_TARE_NOW; + pSh2->opData.sendCmd.req.p[1] = axes; + pSh2->opData.sendCmd.req.p[2] = basis; + + return opProcess(pSh2, &sendCmdOp); +} + +/** + * @brief Clears the previously applied tare operation. + * + * @return SH2_OK \n"); + */ +int sh2_clearTare(void) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + + pSh2->opData.sendCmd.req.command = SH2_CMD_TARE; + pSh2->opData.sendCmd.req.p[0] = SH2_TARE_SET_REORIENTATION; + + return opProcess(pSh2, &sendCmdOp); +} + +/** + * @brief Persist the results of last tare operation to flash. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_persistTare(void) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + + pSh2->opData.sendCmd.req.command = SH2_CMD_TARE; + pSh2->opData.sendCmd.req.p[0] = SH2_TARE_PERSIST_TARE; + + return opProcess(pSh2, &sendCmdOp); +} + +/** + * @brief Set the current run-time sensor reorientation. (Set to zero to clear tare.) + * + * @param orientation Quaternion rotation vector to apply as new tare. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setReorientation(sh2_Quaternion_t *orientation) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + + pSh2->opData.sendCmd.req.command = SH2_CMD_TARE; + pSh2->opData.sendCmd.req.p[0] = SH2_TARE_SET_REORIENTATION; + + // save me a lot of typing and you a lot of reading + uint8_t *p = pSh2->opData.sendCmd.req.p; + + // Put new orientation in command parameters + writeu16(&p[1], toQ14(orientation->x)); + writeu16(&p[3], toQ14(orientation->y)); + writeu16(&p[5], toQ14(orientation->z)); + writeu16(&p[7], toQ14(orientation->w)); + + return opProcess(pSh2, &sendCmdOp); +} + +/** + * @brief Command the sensorhub to reset. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_reinitialize(void) +{ + sh2_t *pSh2 = &_sh2; + + return opProcess(pSh2, &reinitOp); +} + +/** + * @brief Save Dynamic Calibration Data to flash. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_saveDcdNow(void) +{ + sh2_t *pSh2 = &_sh2; + + return opProcess(pSh2, &saveDcdNowOp); +} + +/** + * @brief Get Oscillator type. + * + * @param pOscType pointer to data structure to receive results. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getOscType(sh2_OscType_t *pOscType) +{ + sh2_t *pSh2 = &_sh2; + + pSh2->opData.getOscType.pOscType = pOscType; + + return opProcess(pSh2, &getOscTypeOp); +} + +/** + * @brief Enable/Disable dynamic calibration for certain sensors + * + * @param sensors Bit mask to configure which sensors are affected. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setCalConfig(uint8_t sensors) +{ + sh2_t *pSh2 = &_sh2; + + pSh2->opData.calConfig.sensors = sensors; + + return opProcess(pSh2, &setCalConfigOp); +} + +/** + * @brief Get dynamic calibration configuration settings. + * + * @param pSensors pointer to Bit mask, set on return. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getCalConfig(uint8_t *pSensors) +{ + sh2_t *pSh2 = &_sh2; + + pSh2->opData.getCalConfig.pSensors = pSensors; + + return opProcess(pSh2, &getCalConfigOp); +} + +/** + * @brief Configure automatic saving of dynamic calibration data. + * + * @param enabled Enable or Disable DCD auto-save. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setDcdAutoSave(bool enabled) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + pSh2->opData.sendCmd.req.command = SH2_CMD_DCD_SAVE; + pSh2->opData.sendCmd.req.p[0] = enabled ? 0 : 1; + + return opProcess(pSh2, &sendCmdOp); +} + +/** + * @brief Immediately issue all buffered sensor reports from a given sensor. + * + * @param sensorId Which sensor reports to flush. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_flush(sh2_SensorId_t sensorId) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + pSh2->opData.forceFlush.sensorId = sensorId; + + return opProcess(pSh2, &forceFlushOp); +} + +/** + * @brief Command clear DCD in RAM, then reset sensor hub. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_clearDcdAndReset(void) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + pSh2->opData.sendCmd.req.command = SH2_CMD_CLEAR_DCD_AND_RESET; + + return opProcess(pSh2, &sendCmdOp); +} + +/** + * @brief Start simple self-calibration procedure. + * + * @parameter interval_us sensor report interval, uS. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_startCal(uint32_t interval_us) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + pSh2->opData.startCal.interval_us = interval_us; + + return opProcess(pSh2, &startCalOp); +} + +/** + * @brief Finish simple self-calibration procedure. + * + * @parameter status contains calibration status code on return. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_finishCal(sh2_CalStatus_t *status) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + return opProcess(pSh2, &finishCalOp); +} + +/** + * @brief send Interactive ZRO Request. + * + * @parameter intent Inform the sensor hub what sort of motion should be in progress. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setIZro(sh2_IZroMotionIntent_t intent) +{ + sh2_t *pSh2 = &_sh2; + + // clear opData + memset(&pSh2->opData, 0, sizeof(sh2_OpData_t)); + + // set up opData for iZRO request + pSh2->opData.sendCmd.req.command = SH2_CMD_INTERACTIVE_ZRO; + pSh2->opData.sendCmd.req.p[0] = intent; + + // Send command + return opProcess(pSh2, &sendCmdOp); +} diff --git a/SH2/sh2.h b/SH2/sh2.h new file mode 100644 index 0000000..ec556ed --- /dev/null +++ b/SH2/sh2.h @@ -0,0 +1,695 @@ +/* + * Copyright 2015-2018 Hillcrest Laboratories, Inc. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License and + * any applicable agreements you may have with Hillcrest Laboratories, Inc. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file sh2.h + * @author David Wheeler + * @date 22 Sept 2015 + * @brief API Definition for Hillcrest SH-2 Sensor Hub. + * + * The sh2 API provides an interface to the Hillcrest Labs sensor hub devices. + */ + +#ifndef SH2_H +#define SH2_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include +#include + +#include "sh2_hal.h" + +/*************************************************************************************** + * Public type definitions + ***************************************************************************************/ + +/** + * @brief Sensor Event + * + * See the SH-2 Reference Manual for more detail. + */ +#define SH2_MAX_SENSOR_EVENT_LEN (16) +typedef struct sh2_SensorEvent { + uint64_t timestamp_uS; + uint8_t len; + uint8_t reportId; + uint8_t report[SH2_MAX_SENSOR_EVENT_LEN]; +} sh2_SensorEvent_t; + +typedef void (sh2_SensorCallback_t)(void * cookie, sh2_SensorEvent_t *pEvent); + +/** + * @brief Product Id value + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_ProductId_s { + uint8_t resetCause; + uint8_t swVersionMajor; + uint8_t swVersionMinor; + uint32_t swPartNumber; + uint32_t swBuildNumber; + uint16_t swVersionPatch; + uint8_t reserved0; + uint8_t reserved1; +} sh2_ProductId_t; + +#define SH2_MAX_PROD_ID_ENTRIES (5) +typedef struct sh2_ProductIds_s { + sh2_ProductId_t entry[SH2_MAX_PROD_ID_ENTRIES]; + uint8_t numEntries; +} sh2_ProductIds_t; + +/** + * @brief List of sensor types supported by the hub + * + * See the SH-2 Reference Manual for more information on each type. + */ +enum sh2_SensorId_e { + SH2_RAW_ACCELEROMETER = 0x14, + SH2_ACCELEROMETER = 0x01, + SH2_LINEAR_ACCELERATION = 0x04, + SH2_GRAVITY = 0x06, + SH2_RAW_GYROSCOPE = 0x15, + SH2_GYROSCOPE_CALIBRATED = 0x02, + SH2_GYROSCOPE_UNCALIBRATED = 0x07, + SH2_RAW_MAGNETOMETER = 0x16, + SH2_MAGNETIC_FIELD_CALIBRATED = 0x03, + SH2_MAGNETIC_FIELD_UNCALIBRATED = 0x0f, + SH2_ROTATION_VECTOR = 0x05, + SH2_GAME_ROTATION_VECTOR = 0x08, + SH2_GEOMAGNETIC_ROTATION_VECTOR = 0x09, + SH2_PRESSURE = 0x0a, + SH2_AMBIENT_LIGHT = 0x0b, + SH2_HUMIDITY = 0x0c, + SH2_PROXIMITY = 0x0d, + SH2_TEMPERATURE = 0x0e, + SH2_RESERVED = 0x17, + SH2_TAP_DETECTOR = 0x10, + SH2_STEP_DETECTOR = 0x18, + SH2_STEP_COUNTER = 0x11, + SH2_SIGNIFICANT_MOTION = 0x12, + SH2_STABILITY_CLASSIFIER = 0x13, + SH2_SHAKE_DETECTOR = 0x19, + SH2_FLIP_DETECTOR = 0x1a, + SH2_PICKUP_DETECTOR = 0x1b, + SH2_STABILITY_DETECTOR = 0x1c, + SH2_PERSONAL_ACTIVITY_CLASSIFIER = 0x1e, + SH2_SLEEP_DETECTOR = 0x1f, + SH2_TILT_DETECTOR = 0x20, + SH2_POCKET_DETECTOR = 0x21, + SH2_CIRCLE_DETECTOR = 0x22, + SH2_HEART_RATE_MONITOR = 0x23, + SH2_ARVR_STABILIZED_RV = 0x28, + SH2_ARVR_STABILIZED_GRV = 0x29, + SH2_GYRO_INTEGRATED_RV = 0x2A, + SH2_IZRO_MOTION_REQUEST = 0x2B, + + // UPDATE to reflect greatest sensor id + SH2_MAX_SENSOR_ID = 0x2B, +}; +typedef uint8_t sh2_SensorId_t; + +/** + * @brief Sensor Configuration settings + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_SensorConfig { + /* Change sensitivity enabled */ + bool changeSensitivityEnabled; /**< @brief Enable reports on change */ + + /* Change sensitivity - true if relative; false if absolute */ + bool changeSensitivityRelative; /**< @brief Change reports relative (vs absolute) */ + + /* Wake-up enabled */ + bool wakeupEnabled; /**< @brief Wake host on event */ + + /* Always on enabled */ + bool alwaysOnEnabled; /**< @brief Sensor remains on in sleep state */ + /* 16-bit signed fixed point integer representing the value a + * sensor output must exceed in order to trigger another input + * report. A setting of 0 causes all reports to be sent. + */ + uint16_t changeSensitivity; /**< @brief Report-on-change threshold */ + + /* Interval in microseconds between asynchronous input reports. */ + uint32_t reportInterval_us; /**< @brief [uS] Report interval */ + + /* Reserved field, not used. */ + uint32_t batchInterval_us; /**< @brief [uS] Batch interval */ + + /* Meaning is sensor specific */ + uint32_t sensorSpecific; /**< @brief See SH-2 Reference Manual for details. */ +} sh2_SensorConfig_t; + +/** + * @brief Sensor Metadata Record + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_SensorMetadata { + uint8_t meVersion; /**< @brief Motion Engine Version */ + uint8_t mhVersion; /**< @brief Motion Hub Version */ + uint8_t shVersion; /**< @brief SensorHub Version */ + uint32_t range; /**< @brief Same units as sensor reports */ + uint32_t resolution; /**< @brief Same units as sensor reports */ + uint16_t revision; /**< @brief Metadata record format revision */ + uint16_t power_mA; /**< @brief [mA] Fixed point 16Q10 format */ + uint32_t minPeriod_uS; /**< @brief [uS] */ + uint32_t maxPeriod_uS; /**< @brief [uS] */ + uint32_t fifoReserved; /**< @brief (Unused) */ + uint32_t fifoMax; /**< @brief (Unused) */ + uint32_t batchBufferBytes; /**< @brief (Unused) */ + uint16_t qPoint1; /**< @brief q point for sensor values */ + uint16_t qPoint2; /**< @brief q point for accuracy or bias fields */ + uint16_t qPoint3; /**< @brief q point for sensor data change sensitivity */ + uint32_t vendorIdLen; /**< @brief [bytes] */ + char vendorId[48]; /**< @brief Vendor name and part number */ + uint32_t sensorSpecificLen; /**< @brief [bytes] */ + uint8_t sensorSpecific[48]; /**< @brief See SH-2 Reference Manual */ +} sh2_SensorMetadata_t; + +/** + * @brief SensorHub Error Record + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_ErrorRecord { + uint8_t severity; /**< @brief Error severity, 0: most severe. */ + uint8_t sequence; /**< @brief Sequence number (by severity) */ + uint8_t source; /**< @brief 1-MotionEngine, 2-MotionHub, 3-SensorHub, 4-Chip */ + uint8_t error; /**< @brief See SH-2 Reference Manual */ + uint8_t module; /**< @brief See SH-2 Reference Manual */ + uint8_t code; /**< @brief See SH-2 Reference Manual */ +} sh2_ErrorRecord_t; + +/** + * @brief SensorHub Counter Record + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_Counts { + uint32_t offered; /**< @brief [events] */ + uint32_t accepted; /**< @brief [events] */ + uint32_t on; /**< @brief [events] */ + uint32_t attempted; /**< @brief [events] */ +} sh2_Counts_t; + +/** + * @brief Values for specifying tare basis + * + * See the SH-2 Reference Manual for more detail. + */ +typedef enum sh2_TareBasis { + SH2_TARE_BASIS_ROTATION_VECTOR = 0, /**< @brief Use Rotation Vector */ + SH2_TARE_BASIS_GAMING_ROTATION_VECTOR = 1, /**< @brief Use Game Rotation Vector */ + SH2_TARE_BASIS_GEOMAGNETIC_ROTATION_VECTOR = 2, /**< @brief Use Geomagnetic R.V. */ +} sh2_TareBasis_t; + +/** + * @brief Bit Fields for specifying tare axes. + * + * See the SH-2 Reference Manual for more detail. + */ +typedef enum sh2_TareAxis { + SH2_TARE_X = 1, /**< @brief sh2_tareNow() axes bit field */ + SH2_TARE_Y = 2, /**< @brief sh2_tareNow() axes bit field */ + SH2_TARE_Z = 4, /**< @brief sh2_tareNow() axes bit field */ +} sh2_TareAxis_t; + +/** + * @brief Quaternion (double precision floating point representation.) + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_Quaternion { + double x; + double y; + double z; + double w; +} sh2_Quaternion_t; + +/** + * @brief Oscillator type: Internal or External + * + * See the SH-2 Reference Manual for more detail. + */ +typedef enum { + SH2_OSC_INTERNAL = 0, + SH2_OSC_EXT_CRYSTAL = 1, + SH2_OSC_EXT_CLOCK = 2, +} sh2_OscType_t; + +/** + * @brief Calibration result + * + * See the SH-2 Reference Manual, Finish Calibration Response. + */ +typedef enum { + SH2_CAL_SUCCESS = 0, + SH2_CAL_NO_ZRO, + SH2_CAL_NO_STATIONARY_DETECTION, + SH2_CAL_ROTATION_OUTSIDE_SPEC, + SH2_CAL_ZRO_OUTSIDE_SPEC, + SH2_CAL_ZGO_OUTSIDE_SPEC, + SH2_CAL_GYRO_GAIN_OUTSIDE_SPEC, + SH2_CAL_GYRO_PERIOD_OUTSIDE_SPEC, + SH2_CAL_GYRO_DROPS_OUTSIDE_SPEC, +} sh2_CalStatus_t; + +// FRS Record Ids +#define STATIC_CALIBRATION_AGM (0x7979) +#define NOMINAL_CALIBRATION (0x4D4D) +#define STATIC_CALIBRATION_SRA (0x8A8A) +#define NOMINAL_CALIBRATION_SRA (0x4E4E) +#define DYNAMIC_CALIBRATION (0x1F1F) +#define ME_POWER_MGMT (0xD3E2) +#define SYSTEM_ORIENTATION (0x2D3E) +#define ACCEL_ORIENTATION (0x2D41) +#define SCREEN_ACCEL_ORIENTATION (0x2D43) +#define GYROSCOPE_ORIENTATION (0x2D46) +#define MAGNETOMETER_ORIENTATION (0x2D4C) +#define ARVR_STABILIZATION_RV (0x3E2D) +#define ARVR_STABILIZATION_GRV (0x3E2E) +#define TAP_DETECT_CONFIG (0xC269) +#define SIG_MOTION_DETECT_CONFIG (0xC274) +#define SHAKE_DETECT_CONFIG (0x7D7D) +#define MAX_FUSION_PERIOD (0xD7D7) +#define SERIAL_NUMBER (0x4B4B) +#define ES_PRESSURE_CAL (0x39AF) +#define ES_TEMPERATURE_CAL (0x4D20) +#define ES_HUMIDITY_CAL (0x1AC9) +#define ES_AMBIENT_LIGHT_CAL (0x39B1) +#define ES_PROXIMITY_CAL (0x4DA2) +#define ALS_CAL (0xD401) +#define PROXIMITY_SENSOR_CAL (0xD402) +#define PICKUP_DETECTOR_CONFIG (0x1B2A) +#define FLIP_DETECTOR_CONFIG (0xFC94) +#define STABILITY_DETECTOR_CONFIG (0xED85) +#define ACTIVITY_TRACKER_CONFIG (0xED88) +#define SLEEP_DETECTOR_CONFIG (0xED87) +#define TILT_DETECTOR_CONFIG (0xED89) +#define POCKET_DETECTOR_CONFIG (0xEF27) +#define CIRCLE_DETECTOR_CONFIG (0xEE51) +#define USER_RECORD (0x74B4) +#define ME_TIME_SOURCE_SELECT (0xD403) +#define UART_FORMAT (0xA1A1) +#define GYRO_INTEGRATED_RV_CONFIG (0xA1A2) +#define FRS_ID_META_RAW_ACCELEROMETER (0xE301) +#define FRS_ID_META_ACCELEROMETER (0xE302) +#define FRS_ID_META_LINEAR_ACCELERATION (0xE303) +#define FRS_ID_META_GRAVITY (0xE304) +#define FRS_ID_META_RAW_GYROSCOPE (0xE305) +#define FRS_ID_META_GYROSCOPE_CALIBRATED (0xE306) +#define FRS_ID_META_GYROSCOPE_UNCALIBRATED (0xE307) +#define FRS_ID_META_RAW_MAGNETOMETER (0xE308) +#define FRS_ID_META_MAGNETIC_FIELD_CALIBRATED (0xE309) +#define FRS_ID_META_MAGNETIC_FIELD_UNCALIBRATED (0xE30A) +#define FRS_ID_META_ROTATION_VECTOR (0xE30B) +#define FRS_ID_META_GAME_ROTATION_VECTOR (0xE30C) +#define FRS_ID_META_GEOMAGNETIC_ROTATION_VECTOR (0xE30D) +#define FRS_ID_META_PRESSURE (0xE30E) +#define FRS_ID_META_AMBIENT_LIGHT (0xE30F) +#define FRS_ID_META_HUMIDITY (0xE310) +#define FRS_ID_META_PROXIMITY (0xE311) +#define FRS_ID_META_TEMPERATURE (0xE312) +#define FRS_ID_META_TAP_DETECTOR (0xE313) +#define FRS_ID_META_STEP_DETECTOR (0xE314) +#define FRS_ID_META_STEP_COUNTER (0xE315) +#define FRS_ID_META_SIGNIFICANT_MOTION (0xE316) +#define FRS_ID_META_STABILITY_CLASSIFIER (0xE317) +#define FRS_ID_META_SHAKE_DETECTOR (0xE318) +#define FRS_ID_META_FLIP_DETECTOR (0xE319) +#define FRS_ID_META_PICKUP_DETECTOR (0xE31A) +#define FRS_ID_META_STABILITY_DETECTOR (0xE31B) +#define FRS_ID_META_PERSONAL_ACTIVITY_CLASSIFIER (0xE31C) +#define FRS_ID_META_SLEEP_DETECTOR (0xE31D) +#define FRS_ID_META_TILT_DETECTOR (0xE31E) +#define FRS_ID_META_POCKET_DETECTOR (0xE31F) +#define FRS_ID_META_CIRCLE_DETECTOR (0xE320) +#define FRS_ID_META_HEART_RATE_MONITOR (0xE321) +#define FRS_ID_META_ARVR_STABILIZED_RV (0xE322) +#define FRS_ID_META_ARVR_STABILIZED_GRV (0xE323) +#define FRS_ID_META_GYRO_INTEGRATED_RV (0xE324) + +/** + * @brief Interactive ZRO Motion Intent + * + * See the SH-2 Reference Manual, 6.4.13 + */ +typedef enum { + SH2_IZRO_MI_UNKNOWN = 0, + SH2_IZRO_MI_STATIONARY_NO_VIBRATION, + SH2_IZRO_MI_STATIONARY_WITH_VIBRATION, + SH2_IZRO_MI_IN_MOTION, +} sh2_IZroMotionIntent_t; + +/** + * @brief Interactive ZRO Motion Intent + * + * See the SH-2 Reference Manual, 6.4.13 + */ +typedef enum { + SH2_IZRO_MR_NO_REQUEST = 0, + SH2_IZRO_MR_STAY_STATIONARY, + SH2_IZRO_MR_STATIONARY_NON_URGENT, + SH2_IZRO_MR_STATIONARY_URGENT, +} sh2_IZroMotionRequest_t; + + +/** +* @brief Asynchronous Event +* +* Represents reset events and other non-sensor events received from SH-2 sensor hub. +*/ + +enum sh2_AsyncEventId_e { + SH2_RESET, + SH2_SHTP_EVENT, + SH2_GET_FEATURE_RESP, +}; +typedef enum sh2_AsyncEventId_e sh2_AsyncEventId_t; + +enum sh2_ShtpEvent_e { + SH2_SHTP_TX_DISCARD = 0, + SH2_SHTP_SHORT_FRAGMENT = 1, + SH2_SHTP_TOO_LARGE_PAYLOADS = 2, + SH2_SHTP_BAD_RX_CHAN = 3, + SH2_SHTP_BAD_TX_CHAN = 4, +}; +typedef uint8_t sh2_ShtpEvent_t; + +typedef struct sh2_SensorConfigResp_e { + sh2_SensorId_t sensorId; + sh2_SensorConfig_t sensorConfig; +} sh2_SensorConfigResp_t; + +typedef struct sh2_AsyncEvent { + uint32_t eventId; + union { + sh2_ShtpEvent_t shtpEvent; + sh2_SensorConfigResp_t sh2SensorConfigResp; + }; +} sh2_AsyncEvent_t; + +typedef void (sh2_EventCallback_t)(void * cookie, sh2_AsyncEvent_t *pEvent); + + +/*************************************************************************************** + * Public API + **************************************************************************************/ + +/** + * @brief Open a session with a sensor hub. + * + * This function should be called before others in this API. + * An instance of an SH2 HAL should be passed in. + * This call will result in the open() function of the HAL being called. + * + * As part of the initialization process, a callback function is registered that will + * be invoked when the device generates certain events. (See sh2_AsyncEventId) + * + * @param pHal Pointer to an SH2 HAL instance, provided by the target system. + * @param eventCallback Will be called when events, such as reset complete, occur. + * @param eventCookie Will be passed to eventCallback. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_open(sh2_Hal_t *pHal, + sh2_EventCallback_t *eventCallback, void *eventCookie); + +/** + * @brief Close a session with a sensor hub. + * + * This should be called at the end of a sensor hub session. + * The underlying SHTP and HAL instances will be closed. + * + */ +void sh2_close(void); + +/** + * @brief Service the SH2 device, reading any data that is available and dispatching callbacks. + * + * This function should be called periodically by the host system to service an open sensor hub. + * + */ +void sh2_service(void); + +/** + * @brief Register a function to receive sensor events. + * + * @param callback A function that will be called each time a sensor event is received. + * @param cookie A value that will be passed to the sensor callback function. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setSensorCallback(sh2_SensorCallback_t *callback, void *cookie); + +/** + * @brief Reset the sensor hub device by sending RESET (1) command on "device" channel. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_devReset(void); + +/** + * @brief Turn sensor hub on by sending ON (2) command on "device" channel. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_devOn(void); + +/** + * @brief Put sensor hub in sleep state by sending SLEEP (3) command on "device" channel. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_devSleep(void); + +/** + * @brief Get Product ID information from Sensorhub. + * + * @param prodIds Pointer to structure that will receive results. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getProdIds(sh2_ProductIds_t *prodIds); + +/** + * @brief Get sensor configuration. + * + * @param sensorId Which sensor to query. + * @param config SensorConfig structure to store results. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getSensorConfig(sh2_SensorId_t sensorId, sh2_SensorConfig_t *config); + +/** + * @brief Set sensor configuration. (e.g enable a sensor at a particular rate.) + * + * @param sensorId Which sensor to configure. + * @param pConfig Pointer to structure holding sensor configuration. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setSensorConfig(sh2_SensorId_t sensorId, const sh2_SensorConfig_t *pConfig); + +/** + * @brief Get metadata related to a sensor. + * + * @param sensorId Which sensor to query. + * @param pData Pointer to structure to receive the results. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getMetadata(sh2_SensorId_t sensorId, sh2_SensorMetadata_t *pData); + +/** + * @brief Get an FRS record. + * + * @param recordId Which FRS Record to retrieve. + * @param pData pointer to buffer to receive the results + * @param[in] words Size of pData buffer, in 32-bit words. + * @param[out] words Number of 32-bit words retrieved. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getFrs(uint16_t recordId, uint32_t *pData, uint16_t *words); + +/** + * @brief Set an FRS record + * + * @param recordId Which FRS Record to set. + * @param pData pointer to buffer containing the new data. + * @param words number of 32-bit words to write. (0 to delete record.) + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setFrs(uint16_t recordId, uint32_t *pData, uint16_t words); + +/** + * @brief Get error counts. + * + * @param severity Only errors of this severity or greater are returned. + * @param pErrors Buffer to receive error codes. + * @param numErrors size of pErrors array + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getErrors(uint8_t severity, sh2_ErrorRecord_t *pErrors, uint16_t *numErrors); + +/** + * @brief Read counters related to a sensor. + * + * @param sensorId Which sensor to operate on. + * @param pCounts Pointer to Counts structure that will receive data. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getCounts(sh2_SensorId_t sensorId, sh2_Counts_t *pCounts); + +/** + * @brief Clear counters related to a sensor. + * + * @param sensorId which sensor to operate on. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_clearCounts(sh2_SensorId_t sensorId); + +/** + * @brief Perform a tare operation on one or more axes. + * + * @param axes Bit mask specifying which axes should be tared. + * @param basis Which rotation vector to use as the basis for Tare adjustment. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setTareNow(uint8_t axes, // SH2_TARE_X | SH2_TARE_Y | SH2_TARE_Z + sh2_TareBasis_t basis); + +/** + * @brief Clears the previously applied tare operation. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_clearTare(void); + +/** + * @brief Persist the results of last tare operation to flash. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_persistTare(void); + +/** + * @brief Set the current run-time sensor reorientation. (Set to zero to clear tare.) + * + * @param orientation Quaternion rotation vector to apply as new tare. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setReorientation(sh2_Quaternion_t *orientation); + +/** + * @brief Command the sensorhub to reset. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_reinitialize(void); + +/** + * @brief Save Dynamic Calibration Data to flash. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_saveDcdNow(void); + +/** + * @brief Get Oscillator type. + * + * @param pOscType pointer to data structure to receive results. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getOscType(sh2_OscType_t *pOscType); + +// Flags for sensors field of sh_calConfig +#define SH2_CAL_ACCEL (0x01) +#define SH2_CAL_GYRO (0x02) +#define SH2_CAL_MAG (0x04) +#define SH2_CAL_PLANAR (0x08) + +/** + * @brief Enable/Disable dynamic calibration for certain sensors + * + * @param sensors Bit mask to configure which sensors are affected. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setCalConfig(uint8_t sensors); + +/** + * @brief Get dynamic calibration configuration settings. + * + * @param pSensors pointer to Bit mask, set on return. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_getCalConfig(uint8_t *pSensors); + +/** + * @brief Configure automatic saving of dynamic calibration data. + * + * @param enabled Enable or Disable DCD auto-save. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setDcdAutoSave(bool enabled); + +/** + * @brief Immediately issue all buffered sensor reports from a given sensor. + * + * @param sensorId Which sensor reports to flush. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_flush(sh2_SensorId_t sensorId); + +/** + * @brief Command clear DCD in RAM, then reset sensor hub. + * + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_clearDcdAndReset(void); + +/** + * @brief Start simple self-calibration procedure. + * + * @parameter interval_us sensor report interval, uS. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_startCal(uint32_t interval_us); + +/** + * @brief Finish simple self-calibration procedure. + * + * @parameter status contains calibration status code on return. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_finishCal(sh2_CalStatus_t *status); + +/** + * @brief send Interactive ZRO Request. + * + * @parameter intent Inform the sensor hub what sort of motion should be in progress. + * @return SH2_OK (0), on success. Negative value from sh2_err.h on error. + */ +int sh2_setIZro(sh2_IZroMotionIntent_t intent); + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif diff --git a/SH2/sh2_SensorValue.c b/SH2/sh2_SensorValue.c new file mode 100644 index 0000000..c2aa2ec --- /dev/null +++ b/SH2/sh2_SensorValue.c @@ -0,0 +1,551 @@ +/* + * Copyright 2015-16 Hillcrest Laboratories, Inc. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License and + * any applicable agreements you may have with Hillcrest Laboratories, Inc. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* + * BNO080 Sensor Event decoding + */ + +#include "sh2_SensorValue.h" +#include "sh2_err.h" +#include "sh2_util.h" + +#define SCALE_Q(n) (1.0f / (1 << n)) + +const float scaleRadToDeg = 180.0 / 3.14159265358; + +// ------------------------------------------------------------------------ +// Forward declarations + +static int decodeRawAccelerometer(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeAccelerometer(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeLinearAcceleration(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeGravity(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeRawGyroscope(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeGyroscopeCalibrated(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeGyroscopeUncal(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeRawMagnetometer(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeMagneticFieldCalibrated(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeMagneticFieldUncal(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeRotationVector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeGameRotationVector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeGeomagneticRotationVector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodePressure(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeAmbientLight(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeHumidity(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeProximity(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeTemperature(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeReserved(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeTapDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeStepDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeStepCounter(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeSignificantMotion(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeStabilityClassifier(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeShakeDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeFlipDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodePickupDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeStabilityDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodePersonalActivityClassifier(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeSleepDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeTiltDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodePocketDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeCircleDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeHeartRateMonitor(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeArvrStabilizedRV(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeArvrStabilizedGRV(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeGyroIntegratedRV(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); +static int decodeIZroRequest(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); + +// ------------------------------------------------------------------------ +// Public API + +int sh2_decodeSensorEvent(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + // Fill out fields of *value based on *event, converting data from message representation + // to natural representation. + + int rc = SH2_OK; + + value->sensorId = event->reportId; + value->timestamp = event->timestamp_uS; + + if (value->sensorId != SH2_GYRO_INTEGRATED_RV) { + value->sequence = event->report[1]; + value->status = event->report[2] & 0x03; + } + else { + value->sequence = 0; + value->status = 0; + } + + // extract delay field (100uS units) + + + switch (value->sensorId) { + case SH2_RAW_ACCELEROMETER: + rc = decodeRawAccelerometer(value, event); + break; + case SH2_ACCELEROMETER: + rc = decodeAccelerometer(value, event); + break; + case SH2_LINEAR_ACCELERATION: + rc = decodeLinearAcceleration(value, event); + break; + case SH2_GRAVITY: + rc = decodeGravity(value, event); + break; + case SH2_RAW_GYROSCOPE: + rc = decodeRawGyroscope(value, event); + break; + case SH2_GYROSCOPE_CALIBRATED: + rc = decodeGyroscopeCalibrated(value, event); + break; + case SH2_GYROSCOPE_UNCALIBRATED: + rc = decodeGyroscopeUncal(value, event); + break; + case SH2_RAW_MAGNETOMETER: + rc = decodeRawMagnetometer(value, event); + break; + case SH2_MAGNETIC_FIELD_CALIBRATED: + rc = decodeMagneticFieldCalibrated(value, event); + break; + case SH2_MAGNETIC_FIELD_UNCALIBRATED: + rc = decodeMagneticFieldUncal(value, event); + break; + case SH2_ROTATION_VECTOR: + rc = decodeRotationVector(value, event); + break; + case SH2_GAME_ROTATION_VECTOR: + rc = decodeGameRotationVector(value, event); + break; + case SH2_GEOMAGNETIC_ROTATION_VECTOR: + rc = decodeGeomagneticRotationVector(value, event); + break; + case SH2_PRESSURE: + rc = decodePressure(value, event); + break; + case SH2_AMBIENT_LIGHT: + rc = decodeAmbientLight(value, event); + break; + case SH2_HUMIDITY: + rc = decodeHumidity(value, event); + break; + case SH2_PROXIMITY: + rc = decodeProximity(value, event); + break; + case SH2_TEMPERATURE: + rc = decodeTemperature(value, event); + break; + case SH2_RESERVED: + rc = decodeReserved(value, event); + break; + case SH2_TAP_DETECTOR: + rc = decodeTapDetector(value, event); + break; + case SH2_STEP_DETECTOR: + rc = decodeStepDetector(value, event); + break; + case SH2_STEP_COUNTER: + rc = decodeStepCounter(value, event); + break; + case SH2_SIGNIFICANT_MOTION: + rc = decodeSignificantMotion(value, event); + break; + case SH2_STABILITY_CLASSIFIER: + rc = decodeStabilityClassifier(value, event); + break; + case SH2_SHAKE_DETECTOR: + rc = decodeShakeDetector(value, event); + break; + case SH2_FLIP_DETECTOR: + rc = decodeFlipDetector(value, event); + break; + case SH2_PICKUP_DETECTOR: + rc = decodePickupDetector(value, event); + break; + case SH2_STABILITY_DETECTOR: + rc = decodeStabilityDetector(value, event); + break; + case SH2_PERSONAL_ACTIVITY_CLASSIFIER: + rc = decodePersonalActivityClassifier(value, event); + break; + case SH2_SLEEP_DETECTOR: + rc = decodeSleepDetector(value, event); + break; + case SH2_TILT_DETECTOR: + rc = decodeTiltDetector(value, event); + break; + case SH2_POCKET_DETECTOR: + rc = decodePocketDetector(value, event); + break; + case SH2_CIRCLE_DETECTOR: + rc = decodeCircleDetector(value, event); + break; + case SH2_HEART_RATE_MONITOR: + rc = decodeHeartRateMonitor(value, event); + break; + case SH2_ARVR_STABILIZED_RV: + rc = decodeArvrStabilizedRV(value, event); + break; + case SH2_ARVR_STABILIZED_GRV: + rc = decodeArvrStabilizedGRV(value, event); + break; + case SH2_GYRO_INTEGRATED_RV: + rc = decodeGyroIntegratedRV(value, event); + break; + case SH2_IZRO_MOTION_REQUEST: + rc = decodeIZroRequest(value, event); + break; + default: + // Unknown report id + rc = SH2_ERR; + break; + } + + return rc; +} + +// ------------------------------------------------------------------------ +// Private utility functions + +static int decodeRawAccelerometer(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.rawAccelerometer.x = read16(&event->report[4]); + value->un.rawAccelerometer.y = read16(&event->report[6]); + value->un.rawAccelerometer.z = read16(&event->report[8]); + value->un.rawAccelerometer.timestamp = read32(&event->report[12]); + + return SH2_OK; +} + +static int decodeAccelerometer(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.accelerometer.x = read16(&event->report[4]) * SCALE_Q(8); + value->un.accelerometer.y = read16(&event->report[6]) * SCALE_Q(8); + value->un.accelerometer.z = read16(&event->report[8]) * SCALE_Q(8); + + return SH2_OK; +} + +static int decodeLinearAcceleration(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.linearAcceleration.x = read16(&event->report[4]) * SCALE_Q(8); + value->un.linearAcceleration.y = read16(&event->report[6]) * SCALE_Q(8); + value->un.linearAcceleration.z = read16(&event->report[8]) * SCALE_Q(8); + + return SH2_OK; +} + +static int decodeGravity(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.gravity.x = read16(&event->report[4]) * SCALE_Q(8); + value->un.gravity.y = read16(&event->report[6]) * SCALE_Q(8); + value->un.gravity.z = read16(&event->report[8]) * SCALE_Q(8); + + return SH2_OK; +} + +static int decodeRawGyroscope(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.rawGyroscope.x = read16(&event->report[4]); + value->un.rawGyroscope.y = read16(&event->report[6]); + value->un.rawGyroscope.z = read16(&event->report[8]); + value->un.rawGyroscope.temperature = read16(&event->report[10]); + value->un.rawGyroscope.timestamp = read32(&event->report[12]); + + return SH2_OK; +} + +static int decodeGyroscopeCalibrated(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.gyroscope.x = read16(&event->report[4]) * SCALE_Q(9); + value->un.gyroscope.y = read16(&event->report[6]) * SCALE_Q(9); + value->un.gyroscope.z = read16(&event->report[8]) * SCALE_Q(9); + + return SH2_OK; +} + +static int decodeGyroscopeUncal(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.gyroscopeUncal.x = read16(&event->report[4]) * SCALE_Q(9); + value->un.gyroscopeUncal.y = read16(&event->report[6]) * SCALE_Q(9); + value->un.gyroscopeUncal.z = read16(&event->report[8]) * SCALE_Q(9); + + value->un.gyroscopeUncal.biasX = read16(&event->report[10]) * SCALE_Q(9); + value->un.gyroscopeUncal.biasY = read16(&event->report[12]) * SCALE_Q(9); + value->un.gyroscopeUncal.biasZ = read16(&event->report[14]) * SCALE_Q(9); + + return SH2_OK; +} + +static int decodeRawMagnetometer(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.rawMagnetometer.x = read16(&event->report[4]); + value->un.rawMagnetometer.y = read16(&event->report[6]); + value->un.rawMagnetometer.z = read16(&event->report[8]); + value->un.rawMagnetometer.timestamp = read32(&event->report[12]); + + return SH2_OK; +} + +static int decodeMagneticFieldCalibrated(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.magneticField.x = read16(&event->report[4]) * SCALE_Q(4); + value->un.magneticField.y = read16(&event->report[6]) * SCALE_Q(4); + value->un.magneticField.z = read16(&event->report[8]) * SCALE_Q(4); + + return SH2_OK; +} + +static int decodeMagneticFieldUncal(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.magneticFieldUncal.x = read16(&event->report[4]) * SCALE_Q(4); + value->un.magneticFieldUncal.y = read16(&event->report[6]) * SCALE_Q(4); + value->un.magneticFieldUncal.z = read16(&event->report[8]) * SCALE_Q(4); + + value->un.magneticFieldUncal.biasX = read16(&event->report[10]) * SCALE_Q(4); + value->un.magneticFieldUncal.biasY = read16(&event->report[12]) * SCALE_Q(4); + value->un.magneticFieldUncal.biasZ = read16(&event->report[14]) * SCALE_Q(4); + + return SH2_OK; +} + +static int decodeRotationVector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.rotationVector.i = read16(&event->report[4]) * SCALE_Q(14); + value->un.rotationVector.j = read16(&event->report[6]) * SCALE_Q(14); + value->un.rotationVector.k = read16(&event->report[8]) * SCALE_Q(14); + value->un.rotationVector.real = read16(&event->report[10]) * SCALE_Q(14); + value->un.rotationVector.accuracy = read16(&event->report[12]) * SCALE_Q(12); + + return SH2_OK; +} + +static int decodeGameRotationVector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.gameRotationVector.i = read16(&event->report[4]) * SCALE_Q(14); + value->un.gameRotationVector.j = read16(&event->report[6]) * SCALE_Q(14); + value->un.gameRotationVector.k = read16(&event->report[8]) * SCALE_Q(14); + value->un.gameRotationVector.real = read16(&event->report[10]) * SCALE_Q(14); + + return SH2_OK; +} + +static int decodeGeomagneticRotationVector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.geoMagRotationVector.i = read16(&event->report[4]) * SCALE_Q(14); + value->un.geoMagRotationVector.j = read16(&event->report[6]) * SCALE_Q(14); + value->un.geoMagRotationVector.k = read16(&event->report[8]) * SCALE_Q(14); + value->un.geoMagRotationVector.real = read16(&event->report[10]) * SCALE_Q(14); + value->un.geoMagRotationVector.accuracy = read16(&event->report[12]) * SCALE_Q(12); + + return SH2_OK; +} + +static int decodePressure(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.pressure.value = read32(&event->report[4]) * SCALE_Q(20); + + return SH2_OK; +} + +static int decodeAmbientLight(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.ambientLight.value = read32(&event->report[4]) * SCALE_Q(8); + + return SH2_OK; +} + +static int decodeHumidity(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.humidity.value = read16(&event->report[4]) * SCALE_Q(8); + + return SH2_OK; +} + +static int decodeProximity(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.proximity.value = read16(&event->report[4]) * SCALE_Q(4); + + return SH2_OK; +} + +static int decodeTemperature(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.temperature.value = read16(&event->report[4]) * SCALE_Q(7); + + return SH2_OK; +} + +static int decodeReserved(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.reserved.tbd = read16(&event->report[4]) * SCALE_Q(7); + + return SH2_OK; +} + +static int decodeTapDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.tapDetector.flags = event->report[4]; + + return SH2_OK; +} + +static int decodeStepDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.stepDetector.latency = readu32(&event->report[4]); + + return SH2_OK; +} + +static int decodeStepCounter(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.stepCounter.latency = readu32(&event->report[4]); + value->un.stepCounter.steps = readu32(&event->report[8]); + + return SH2_OK; +} + +static int decodeSignificantMotion(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.sigMotion.motion = readu16(&event->report[4]); + + return SH2_OK; +} + +static int decodeStabilityClassifier(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.stabilityClassifier.classification = event->report[4]; + + return SH2_OK; +} + +static int decodeShakeDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.shakeDetector.shake = readu16(&event->report[4]); + + return SH2_OK; +} + +static int decodeFlipDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.flipDetector.flip = readu16(&event->report[4]); + + return SH2_OK; +} + +static int decodePickupDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.pickupDetector.pickup = readu16(&event->report[4]); + + return SH2_OK; +} + +static int decodeStabilityDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.stabilityDetector.stability = readu16(&event->report[4]); + + return SH2_OK; +} + +static int decodePersonalActivityClassifier(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.personalActivityClassifier.page = event->report[4] & 0x7F; + value->un.personalActivityClassifier.lastPage = ((event->report[4] & 0x80) != 0); + value->un.personalActivityClassifier.mostLikelyState = event->report[5]; + for (int n = 0; n < 10; n++) { + value->un.personalActivityClassifier.confidence[n] = event->report[6+n]; + } + + return SH2_OK; +} + +static int decodeSleepDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.sleepDetector.sleepState = event->report[4]; + + return SH2_OK; +} + +static int decodeTiltDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.tiltDetector.tilt = readu16(&event->report[4]); + + return SH2_OK; +} + +static int decodePocketDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.pocketDetector.pocket = readu16(&event->report[4]); + + return SH2_OK; +} + +static int decodeCircleDetector(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.circleDetector.circle = readu16(&event->report[4]); + + return SH2_OK; +} + +static int decodeHeartRateMonitor(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.heartRateMonitor.heartRate = readu16(&event->report[4]); + + return SH2_OK; +} + +static int decodeArvrStabilizedRV(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.arvrStabilizedRV.i = read16(&event->report[4]) * SCALE_Q(14); + value->un.arvrStabilizedRV.j = read16(&event->report[6]) * SCALE_Q(14); + value->un.arvrStabilizedRV.k = read16(&event->report[8]) * SCALE_Q(14); + value->un.arvrStabilizedRV.real = read16(&event->report[10]) * SCALE_Q(14); + value->un.arvrStabilizedRV.accuracy = read16(&event->report[12]) * SCALE_Q(12); + + return SH2_OK; +} + +static int decodeArvrStabilizedGRV(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.arvrStabilizedGRV.i = read16(&event->report[4]) * SCALE_Q(14); + value->un.arvrStabilizedGRV.j = read16(&event->report[6]) * SCALE_Q(14); + value->un.arvrStabilizedGRV.k = read16(&event->report[8]) * SCALE_Q(14); + value->un.arvrStabilizedGRV.real = read16(&event->report[10]) * SCALE_Q(14); + + return SH2_OK; +} + +static int decodeGyroIntegratedRV(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.gyroIntegratedRV.i = read16(&event->report[0]) * SCALE_Q(14); + value->un.gyroIntegratedRV.j = read16(&event->report[2]) * SCALE_Q(14); + value->un.gyroIntegratedRV.k = read16(&event->report[4]) * SCALE_Q(14); + value->un.gyroIntegratedRV.real = read16(&event->report[6]) * SCALE_Q(14); + value->un.gyroIntegratedRV.angVelX = read16(&event->report[8]) * SCALE_Q(10); + value->un.gyroIntegratedRV.angVelY = read16(&event->report[10]) * SCALE_Q(10); + value->un.gyroIntegratedRV.angVelZ = read16(&event->report[12]) * SCALE_Q(10); + + return SH2_OK; +} + +static int decodeIZroRequest(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event) +{ + value->un.izroRequest.intent = (sh2_IZroMotionIntent_t)event->report[4]; + value->un.izroRequest.request = (sh2_IZroMotionRequest_t)event->report[5]; + + return SH2_OK; +} diff --git a/SH2/sh2_SensorValue.h b/SH2/sh2_SensorValue.h new file mode 100644 index 0000000..19a6105 --- /dev/null +++ b/SH2/sh2_SensorValue.h @@ -0,0 +1,511 @@ +/* + * Copyright 2015-16 Hillcrest Laboratories, Inc. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License and + * any applicable agreements you may have with Hillcrest Laboratories, Inc. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file sh2_SensorValue.h + * @author David Wheeler + * @date 10 Nov 2015 + * @brief Support for converting sensor events (messages) into natural data structures. + * + */ + +#ifndef SH2_SENSORVALUE_H +#define SH2_SENSORVALUE_H + +#ifdef __cplusplus +extern "C" { +#endif + +#include + +#include "sh2.h" + +/* Note on quaternion naming conventions: + * Quaternions are values with four real components that are usually + * interpreted as coefficients in the complex quantity, Q. + * + * As in, Q = W + Xi + Yj + Zk + * + * Where i, j and k represent the three imaginary dimensions. + * + * So W represents the Real components and X, Y and Z the Imaginary ones. + * + * In the Hillcrest datasheets and in this code, however, the four components + * are named real, i, j and k, to make it explicit which is which. If you + * need to translate these names into the "wxyz" or "xyzw" convention, then, the + * appropriate mapping is this: + * w = real + * x = i + * y = j + * z = k + */ + +/** + * @brief Raw Accelerometer + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_RawAccelerometer { + /* Units are ADC counts */ + int16_t x; /**< @brief [ADC counts] */ + int16_t y; /**< @brief [ADC counts] */ + int16_t z; /**< @brief [ADC counts] */ + + /* Microseconds */ + uint32_t timestamp; /**< @brief [uS] */ +} sh2_RawAccelerometer_t; + +/** + * @brief Accelerometer + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_Accelerometer { + float x; + float y; + float z; +} sh2_Accelerometer_t; + +/** + * @brief Raw gyroscope + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_RawGyroscope { + /* Units are ADC counts */ + int16_t x; /**< @brief [ADC Counts] */ + int16_t y; /**< @brief [ADC Counts] */ + int16_t z; /**< @brief [ADC Counts] */ + int16_t temperature; /**< @brief [ADC Counts] */ + + /* Microseconds */ + uint32_t timestamp; /**< @brief [uS] */ +} sh2_RawGyroscope_t; + +/** + * @brief Gyroscope + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_Gyroscope { + /* Units are rad/s */ + float x; + float y; + float z; +} sh2_Gyroscope_t; + +/** + * @brief Uncalibrated gyroscope + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_GyroscopeUncalibrated { + /* Units are rad/s */ + float x; /**< @brief [rad/s] */ + float y; /**< @brief [rad/s] */ + float z; /**< @brief [rad/s] */ + float biasX; /**< @brief [rad/s] */ + float biasY; /**< @brief [rad/s] */ + float biasZ; /**< @brief [rad/s] */ +} sh2_GyroscopeUncalibrated_t; + +/** + * @brief Raw Magnetometer + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_RawMagnetometer { + /* Units are ADC counts */ + int16_t x; /**< @brief [ADC Counts] */ + int16_t y; /**< @brief [ADC Counts] */ + int16_t z; /**< @brief [ADC Counts] */ + + /* Microseconds */ + uint32_t timestamp; /**< @brief [uS] */ +} sh2_RawMagnetometer_t; + +/** + * @brief Magnetic field + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_MagneticField { + /* Units are uTesla */ + float x; /**< @brief [uTesla] */ + float y; /**< @brief [uTesla] */ + float z; /**< @brief [uTesla] */ +} sh2_MagneticField_t; + +/** + * @brief Uncalibrated magnetic field + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_MagneticFieldUncalibrated { + /* Units are uTesla */ + float x; /**< @brief [uTesla] */ + float y; /**< @brief [uTesla] */ + float z; /**< @brief [uTesla] */ + float biasX; /**< @brief [uTesla] */ + float biasY; /**< @brief [uTesla] */ + float biasZ; /**< @brief [uTesla] */ +} sh2_MagneticFieldUncalibrated_t; + +/** + * @brief Rotation Vector with Accuracy + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_RotationVectorWAcc { + float i; /**< @brief Quaternion component i */ + float j; /**< @brief Quaternion component j */ + float k; /**< @brief Quaternion component k */ + float real; /**< @brief Quaternion component, real */ + float accuracy; /**< @brief Accuracy estimate [radians] */ +} sh2_RotationVectorWAcc_t; + +/** + * @brief Rotation Vector + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_RotationVector { + float i; /**< @brief Quaternion component i */ + float j; /**< @brief Quaternion component j */ + float k; /**< @brief Quaternion component k */ + float real; /**< @brief Quaternion component real */ +} sh2_RotationVector_t; + +/** + * @brief Atmospheric Pressure + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_Pressure { + float value; /**< @brief Atmospheric Pressure. [hectopascals] */ +} sh2_Pressure_t; + +/** + * @brief Ambient Light + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_AmbientLight { + float value; /**< @brief Ambient Light. [lux] */ +} sh2_AmbientLight_t; + +/** + * @brief Humidity + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_Humidity { + float value; /**< @brief Relative Humidity. [percent] */ +} sh2_Humidity_t; + +/** + * @brief Proximity + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_Proximity { + float value; /**< @brief Proximity. [cm] */ +} sh2_Proximity_t; + +/** + * @brief Temperature + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_Temperature { + float value; /**< @brief Temperature. [C] */ +} sh2_Temperature_t; + +/** + * @brief Reserved + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_Reserved { + float tbd; /**< @brief Reserved */ +} sh2_Reserved_t; + +/** + * @brief TapDetector + * + * See the SH-2 Reference Manual for more detail. + */ +#define TAPDET_X (1) +#define TAPDET_X_POS (2) +#define TAPDET_Y (4) +#define TAPDET_Y_POS (8) +#define TAPDET_Z (16) +#define TAPDET_Z_POS (32) +#define TAPDET_DOUBLE (64) +typedef struct sh2_TapDetector { + uint8_t flags; /**< @brief TapDetector. */ +} sh2_TapDetector_t; + +/** + * @brief StepDetector + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_StepDetector { + uint32_t latency; /**< @brief Step detect latency [uS]. */ +} sh2_StepDetector_t; + +/** + * @brief StepCounter + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_StepCounter { + uint32_t latency; /**< @brief Step counter latency [uS]. */ + uint16_t steps; /**< @brief Steps counted. */ +} sh2_StepCounter_t; + +/** + * @brief SigMotion + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_SigMotion { + uint16_t motion; +} sh2_SigMotion_t; + +/** + * @brief StabilityClassifier + * + * See the SH-2 Reference Manual for more detail. + */ +#define STABILITY_CLASSIFIER_UNKNOWN (0) +#define STABILITY_CLASSIFIER_ON_TABLE (1) +#define STABILITY_CLASSIFIER_STATIONARY (2) +#define STABILITY_CLASSIFIER_STABLE (3) +#define STABILITY_CLASSIFIER_MOTION (4) +typedef struct sh2_StabilityClassifier { + uint8_t classification; +} sh2_StabilityClassifier_t; + +/** + * @brief ShakeDetector + * + * See the SH-2 Reference Manual for more detail. + */ +#define SHAKE_X (1) +#define SHAKE_Y (2) +#define SHAKE_Z (4) +typedef struct sh2_ShakeDetector { + uint16_t shake; +} sh2_ShakeDetector_t; + +/** + * @brief flipDetector + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_FlipDetector { + uint16_t flip; +} sh2_FlipDetector_t; + +/** + * @brief pickupDetector + * + * See the SH-2 Reference Manual for more detail. + */ +#define PICKUP_LEVEL_TO_NOT_LEVEL (1) +#define PICKUP_STOP_WITHIN_REGION (2) +typedef struct sh2_PickupDetector { + uint16_t pickup; /**< flag field with bits defined above. */ +} sh2_PickupDetector_t; + +/** + * @brief stabilityDetector + * + * See the SH-2 Reference Manual for more detail. + */ +#define STABILITY_ENTERED (1) +#define STABILITY_EXITED (2) +typedef struct sh2_StabilityDetector { + uint16_t stability; /**< flag field with bits defined above. */ +} sh2_StabilityDetector_t; + +/** + * @brief Personal Activity Classifier + * + * See the SH-2 Reference Manual for more detail. + */ +#define PAC_UNKNOWN (0) +#define PAC_IN_VEHICLE (1) +#define PAC_ON_BICYCLE (2) +#define PAC_ON_FOOT (3) +#define PAC_STILL (4) +#define PAC_TILTING (5) +#define PAC_WALKING (6) +#define PAC_RUNNING (7) +typedef struct sh2_PersonalActivityClassifier { + uint8_t page; + bool lastPage; + uint8_t mostLikelyState; + uint8_t confidence[10]; +} sh2_PersonalActivityClassifier_t; + +/** + * @brief sleepDetector + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_SleepDetector { + uint8_t sleepState; +} sh2_SleepDetector_t; + +/** + * @brief tiltDetector + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_TiltDetector { + uint16_t tilt; +} sh2_TiltDetector_t; + +/** + * @brief pocketDetector + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_PocketDetector { + uint16_t pocket; +} sh2_PocketDetector_t; + +/** + * @brief circleDetector + * + * See the SH-2 Reference Manual for more detail. + */ +typedef struct sh2_CircleDetector { + uint16_t circle; +} sh2_CircleDetector_t; + +/** + * @brief heartRateMonitor + * + * See SH-2 Reference Manual for details. + */ +typedef struct sh2_HeartRateMonitor { + uint16_t heartRate; /**< heart rate in beats per minute. */ +} sh2_HeartRateMonitor_t; + +/** + * @brief Gyro Integrated Rotation Vector + * + * See SH-2 Reference Manual for details. + */ +typedef struct sh2_GyroIntegratedRV { + float i; /**< @brief Quaternion component i */ + float j; /**< @brief Quaternion component j */ + float k; /**< @brief Quaternion component k */ + float real; /**< @brief Quaternion component real */ + float angVelX; /**< @brief Angular velocity about x [rad/s] */ + float angVelY; /**< @brief Angular velocity about y [rad/s] */ + float angVelZ; /**< @brief Angular velocity about z [rad/s] */ +} sh2_GyroIntegratedRV_t; + +typedef struct sh2_IZroRequest { + sh2_IZroMotionIntent_t intent; + sh2_IZroMotionRequest_t request; +} sh2_IZroRequest_t; + +typedef struct sh2_SensorValue { + + /** Which sensor produced this event. */ + uint8_t sensorId; + + /** @brief 8-bit unsigned integer used to track reports. + * + * The sequence number increments once for each report sent. Gaps + * in the sequence numbers indicate missing or dropped reports. + */ + uint8_t sequence; + + /* Status of a sensor + * 0 - Unreliable + * 1 - Accuracy low + * 2 - Accuracy medium + * 3 - Accuracy high + */ + uint8_t status; /**< @brief bits 7-5: reserved, 4-2: exponent delay, 1-0: Accuracy */ + + uint64_t timestamp; /**< [uS] */ + + uint32_t delay; /**< @brief [uS] value is delay * 2^exponent (see status) */ + + /** @brief Sensor Data + * + * Use the structure based on the value of the sensor + * field. + */ + union { + sh2_RawAccelerometer_t rawAccelerometer; + sh2_Accelerometer_t accelerometer; + sh2_Accelerometer_t linearAcceleration; + sh2_Accelerometer_t gravity; + sh2_RawGyroscope_t rawGyroscope; + sh2_Gyroscope_t gyroscope; + sh2_GyroscopeUncalibrated_t gyroscopeUncal; + sh2_RawMagnetometer_t rawMagnetometer; + sh2_MagneticField_t magneticField; + sh2_MagneticFieldUncalibrated_t magneticFieldUncal; + sh2_RotationVectorWAcc_t rotationVector; + sh2_RotationVector_t gameRotationVector; + sh2_RotationVectorWAcc_t geoMagRotationVector; + sh2_Pressure_t pressure; + sh2_AmbientLight_t ambientLight; + sh2_Humidity_t humidity; + sh2_Proximity_t proximity; + sh2_Temperature_t temperature; + sh2_Reserved_t reserved; + sh2_TapDetector_t tapDetector; + sh2_StepDetector_t stepDetector; + sh2_StepCounter_t stepCounter; + sh2_SigMotion_t sigMotion; + sh2_StabilityClassifier_t stabilityClassifier; + sh2_ShakeDetector_t shakeDetector; + sh2_FlipDetector_t flipDetector; + sh2_PickupDetector_t pickupDetector; + sh2_StabilityDetector_t stabilityDetector; + sh2_PersonalActivityClassifier_t personalActivityClassifier; + sh2_SleepDetector_t sleepDetector; + sh2_TiltDetector_t tiltDetector; + sh2_PocketDetector_t pocketDetector; + sh2_CircleDetector_t circleDetector; + sh2_HeartRateMonitor_t heartRateMonitor; + sh2_RotationVectorWAcc_t arvrStabilizedRV; + sh2_RotationVector_t arvrStabilizedGRV; + sh2_GyroIntegratedRV_t gyroIntegratedRV; + sh2_IZroRequest_t izroRequest; + } un; +} sh2_SensorValue_t; + +int sh2_decodeSensorEvent(sh2_SensorValue_t *value, const sh2_SensorEvent_t *event); + + +#ifdef __cplusplus +} // extern "C" +#endif + +#endif diff --git a/SH2/sh2_err.h b/SH2/sh2_err.h new file mode 100644 index 0000000..f10ebad --- /dev/null +++ b/SH2/sh2_err.h @@ -0,0 +1,42 @@ +/* + * Copyright 2015-16 Hillcrest Laboratories, Inc. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License and + * any applicable agreements you may have with Hillcrest Laboratories, Inc. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/** + * @file sh2_err.h + * @author David Wheeler + * @date 22 May 2015 + * @brief Type definitions for Hillcrest SH-2 API. + * + * Struct and type definitions supporting the Hillcrest SH-2 SensorHub API. + * + */ + + +#ifndef SH2_ERR_H +#define SH2_ERR_H + + +#define SH2_OK (0) /**< Success */ +#define SH2_ERR (-1) /**< General Error */ +#define SH2_ERR_BAD_PARAM (-2) /**< Bad parameter to an API call */ +#define SH2_ERR_OP_IN_PROGRESS (-3) /**< Operation in progress */ +#define SH2_ERR_IO (-4) /**< Error communicating with hub */ +#define SH2_ERR_HUB (-5) /**< Error reported by hub */ +#define SH2_ERR_TIMEOUT (-6) /**< Operation timed out */ + + +#endif diff --git a/SH2/sh2_hal.h b/SH2/sh2_hal.h new file mode 100644 index 0000000..b1cd808 --- /dev/null +++ b/SH2/sh2_hal.h @@ -0,0 +1,106 @@ +/* + * Copyright 2018 Hillcrest Laboratories, Inc. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License and + * any applicable agreements you may have with Hillcrest Laboratories, Inc. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* + * SH2 HAL Interface for Non-RTOS Applications. + */ + +// Include guard +#ifndef SH2_HAL_H +#define SH2_HAL_H + +#include + +// SH2 Implementations generally have a max out transfer len of 256 +#define SH2_HAL_MAX_TRANSFER_OUT (256) +#define SH2_HAL_MAX_PAYLOAD_OUT (256) + +// Although some implementations adversize a max in transfer of 32K, +// in practice, the largest transfer performed is the advertisements +// which is 272 bytes at time of writing. +#define SH2_HAL_MAX_TRANSFER_IN (384) +#define SH2_HAL_MAX_PAYLOAD_IN (384) + +// This needs to be a power of 2, greater than max of the above. +#define SH2_HAL_DMA_SIZE (512) + +typedef struct sh2_Hal_s sh2_Hal_t; + +// The SH2 interface uses these functions to access the underlying +// communications device, so the system integrator will need to +// implement these. At system intialization time, an sh2_Hal_t +// structure should be initialized with pointers to all the hardware +// access layer functions. A pointer to this structure must then be +// passed to sh2_open() to initialize the SH2 interface. +// +// If the DFU (download firmware update) capability is needed, the +// example DFU code also uses this interface but each function has +// somewhat different requirements. So a separate instance of an +// sh2_Hal_t structure, pointing to different functions, is +// recommended for supporting DFU. + +struct sh2_Hal_s { + // This function initializes communications with the device. It + // can initialize any GPIO pins and peripheral devices used to + // interface with the sensor hub. + // It should also perform a reset cycle on the sensor hub to + // ensure communications start from a known state. + int (*open)(sh2_Hal_t *self); + + // This function completes communications with the sensor hub. + // It should put the device in reset then de-initialize any + // peripherals or hardware resources that were used. + void (*close)(sh2_Hal_t *self); + + // This function supports reading data from the sensor hub. + // It will be called frequently to sevice the device. + // + // If the HAL has received a full SHTP transfer, this function + // should load the data into pBuffer, set the timestamp to the + // time the interrupt was detected and return the non-zero length + // of data in this transfer. + // + // If the HAL has not recevied a full SHTP transfer, this function + // should return 0. + // + // Because this function is called regularly, it can be used to + // perform other housekeeping operations. (In the case of UART + // interfacing, bytes transmitted are staggered in time and this + // function can be used to keep the transmission flowing.) + int (*read)(sh2_Hal_t *self, uint8_t *pBuffer, unsigned len, uint32_t *t_us); + + // This function supports writing data to the sensor hub. + // It is called each time the application has a block of data to + // transfer to the device. + // + // If the device isn't ready to receive data this function can + // return 0 without performing the transmit function. + // + // If the transmission can be started, this function needs to + // copy the data from pBuffer and return the number of bytes + // accepted. It need not block. The actual transmission of + // the data can continue after this function returns. + int (*write)(sh2_Hal_t *self, uint8_t *pBuffer, unsigned len); + + // This function should return a 32-bit value representing a + // microsecond counter. The count may roll over after 2^32 + // microseconds. + uint32_t (*getTimeUs)(sh2_Hal_t *self); +}; + +// End of include guard +#endif diff --git a/SH2/sh2_util.c b/SH2/sh2_util.c new file mode 100644 index 0000000..ec62afe --- /dev/null +++ b/SH2/sh2_util.c @@ -0,0 +1,104 @@ +/* + * Copyright 2015-16 Hillcrest Laboratories, Inc. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License and + * any applicable agreements you may have with Hillcrest Laboratories, Inc. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* + * Simple Utility functions common to several SH2 files. + */ + +#include "sh2_util.h" + +uint8_t readu8(const uint8_t *p) +{ + uint8_t retval = p[0]; + return retval; +} + +void writeu8(uint8_t * p, uint8_t value) +{ + *p = (uint8_t)(value & 0xFF); +} + +uint16_t readu16(const uint8_t *p) +{ + uint16_t retval = p[0] | (p[1] << 8); + return retval; +} + +void writeu16(uint8_t * p, uint16_t value) +{ + *p++ = (uint8_t)(value & 0xFF); + value >>= 8; + *p = (uint8_t)(value & 0xFF); +} + +uint32_t readu32(const uint8_t *p) +{ + uint32_t retval = p[0] | (p[1] << 8) | (p[2] << 16) | (p[3] << 24); + return retval; +} + +void writeu32(uint8_t * p, uint32_t value) +{ + *p++ = (uint8_t)(value & 0xFF); + value >>= 8; + *p++ = (uint8_t)(value & 0xFF); + value >>= 8; + *p++ = (uint8_t)(value & 0xFF); + value >>= 8; + *p = (uint8_t)(value & 0xFF); +} + +int8_t read8(const uint8_t *p) +{ + int8_t retval = p[0]; + return retval; +} + +void write8(uint8_t * p, int8_t value) +{ + *p = (uint8_t)(value & 0xFF); +} + +int16_t read16(const uint8_t *p) +{ + int16_t retval = p[0] | (p[1] << 8); + return retval; +} + +void write16(uint8_t * p, int16_t value) +{ + *p++ = (uint8_t)(value & 0xFF); + value >>= 8; + *p = (uint8_t)(value & 0xFF); +} + +int32_t read32(const uint8_t *p) +{ + int32_t retval = p[0] | (p[1] << 8) | (p[2] << 16) | (p[3] << 24); + return retval; +} + +void write32(uint8_t * p, int32_t value) +{ + *p++ = (uint8_t)(value & 0xFF); + value >>= 8; + *p++ = (uint8_t)(value & 0xFF); + value >>= 8; + *p++ = (uint8_t)(value & 0xFF); + value >>= 8; + *p = (uint8_t)(value & 0xFF); +} diff --git a/SH2/sh2_util.h b/SH2/sh2_util.h new file mode 100644 index 0000000..6992a17 --- /dev/null +++ b/SH2/sh2_util.h @@ -0,0 +1,45 @@ +/* + * Copyright 2015-16 Hillcrest Laboratories, Inc. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License and + * any applicable agreements you may have with Hillcrest Laboratories, Inc. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* + * Simple Utility functions common to several SH2 files. + */ + +#ifndef SH2_UTIL_H +#define SH2_UTIL_H + +#include + +#ifndef ARRAY_LEN +#define ARRAY_LEN(a) (sizeof(a)/sizeof(a[0])) +#endif + +uint8_t readu8(const uint8_t * buffer); +void writeu8(uint8_t * buffer, uint8_t value); +uint16_t readu16(const uint8_t * buffer); +void writeu16(uint8_t * buffer, uint16_t value); +uint32_t readu32(const uint8_t * buffer); +void writeu32(uint8_t * buffer, uint32_t value); + +int8_t read8(const uint8_t * buffer); +void write8(uint8_t * buffer, int8_t value); +int16_t read16(const uint8_t * buffer); +void write16(uint8_t * buffer, int16_t value); +int32_t read32(const uint8_t * buffer); +void write32(uint8_t * buffer, int32_t value); + +#endif diff --git a/SH2/shtp.c b/SH2/shtp.c new file mode 100644 index 0000000..503b5eb --- /dev/null +++ b/SH2/shtp.c @@ -0,0 +1,819 @@ +/* + * Copyright 2015-18 Hillcrest Laboratories, Inc. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License and + * any applicable agreements you may have with Hillcrest Laboratories, Inc. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* + * Hillcrest Sensor Hub Transport Protocol (SHTP) API + */ + +#include "shtp.h" +#include "sh2_err.h" +#include "sh2_util.h" + +#include + +// ------------------------------------------------------------------------ +// Private types + +#define SH2_MAX_APPS (5) +#define SHTP_APP_NAME_LEN (32) +#define SH2_MAX_CHANS (8) +#define SHTP_CHAN_NAME_LEN (32) + +// Defined Globally Unique Identifiers +#define GUID_SHTP (0) + +// Command Channel commands and parameters +#define SHTP_CHAN_COMMAND (0) +#define CMD_ADVERTISE (0) +#define CMD_ADVERTISE_SHTP (0) +#define CMD_ADVERTISE_ALL (1) +#define RESP_ADVERTISE (0) + +#define SHTP_HDR_LEN (4) + +#define TAG_SHTP_VERSION 0x80 + +typedef struct shtp_App_s { + uint32_t guid; + char appName[SHTP_APP_NAME_LEN]; +} shtp_App_t; + +typedef struct shtp_AppListener_s { + uint16_t guid; + shtp_AdvertCallback_t *callback; + void *cookie; +} shtp_AppListener_t; + +typedef struct shtp_ChanListener_s { + uint16_t guid; + char chanName[SHTP_CHAN_NAME_LEN]; + shtp_Callback_t *callback; + void *cookie; +} shtp_ChanListener_t; + +typedef struct shtp_Channel_s { + uint8_t nextOutSeq; + uint8_t nextInSeq; + uint32_t guid; // app id + char chanName[SHTP_CHAN_NAME_LEN]; + bool wake; + shtp_Callback_t *callback; + void *cookie; +} shtp_Channel_t; + +typedef enum { + ADVERT_NEEDED, + ADVERT_REQUESTED, + ADVERT_IDLE, +} advert_phase_t; + +// Per-instance data for SHTP +typedef struct shtp_s { + // Associated SHTP HAL + // If 0, this indicates the SHTP instance is available for new opens + sh2_Hal_t *pHal; + + // Asynchronous Event callback and it's cookie + shtp_EventCallback_t *eventCallback; + void * eventCookie; + + // Data from adverts + char shtpVersion[8]; + uint16_t outMaxPayload; + uint16_t outMaxTransfer; + + // Transmit support + uint8_t outTransfer[SH2_HAL_MAX_TRANSFER_OUT]; + + // Receive support + uint16_t inMaxTransfer; + uint16_t inRemaining; + uint8_t inChan; + uint8_t inPayload[SH2_HAL_MAX_PAYLOAD_IN]; + uint16_t inCursor; + uint32_t inTimestamp; + uint8_t inTransfer[SH2_HAL_MAX_TRANSFER_IN]; + + // What stage of advertisement processing are we in. + advert_phase_t advertPhase; + + // Applications + shtp_App_t app[SH2_MAX_APPS]; + uint8_t nextApp; + + // Advert registrations + uint8_t nextAppListener; + shtp_AppListener_t appListener[SH2_MAX_APPS]; + + // SHTP Channels + shtp_Channel_t chan[SH2_MAX_CHANS]; + + // Channel listeners + shtp_ChanListener_t chanListener[SH2_MAX_CHANS]; + uint8_t nextChanListener; + + // Stats + uint32_t txDiscards; + uint32_t shortFragments; + uint32_t tooLargePayloads; + uint32_t badRxChan; + uint32_t badTxChan; + +} shtp_t; + + +// ------------------------------------------------------------------------ +// Private data + +// Advertisement request +static const uint8_t advertise[] = { + CMD_ADVERTISE, + CMD_ADVERTISE_ALL +}; + +#define MAX_INSTANCES (1) +static shtp_t instances[MAX_INSTANCES]; + +static bool shtp_initialized = false; + +// ------------------------------------------------------------------------ +// Private functions + +static void shtp_init(void) +{ + // clear instance memory. + // In particular, this clears the pHal pointers which are used + // to determine if an instance is open and in-use. + memset(instances, 0, sizeof(instances)); + + // Set the initialized flag so this doesn't happen again. + shtp_initialized = true; +} + +static shtp_t *getInstance(void) +{ + for (int n = 0; n < MAX_INSTANCES; n++) { + if (instances[n].pHal == 0) { + // This instance is free + return &instances[n]; + } + } + + // Can't give an instance, none are free + return 0; +} + +// Register a listener for an app (advertisement listener) +static void addAdvertListener(shtp_t *pShtp, uint16_t guid, + shtp_AdvertCallback_t *callback, void * cookie) +{ + shtp_AppListener_t *pAppListener = 0; + + // Bail out if no space for more apps + if (pShtp->nextAppListener >= SH2_MAX_APPS) return; + + // Register this app + pAppListener = &pShtp->appListener[pShtp->nextAppListener]; + pShtp->nextAppListener++; + pAppListener->guid = guid; + pAppListener->callback = callback; + pAppListener->cookie = cookie; +} + +// Try to match registered listeners with their channels. +// This is performed every time the underlying Channel, App, Listener data structures are updated. +// As a result, channel number to callback association is fast when receiving packets +static void updateCallbacks(shtp_t *pShtp) +{ + // Figure out which callback is associated with each channel. + // Channel -> (GUID, Chan name). + // GUID -> App name. + // (App name, Chan name) -> Callback + + uint32_t guid; + const char * chanName = 0; + + for (int chanNo = 0; chanNo < SH2_MAX_CHANS; chanNo++) { + // Reset callback for this channel until we find the right one. + pShtp->chan[chanNo].callback = 0; + + if (pShtp->chan[chanNo].guid == 0xFFFFFFFF) { + // This channel entry not used. + continue; + } + + // Get GUID and Channel Name for this channel + guid = pShtp->chan[chanNo].guid; + chanName = pShtp->chan[chanNo].chanName; + + // Look for a listener registered with this guid, channel name + for (int listenerNo = 0; listenerNo < SH2_MAX_CHANS; listenerNo++) + { + if ((pShtp->chanListener[listenerNo].callback != 0) && + (pShtp->chanListener[listenerNo].guid == guid) && + (strcmp(chanName, pShtp->chanListener[listenerNo].chanName) == 0)) + { + + // This listener is the one for this channel + pShtp->chan[chanNo].callback = pShtp->chanListener[listenerNo].callback; + pShtp->chan[chanNo].cookie = pShtp->chanListener[listenerNo].cookie; + break; + } + } + } +} + +// Register a new channel listener +static int addChanListener(shtp_t *pShtp, + uint16_t guid, const char * chanName, + shtp_Callback_t *callback, void *cookie) +{ + shtp_ChanListener_t *pListener = 0; + + // Bail out if there are too many listeners registered + if (pShtp->nextChanListener >= SH2_MAX_CHANS) return SH2_ERR; + + // Register channel listener + pListener = &pShtp->chanListener[pShtp->nextChanListener]; + pShtp->nextChanListener++; + pListener->guid = guid; + strcpy(pListener->chanName, chanName); + pListener->callback = callback; + pListener->cookie = cookie; + + // re-evaluate channel callbacks + updateCallbacks(pShtp); + + return SH2_OK; +} + +static inline uint16_t min_u16(uint16_t a, uint16_t b) +{ + if (a < b) { + return a; + } + else { + return b; + } +} + +// Send a cargo as a sequence of transports +static int txProcess(shtp_t *pShtp, uint8_t chan, const uint8_t* pData, uint32_t len) +{ + int status = SH2_OK; + + bool continuation = false; + uint16_t cursor = 0; + uint16_t remaining; + uint16_t transferLen; // length of transfer, minus the header + uint16_t lenField; + + cursor = 0; + remaining = len; + while (remaining > 0) { + // How much data (not header) can we send in next transfer + transferLen = min_u16(remaining, pShtp->outMaxTransfer-SHTP_HDR_LEN); + + // Length field will be transferLen + SHTP_HDR_LEN + lenField = transferLen + SHTP_HDR_LEN; + + // Put the header in the out buffer + pShtp->outTransfer[0] = lenField & 0xFF; + pShtp->outTransfer[1] = (lenField >> 8) & 0xFF; + if (continuation) { + pShtp->outTransfer[1] |= 0x80; + } + pShtp->outTransfer[2] = chan; + pShtp->outTransfer[3] = pShtp->chan[chan].nextOutSeq++; + + // Stage one tranfer in the out buffer + memcpy(pShtp->outTransfer+SHTP_HDR_LEN, pData+cursor, transferLen); + remaining -= transferLen; + cursor += transferLen; + + // Transmit (try repeatedly while HAL write returns 0) + status = pShtp->pHal->write(pShtp->pHal, pShtp->outTransfer, lenField); + while (status == 0) + { + shtp_service(pShtp); + status = pShtp->pHal->write(pShtp->pHal, pShtp->outTransfer, lenField); + } + + if (status < 0) + { + // Error, throw away this cargo + pShtp->txDiscards++; + return status; + } + + // For the rest of this transmission, packets are continuations. + continuation = true; + } + + return SH2_OK; +} + +// Callback for SHTP app-specific advertisement tags +static void shtpAdvertHdlr(void *cookie, uint8_t tag, uint8_t len, uint8_t *val) +{ + shtp_t *pShtp = (shtp_t *)cookie; + + switch (tag) { + case TAG_SHTP_VERSION: + if (strlen((const char *)val) < sizeof(pShtp->shtpVersion)) { + strcpy(pShtp->shtpVersion, (const char *)val); + } + break; + default: + break; + } +} + +// Add one to the set of known Apps +static void addApp(shtp_t *pShtp, uint32_t guid) +{ + shtp_App_t *pApp = 0; + + // Bail out if this GUID is already registered + for (int n = 0; n < pShtp->nextApp; n++) { + if (pShtp->app[n].guid == guid) return; + } + + // Bail out if no space for more apps + if (pShtp->nextApp >= SH2_MAX_APPS) return; + + // Register this app + pApp = &pShtp->app[pShtp->nextApp]; + pShtp->nextApp++; + pApp->guid = guid; + strcpy(pApp->appName, ""); + + // Re-evaluate channel callbacks + updateCallbacks(pShtp); +} + +static void setAppName(shtp_t *pShtp, uint32_t guid, const char * appName) +{ + shtp_App_t *pApp = 0; + + // Find the app entry with this GUID + for (unsigned n = 0; n < pShtp->nextApp; n++) { + if (pShtp->app[n].guid == guid) { + pApp = &pShtp->app[n]; + strcpy(pApp->appName, appName); + return; + } + } +} + +// Add one to the set of known channels +static void addChannel(shtp_t *pShtp, uint8_t chanNo, uint32_t guid, const char * chanName, bool wake) +{ + if (chanNo >= SH2_MAX_CHANS) return; + + shtp_Channel_t * pChan = &pShtp->chan[chanNo]; + + // Store channel definition + pChan->guid = guid; + strcpy(pChan->chanName, chanName); + pChan->wake = wake; + + // Init channel-associated data + pChan->nextOutSeq = 0; + pChan->nextInSeq = 0; + pChan->callback = 0; + pChan->cookie = 0; + + // Re-evaluate channel callbacks + updateCallbacks(pShtp); +} + +static void callAdvertHandler(shtp_t *pShtp, uint32_t guid, + uint8_t tag, uint8_t len, uint8_t *val) +{ + // Find listener for this app + for (int n = 0; n < SH2_MAX_APPS; n++) + { + if (pShtp->appListener[n].guid == guid) { + // Found matching App entry + if (pShtp->appListener[n].callback != 0) { + pShtp->appListener[n].callback(pShtp->appListener[n].cookie, tag, len, val); + return; + } + } + } +} + +static void processAdvertisement(shtp_t *pShtp, uint8_t *payload, uint16_t payloadLen) +{ + uint16_t x; + uint8_t tag; + uint8_t len; + uint8_t *val; + uint16_t cursor = 1; + uint32_t guid = 0; + char appName[SHTP_APP_NAME_LEN]; + char chanName[SHTP_CHAN_NAME_LEN]; + uint8_t chanNo = 0; + bool wake = false; + + strcpy(appName, ""); + strcpy(chanName, ""); + + pShtp->advertPhase = ADVERT_IDLE; + + while (cursor < payloadLen) { + tag = payload[cursor++]; + len = payload[cursor++]; + val = payload+cursor; + cursor += len; + + // Process tag + switch (tag) { + case TAG_NULL: + // Reserved value, not a valid tag. + break; + case TAG_GUID: + // A new GUID is being established so terminate advertisement process with earlier app, if any. + callAdvertHandler(pShtp, guid, TAG_NULL, 0, 0); + + guid = readu32(val); + addApp(pShtp, guid); + + strcpy(appName, ""); + strcpy(chanName, ""); + break; + case TAG_MAX_CARGO_PLUS_HEADER_WRITE: + x = readu16(val) - SHTP_HDR_LEN; + + if (x < SH2_HAL_MAX_PAYLOAD_OUT) { + pShtp->outMaxPayload = x; + } + break; + case TAG_MAX_CARGO_PLUS_HEADER_READ: + x = readu16(val) - SHTP_HDR_LEN; + // No need to store this! + break; + case TAG_MAX_TRANSFER_WRITE: + x = readu16(val) - SHTP_HDR_LEN; + if (x < SH2_HAL_MAX_TRANSFER_OUT) { + pShtp->outMaxTransfer = x; + } else { + pShtp->outMaxTransfer = SH2_HAL_MAX_TRANSFER_OUT; + } + break; + case TAG_MAX_TRANSFER_READ: + x = readu16(val) - SHTP_HDR_LEN; + if (x < SH2_HAL_MAX_TRANSFER_IN) { + pShtp->inMaxTransfer = x; + } + break; + case TAG_NORMAL_CHANNEL: + chanNo = readu8(val); + wake = false; + break; + case TAG_WAKE_CHANNEL: + chanNo = readu8(val); + wake = true; + break; + case TAG_APP_NAME: + strcpy(appName, (const char *)val); + setAppName(pShtp, guid, appName); + + break; + case TAG_CHANNEL_NAME: + strcpy(chanName, (const char *)val); + addChannel(pShtp, chanNo, guid, (const char *)val, wake); + + // Store channel metadata + if (chanNo < SH2_MAX_CHANS) { + pShtp->chan[chanNo].guid = guid; + strcpy(pShtp->chan[chanNo].chanName, chanName); + pShtp->chan[chanNo].wake = wake; + } + break; + case TAG_ADV_COUNT: + // Not yet supported. + break; + default: + // Nothing special needs to be done with this tag. + break; + } + + // Deliver a TLV entry to the app's handler + callAdvertHandler(pShtp, guid, tag, len, val); + } + + // terminate advertisement process with last app + callAdvertHandler(pShtp, guid, TAG_NULL, 0, 0); +} + +// Callback for SHTP command channel +static void shtpCmdListener(void *cookie, uint8_t *payload, uint16_t len, uint32_t timestamp) +{ + shtp_t *pShtp = (shtp_t *)cookie; + + if ((payload == 0) || (len == 0)) return; + + uint8_t response = payload[0]; + + switch (response) { + case RESP_ADVERTISE: + processAdvertisement(pShtp, payload, len); + break; + default: + // unknown response + break; + } +} + +static void rxAssemble(shtp_t *pShtp, uint8_t *in, uint16_t len, uint32_t t_us) +{ + uint16_t payloadLen; + bool continuation; + uint8_t chan = 0; + uint8_t seq = 0; + + // discard invalid short fragments + if (len < SHTP_HDR_LEN) { + pShtp->shortFragments++; + return; + } + + // Interpret header fields + payloadLen = (in[0] + (in[1] << 8)) & (~0x8000); + continuation = ((in[1] & 0x80) != 0); + chan = in[2]; + seq = in[3]; + + if (payloadLen < SHTP_HDR_LEN) { + pShtp->shortFragments++; + + if (pShtp->eventCallback) { + pShtp->eventCallback(pShtp->eventCookie, SHTP_SHORT_FRAGMENT); + } + return; + } + + if ((chan >= SH2_MAX_CHANS) || + (chan >= pShtp->nextChanListener)) { + // Invalid channel id. + pShtp->badRxChan++; + + if (pShtp->eventCallback) { + pShtp->eventCallback(pShtp->eventCookie, SHTP_BAD_RX_CHAN); + } + return; + } + + // Discard earlier assembly in progress if the received data doesn't match it. + if (pShtp->inRemaining) { + // Check this against previously received data. + if (!continuation || + (chan != pShtp->inChan) || + (seq != pShtp->chan[chan].nextInSeq)) { + // This fragment doesn't fit with previous one, discard earlier data + pShtp->inRemaining = 0; + } + } + + if (pShtp->inRemaining == 0) { + if (payloadLen > sizeof(pShtp->inPayload)) { + // Error: This payload won't fit! Discard it. + pShtp->tooLargePayloads++; + + if (pShtp->eventCallback) { + pShtp->eventCallback(pShtp->eventCookie, SHTP_TOO_LARGE_PAYLOADS); + } + return; + } + + // This represents a new payload + + // Store timestamp + pShtp->inTimestamp = t_us; + + // Start a new assembly. + pShtp->inCursor = 0; + pShtp->inChan = chan; + } + + // Append the new fragment to the payload under construction. + if (len > payloadLen) { + // Only use the valid portion of the transfer + len = payloadLen; + } + memcpy(pShtp->inPayload + pShtp->inCursor, in+SHTP_HDR_LEN, len-SHTP_HDR_LEN); + pShtp->inCursor += len-SHTP_HDR_LEN; + pShtp->inRemaining = payloadLen - len; + + // If whole payload received, deliver it to channel listener. + if (pShtp->inRemaining == 0) { + + // Call callback if there is one. + if (pShtp->chan[chan].callback != 0) { + pShtp->chan[chan].callback(pShtp->chan[chan].cookie, + pShtp->inPayload, pShtp->inCursor, + pShtp->inTimestamp); + } + } + + // Remember next sequence number we expect for this channel. + pShtp->chan[chan].nextInSeq = seq + 1; +} + +// ------------------------------------------------------------------------ +// Public functions + +// Takes HAL pointer, returns shtp ID for use in future calls. +// HAL will be opened by this call. +void *shtp_open(sh2_Hal_t *pHal) +{ + if (!shtp_initialized) { + // Perform one-time module initialization + shtp_init(); + } + + // Validate params + if (pHal == 0) { + // Error + return 0; + } + + // Find an available instance for this open + shtp_t *pShtp = getInstance(); + if (pShtp == 0) { + // No instances available, return error + return 0; + } + + // Clear the SHTP instance as a shortcut to initializing all fields + memset(pShtp, 0, sizeof(shtp_t)); + + // Store reference to the HAL + pShtp->pHal = pHal; + + // Clear the asynchronous event callback point + pShtp->eventCallback = 0; + pShtp->eventCookie = 0; + + // Initialize state vars (be prepared for adverts) + pShtp->outMaxPayload = SH2_HAL_MAX_PAYLOAD_OUT; + pShtp->outMaxTransfer = SH2_HAL_MAX_TRANSFER_OUT; + + // Establish SHTP App and command channel a priori + addApp(pShtp, GUID_SHTP); + addChannel(pShtp, 0, GUID_SHTP, "command", false); + + // Register SHTP advert listener and command channel listener + shtp_listenAdvert(pShtp, GUID_SHTP, shtpAdvertHdlr, pShtp); + shtp_listenChan(pShtp, GUID_SHTP, "command", shtpCmdListener, pShtp); + + // When we open the HAL, it resets the device and adverts are sent automatically. + // So we go to ADVERT_REQUESTED state. They are on the way. + pShtp->advertPhase = ADVERT_REQUESTED; + + // Open HAL + pHal->open(pHal); + + return pShtp; +} + +// Releases resources associated with this SHTP instance. +// HAL will not be closed. +void shtp_close(void *pInstance) +{ + shtp_t *pShtp = (shtp_t *)pInstance; + + pShtp->pHal->close(pShtp->pHal); + + // Clear pShtp + // (Resetting pShtp->pHal to 0, returns this instance to the free pool) + memset(pShtp, 0, sizeof(shtp_t)); +} + +// Register the pointer of the callback function for reporting asynchronous events +void shtp_setEventCallback(void *pInstance, + shtp_EventCallback_t * eventCallback, + void *eventCookie) { + shtp_t *pShtp = (shtp_t *)pInstance; + + pShtp->eventCallback = eventCallback; + pShtp->eventCookie = eventCookie; +} + +// Register a listener for an SHTP channel +int shtp_listenChan(void *pInstance, + uint16_t guid, const char * chan, + shtp_Callback_t *callback, void * cookie) +{ + shtp_t *pShtp = (shtp_t *)pInstance; + + // Balk if channel name isn't valid + if ((chan == 0) || (strlen(chan) == 0)) return SH2_ERR_BAD_PARAM; + + return addChanListener(pShtp, guid, chan, callback, cookie); +} + +// Register a listener for SHTP advertisements +int shtp_listenAdvert(void *pInstance, + uint16_t guid, + shtp_AdvertCallback_t *advertCallback, void * cookie) +{ + shtp_t *pShtp = (shtp_t *)pInstance; + + // Register the advert listener + addAdvertListener(pShtp, guid, advertCallback, cookie); + + // Arrange for a new set of advertisements, for this listener + if (pShtp->advertPhase == ADVERT_IDLE) { + pShtp->advertPhase = ADVERT_NEEDED; + } + + return SH2_OK; +} + +// Look up the channel number for a particular app, channel. +uint8_t shtp_chanNo(void *pInstance, + const char * appName, const char * chanName) +{ + shtp_t *pShtp = (shtp_t *)pInstance; + + int chan = 0; + uint32_t guid = 0xFFFFFFFF; + + // Determine GUID for this appname + for (int n = 0; n < SH2_MAX_APPS; n++) { + if (strcmp(pShtp->app[n].appName, appName) == 0) { + guid = pShtp->app[n].guid; + break; + } + } + if (guid == 0xFFFFFFFF) return -1; + + for (chan = 0; chan < SH2_MAX_CHANS; chan++) { + if ((strcmp(pShtp->chan[chan].chanName, chanName) == 0) && + pShtp->chan[chan].guid == guid) { + // Found match + return chan; + } + } + + // Not found + return 0xFF; +} + +// Send an SHTP payload on a particular channel +int shtp_send(void *pInstance, + uint8_t channel, const uint8_t *payload, uint16_t len) +{ + shtp_t *pShtp = (shtp_t *)pInstance; + int ret = SH2_OK; + + if (len > pShtp->outMaxPayload) { + return SH2_ERR_BAD_PARAM; + } + if (channel >= SH2_MAX_CHANS) { + pShtp->badTxChan++; + return SH2_ERR_BAD_PARAM; + } + + ret = txProcess(pShtp, channel, payload, len); + + return ret; +} + +// Check for received data and process it. +void shtp_service(void *pInstance) +{ + shtp_t *pShtp = (shtp_t *)pInstance; + uint32_t t_us = 0; + + if (pShtp->advertPhase == ADVERT_NEEDED) { + pShtp->advertPhase = ADVERT_REQUESTED; // do this before send, to avoid recursion. + int status = shtp_send(pShtp, SHTP_CHAN_COMMAND, advertise, sizeof(advertise)); + if (status != SH2_OK) { + // Oops, advert request failed. Go back to needing one. + pShtp->advertPhase = ADVERT_NEEDED; + } + } + + int len = pShtp->pHal->read(pShtp->pHal, pShtp->inTransfer, sizeof(pShtp->inTransfer), &t_us); + if (len) { + rxAssemble(pShtp, pShtp->inTransfer, len, t_us); + } +} diff --git a/SH2/shtp.h b/SH2/shtp.h new file mode 100644 index 0000000..4e5a10b --- /dev/null +++ b/SH2/shtp.h @@ -0,0 +1,92 @@ +/* + * Copyright 2015-18 Hillcrest Laboratories, Inc. + * + * Licensed under the Apache License, Version 2.0 (the "License"); + * you may not use this file except in compliance with the License and + * any applicable agreements you may have with Hillcrest Laboratories, Inc. + * You may obtain a copy of the License at + * + * http://www.apache.org/licenses/LICENSE-2.0 + * + * Unless required by applicable law or agreed to in writing, software + * distributed under the License is distributed on an "AS IS" BASIS, + * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied. + * See the License for the specific language governing permissions and + * limitations under the License. + */ + +/* + * Hillcrest Sensor Hub Transport Protocol (SHTP) API + */ + +#ifndef SHTP_H +#define SHTP_H + +#include +#include + +#include "sh2_hal.h" + +// Advertisement TLV tags +#define TAG_NULL 0 +#define TAG_GUID 1 +#define TAG_MAX_CARGO_PLUS_HEADER_WRITE 2 +#define TAG_MAX_CARGO_PLUS_HEADER_READ 3 +#define TAG_MAX_TRANSFER_WRITE 4 +#define TAG_MAX_TRANSFER_READ 5 +#define TAG_NORMAL_CHANNEL 6 +#define TAG_WAKE_CHANNEL 7 +#define TAG_APP_NAME 8 +#define TAG_CHANNEL_NAME 9 +#define TAG_ADV_COUNT 10 +#define TAG_APP_SPECIFIC 0x80 + +typedef enum shtp_Event_e { + SHTP_TX_DISCARD = 0, + SHTP_SHORT_FRAGMENT = 1, + SHTP_TOO_LARGE_PAYLOADS = 2, + SHTP_BAD_RX_CHAN = 3, + SHTP_BAD_TX_CHAN = 4, +} shtp_Event_t; + +typedef void shtp_Callback_t(void * cookie, uint8_t *payload, uint16_t len, uint32_t timestamp); +typedef void shtp_AdvertCallback_t(void * cookie, uint8_t tag, uint8_t len, uint8_t *value); +typedef void shtp_SendCallback_t(void *cookie); +typedef void shtp_EventCallback_t(void *cookie, shtp_Event_t shtpEvent); + +// Takes HAL pointer, returns shtp ID for use in future calls. +// HAL will be opened by this call. +void * shtp_open(sh2_Hal_t *pHal); + +// Releases resources associated with this SHTP instance. +// HAL will not be closed. +void shtp_close(void *pShtp); + +// Provide the point of the callback function for reporting SHTP asynchronous events +void shtp_setEventCallback(void *pInstance, + shtp_EventCallback_t * eventCallback, + void *eventCookie); + +// Register a listener for an SHTP channel +int shtp_listenChan(void *pShtp, + uint16_t guid, const char * chan, + shtp_Callback_t *callback, void * cookie); + +// Register a listener for SHTP advertisements +int shtp_listenAdvert(void *pShtp, + uint16_t guid, + shtp_AdvertCallback_t *advertCallback, void * cookie); + +// Look up the channel number for a particular app, channel. +uint8_t shtp_chanNo(void *pShtp, + const char * appName, const char * chanName); + +// Send an SHTP payload on a particular channel +int shtp_send(void *pShtp, + uint8_t channel, const uint8_t *payload, uint16_t len); + +// Check for received data and process it. +void shtp_service(void *pShtp); + +// #ifdef SHTP_H +#endif diff --git a/documentation/html/_b_n_o08x_8cpp.html b/documentation/html/_b_n_o08x_8cpp.html deleted file mode 100644 index 3aad18e..0000000 --- a/documentation/html/_b_n_o08x_8cpp.html +++ /dev/null @@ -1,163 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08x.cpp File Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
BNO08x.cpp File Reference
-
-
-
#include "BNO08x.hpp"
-#include "BNO08x_macros.hpp"
-
-Include dependency graph for BNO08x.cpp:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-
- - - - diff --git a/documentation/html/_b_n_o08x_8cpp__incl.map b/documentation/html/_b_n_o08x_8cpp__incl.map deleted file mode 100644 index f29bf43..0000000 --- a/documentation/html/_b_n_o08x_8cpp__incl.map +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_b_n_o08x_8cpp__incl.md5 b/documentation/html/_b_n_o08x_8cpp__incl.md5 deleted file mode 100644 index c1ed075..0000000 --- a/documentation/html/_b_n_o08x_8cpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -41f1e1af7ac203ebf5cacac2a846b9ce \ No newline at end of file diff --git a/documentation/html/_b_n_o08x_8cpp__incl.png b/documentation/html/_b_n_o08x_8cpp__incl.png deleted file mode 100644 index e330463..0000000 Binary files a/documentation/html/_b_n_o08x_8cpp__incl.png and /dev/null differ diff --git a/documentation/html/_b_n_o08x_8hpp.html b/documentation/html/_b_n_o08x_8hpp.html deleted file mode 100644 index 29659cb..0000000 --- a/documentation/html/_b_n_o08x_8hpp.html +++ /dev/null @@ -1,216 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08x.hpp File Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
- -
BNO08x.hpp File Reference
-
-
-
#include <inttypes.h>
-#include <math.h>
-#include <stdio.h>
-#include <cstring>
-#include <functional>
-#include <vector>
-#include <esp_log.h>
-#include <esp_rom_gpio.h>
-#include <esp_timer.h>
-#include <freertos/FreeRTOS.h>
-#include <freertos/task.h>
-#include <freertos/event_groups.h>
-#include <freertos/queue.h>
-#include <freertos/semphr.h>
-#include <rom/ets_sys.h>
-#include "BNO08x_global_types.hpp"
-
-Include dependency graph for BNO08x.hpp:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-This graph shows which files directly or indirectly include this file:
-
-
- - - - - - - - - - - - - - - - - -
-
-

Go to the source code of this file.

- - - - - - - - - - - - - - - - -

-Classes

class  BNO08x
 BNO08x IMU driver class. More...
 
struct  BNO08x::bno08x_rx_packet_t
 Holds data that is received over spi. More...
 
struct  BNO08x::bno08x_tx_packet_t
 Holds data that is sent over spi. More...
 
struct  BNO08x::bno08x_report_period_tracker_t
 
struct  BNO08x::bno08x_init_status_t
 Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup). More...
 
-

Detailed Description

-
Author
Myles Parfeniuk
-
-
- - - - diff --git a/documentation/html/_b_n_o08x_8hpp.js b/documentation/html/_b_n_o08x_8hpp.js deleted file mode 100644 index 69adc18..0000000 --- a/documentation/html/_b_n_o08x_8hpp.js +++ /dev/null @@ -1,8 +0,0 @@ -var _b_n_o08x_8hpp = -[ - [ "BNO08x", "class_b_n_o08x.html", "class_b_n_o08x" ], - [ "BNO08x::bno08x_rx_packet_t", "struct_b_n_o08x_1_1bno08x__rx__packet__t.html", "struct_b_n_o08x_1_1bno08x__rx__packet__t" ], - [ "BNO08x::bno08x_tx_packet_t", "struct_b_n_o08x_1_1bno08x__tx__packet__t.html", "struct_b_n_o08x_1_1bno08x__tx__packet__t" ], - [ "BNO08x::bno08x_report_period_tracker_t", "struct_b_n_o08x_1_1bno08x__report__period__tracker__t.html", "struct_b_n_o08x_1_1bno08x__report__period__tracker__t" ], - [ "BNO08x::bno08x_init_status_t", "struct_b_n_o08x_1_1bno08x__init__status__t.html", "struct_b_n_o08x_1_1bno08x__init__status__t" ] -]; \ No newline at end of file diff --git a/documentation/html/_b_n_o08x_8hpp__dep__incl.map b/documentation/html/_b_n_o08x_8hpp__dep__incl.map deleted file mode 100644 index b162012..0000000 --- a/documentation/html/_b_n_o08x_8hpp__dep__incl.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_b_n_o08x_8hpp__dep__incl.md5 b/documentation/html/_b_n_o08x_8hpp__dep__incl.md5 deleted file mode 100644 index a9895c1..0000000 --- a/documentation/html/_b_n_o08x_8hpp__dep__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -1c9e1c80262ef4583f7de7fae85142bc \ No newline at end of file diff --git a/documentation/html/_b_n_o08x_8hpp__dep__incl.png b/documentation/html/_b_n_o08x_8hpp__dep__incl.png deleted file mode 100644 index e5f87e0..0000000 Binary files a/documentation/html/_b_n_o08x_8hpp__dep__incl.png and /dev/null differ diff --git a/documentation/html/_b_n_o08x_8hpp__incl.map b/documentation/html/_b_n_o08x_8hpp__incl.map deleted file mode 100644 index 1f83973..0000000 --- a/documentation/html/_b_n_o08x_8hpp__incl.map +++ /dev/null @@ -1,41 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_b_n_o08x_8hpp__incl.md5 b/documentation/html/_b_n_o08x_8hpp__incl.md5 deleted file mode 100644 index 99349b0..0000000 --- a/documentation/html/_b_n_o08x_8hpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -1cc9ccb34167ce6e7a68060da21b207f \ No newline at end of file diff --git a/documentation/html/_b_n_o08x_8hpp__incl.png b/documentation/html/_b_n_o08x_8hpp__incl.png deleted file mode 100644 index 62bb237..0000000 Binary files a/documentation/html/_b_n_o08x_8hpp__incl.png and /dev/null differ diff --git a/documentation/html/_b_n_o08x_8hpp_source.html b/documentation/html/_b_n_o08x_8hpp_source.html deleted file mode 100644 index beb6643..0000000 --- a/documentation/html/_b_n_o08x_8hpp_source.html +++ /dev/null @@ -1,1090 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08x.hpp Source File - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
BNO08x.hpp
-
-
-Go to the documentation of this file.
1
-
5#pragma once
-
6// standard library includes
-
7#include <inttypes.h>
-
8#include <math.h>
-
9#include <stdio.h>
-
10#include <cstring>
-
11#include <functional>
-
12#include <vector>
-
13
-
14// esp-idf includes
-
15#include <esp_log.h>
-
16#include <esp_rom_gpio.h>
-
17#include <esp_timer.h>
-
18#include <freertos/FreeRTOS.h>
-
19#include <freertos/task.h>
-
20#include <freertos/event_groups.h>
-
21#include <freertos/queue.h>
-
22#include <freertos/semphr.h>
-
23#include <rom/ets_sys.h>
-
24
-
25// in-house includes
- -
27
-
-
33class BNO08x
-
34{
-
35 public:
- -
37 ~BNO08x();
-
38 bool initialize();
-
39
-
40 bool hard_reset();
-
41 bool soft_reset();
- -
43
-
44 bool mode_sleep();
-
45 bool mode_on();
-
46 float q_to_float(int16_t fixed_point_value, uint8_t q_point);
-
47
- -
49 void calibrate_all();
- -
51 void calibrate_gyro();
- - - - -
56 void end_calibration();
-
57 void save_calibration();
-
58
-
59 void enable_rotation_vector(uint32_t time_between_reports);
-
60 void enable_game_rotation_vector(uint32_t time_between_reports);
-
61 void enable_ARVR_stabilized_rotation_vector(uint32_t time_between_reports);
-
62 void enable_ARVR_stabilized_game_rotation_vector(uint32_t time_between_reports);
-
63 void enable_gyro_integrated_rotation_vector(uint32_t time_between_reports);
-
64 void enable_uncalibrated_gyro(uint32_t time_between_reports);
-
65 void enable_calibrated_gyro(uint32_t time_between_reports);
-
66 void enable_accelerometer(uint32_t time_between_reports);
-
67 void enable_linear_accelerometer(uint32_t time_between_reports);
-
68 void enable_gravity(uint32_t time_between_reports);
-
69 void enable_magnetometer(uint32_t time_between_reports);
-
70 void enable_tap_detector(uint32_t time_between_reports);
-
71 void enable_step_counter(uint32_t time_between_reports);
-
72 void enable_stability_classifier(uint32_t time_between_reports);
-
73 void enable_activity_classifier(uint32_t time_between_reports, BNO08xActivityEnable activities_to_enable, uint8_t (&activity_confidence_vals)[9]);
-
74 void enable_raw_mems_gyro(uint32_t time_between_reports);
-
75 void enable_raw_mems_accelerometer(uint32_t time_between_reports);
-
76 void enable_raw_mems_magnetometer(uint32_t time_between_reports);
-
77
- - - - - - - -
85 void disable_gravity();
- - - - - - - - - - -
96
-
97 void tare_now(uint8_t axis_sel = TARE_AXIS_ALL, uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR);
-
98 void save_tare();
-
99 void clear_tare();
-
100
-
101 bool data_available(bool ignore_no_reports_enabled = false);
-
102 void register_cb(std::function<void()> cb_fxn);
-
103
- -
105
-
106 uint32_t get_time_stamp();
-
107
-
108 void get_magf(float& x, float& y, float& z, BNO08xAccuracy& accuracy);
-
109 float get_magf_X();
-
110 float get_magf_Y();
-
111 float get_magf_Z();
- -
113
-
114 void get_gravity(float& x, float& y, float& z, BNO08xAccuracy& accuracy);
-
115 float get_gravity_X();
-
116 float get_gravity_Y();
-
117 float get_gravity_Z();
- -
119
-
120 float get_roll();
-
121 float get_pitch();
-
122 float get_yaw();
-
123
-
124 float get_roll_deg();
-
125 float get_pitch_deg();
-
126 float get_yaw_deg();
-
127
-
128 void get_quat(float& i, float& j, float& k, float& real, float& rad_accuracy, BNO08xAccuracy& accuracy);
-
129 float get_quat_I();
-
130 float get_quat_J();
-
131 float get_quat_K();
-
132 float get_quat_real();
- - -
135
-
136 void get_accel(float& x, float& y, float& z, BNO08xAccuracy& accuracy);
-
137 float get_accel_X();
-
138 float get_accel_Y();
-
139 float get_accel_Z();
- -
141
-
142 void get_linear_accel(float& x, float& y, float& z, BNO08xAccuracy& accuracy);
-
143 float get_linear_accel_X();
-
144 float get_linear_accel_Y();
-
145 float get_linear_accel_Z();
- -
147
-
148 void get_raw_mems_accel(uint16_t& x, uint16_t& y, uint16_t& z);
-
149 uint16_t get_raw_mems_accel_X();
-
150 uint16_t get_raw_mems_accel_Y();
-
151 uint16_t get_raw_mems_accel_Z();
-
152
-
153 void get_raw_mems_gyro(uint16_t& x, uint16_t& y, uint16_t& z);
-
154 uint16_t get_raw_mems_gyro_X();
-
155 uint16_t get_raw_mems_gyro_Y();
-
156 uint16_t get_raw_mems_gyro_Z();
-
157
-
158 void get_raw_mems_magf(uint16_t& x, uint16_t& y, uint16_t& z);
-
159 uint16_t get_raw_mems_magf_X();
-
160 uint16_t get_raw_mems_magf_Y();
-
161 uint16_t get_raw_mems_magf_Z();
-
162
-
163 void get_calibrated_gyro_velocity(float& x, float& y, float& z);
- - - -
167
-
168 void get_uncalibrated_gyro_velocity(float& x, float& y, float& z, float& bx, float& by, float& bz);
- - - - - - -
175
-
176 void get_integrated_gyro_velocity(float& x, float& y, float& z);
- - - -
180
-
181 uint8_t get_tap_detector();
-
182 uint16_t get_step_count();
- - -
185
-
186 // Metadata functions
-
187 int16_t get_Q1(uint16_t record_ID);
-
188 int16_t get_Q2(uint16_t record_ID);
-
189 int16_t get_Q3(uint16_t record_ID);
-
190 float get_resolution(uint16_t record_ID);
-
191 float get_range(uint16_t record_ID);
-
192 uint32_t FRS_read_word(uint16_t record_ID, uint8_t word_number);
-
193 bool FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size);
-
194 bool FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read);
-
195
-
196 // Record IDs from figure 29, page 29 reference manual
-
197 // These are used to read the metadata for each sensor type
-
198 static const constexpr uint16_t FRS_RECORD_ID_ACCELEROMETER =
-
199 0xE302U;
-
200 static const constexpr uint16_t FRS_RECORD_ID_GYROSCOPE_CALIBRATED =
-
201 0xE306U;
-
202 static const constexpr uint16_t FRS_RECORD_ID_MAGNETIC_FIELD_CALIBRATED =
-
203 0xE309U;
-
204 static const constexpr uint16_t FRS_RECORD_ID_ROTATION_VECTOR =
-
205 0xE30BU;
-
206
-
207 static const constexpr uint8_t TARE_AXIS_ALL = 0x07U;
-
208 static const constexpr uint8_t TARE_AXIS_Z = 0x04U;
-
209
-
210 // Which rotation vector to tare, BNO08x saves them seperately
-
211 static const constexpr uint8_t TARE_ROTATION_VECTOR = 0U;
-
212 static const constexpr uint8_t TARE_GAME_ROTATION_VECTOR = 1U;
-
213 static const constexpr uint8_t TARE_GEOMAGNETIC_ROTATION_VECTOR = 2U;
-
214 static const constexpr uint8_t TARE_GYRO_INTEGRATED_ROTATION_VECTOR = 3U;
-
215 static const constexpr uint8_t TARE_ARVR_STABILIZED_ROTATION_VECTOR = 4U;
-
216 static const constexpr uint8_t TARE_ARVR_STABILIZED_GAME_ROTATION_VECTOR = 5U;
-
217
-
218 static const constexpr int16_t ROTATION_VECTOR_Q1 = 14;
-
219 static const constexpr int16_t ROTATION_VECTOR_ACCURACY_Q1 = 12;
-
220 static const constexpr int16_t ACCELEROMETER_Q1 = 8;
-
221 static const constexpr int16_t LINEAR_ACCELEROMETER_Q1 = 8;
-
222 static const constexpr int16_t GYRO_Q1 = 9;
-
223 static const constexpr int16_t MAGNETOMETER_Q1 = 4;
-
224 static const constexpr int16_t ANGULAR_VELOCITY_Q1 = 10;
-
225 static const constexpr int16_t GRAVITY_Q1 = 8;
-
226
-
227 private:
- -
238
-
-
240 typedef struct bno08x_rx_packet_t
-
241 {
-
242 uint8_t header[4];
-
243 uint8_t body[300];
-
244 uint16_t length;
- -
-
246
-
-
248 typedef struct bno08x_tx_packet_t
-
249 {
-
250 uint8_t body[50];
-
251 uint16_t length;
- -
-
253
- -
259
-
-
261 typedef struct bno08x_init_status_t
-
262 {
- - - - -
267 uint8_t task_count;
- -
269 bool spi_task;
-
270 bool spi_bus;
- -
272
-
- -
274 : gpio_outputs(false)
-
275 , gpio_inputs(false)
-
276 , isr_service(false)
-
277 , isr_handler(false)
-
278 , task_count(0)
-
279 , data_proc_task(false)
-
280 , spi_task(false)
-
281 , spi_bus(false)
-
282 , spi_device(false)
-
283 {
-
284 }
-
- -
-
286
-
287 esp_err_t init_config_args();
-
288 esp_err_t init_gpio();
-
289 esp_err_t init_gpio_inputs();
-
290 esp_err_t init_gpio_outputs();
-
291 esp_err_t init_hint_isr();
-
292 esp_err_t init_spi();
-
293
-
294 esp_err_t deinit_gpio();
-
295 esp_err_t deinit_gpio_inputs();
-
296 esp_err_t deinit_gpio_outputs();
-
297 esp_err_t deinit_hint_isr();
-
298 esp_err_t deinit_spi();
-
299
-
300 bool wait_for_rx_done();
-
301 bool wait_for_tx_done();
-
302 bool wait_for_data();
-
303 esp_err_t receive_packet();
-
304 esp_err_t receive_packet_header(bno08x_rx_packet_t* packet);
-
305 esp_err_t receive_packet_body(bno08x_rx_packet_t* packet);
-
306 void send_packet(bno08x_tx_packet_t* packet);
-
307 void flush_rx_packets(uint8_t flush_count);
-
308 void enable_report(uint8_t report_ID, uint32_t time_between_reports, const EventBits_t report_evt_grp_bit, uint32_t special_config = 0);
-
309 void disable_report(uint8_t report_ID, const EventBits_t report_evt_grp_bit);
-
310 void queue_packet(uint8_t channel_number, uint8_t data_length, uint8_t* commands);
-
311 void queue_command(uint8_t command, uint8_t* commands);
-
312 void queue_feature_command(uint8_t report_ID, uint32_t time_between_reports, uint32_t specific_config = 0);
-
313 void queue_calibrate_command(uint8_t _to_calibrate);
-
314 void queue_tare_command(uint8_t command, uint8_t axis = TARE_AXIS_ALL, uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR);
- -
316
-
317 // functions to parse packets received from bno08x
-
318 uint16_t parse_packet(bno08x_rx_packet_t* packet, bool& notify_users);
- - - -
322 uint16_t parse_input_report(bno08x_rx_packet_t* packet);
-
323 void parse_input_report_data(bno08x_rx_packet_t* packet, uint16_t* data, uint16_t data_length);
- - -
326
-
327 // functions to update data returned to user
-
328 void update_accelerometer_data(uint16_t* data, uint8_t status);
-
329 void update_lin_accelerometer_data(uint16_t* data, uint8_t status);
-
330 void update_calibrated_gyro_data(uint16_t* data, uint8_t status);
-
331 void update_uncalibrated_gyro_data(uint16_t* data, uint8_t status);
-
332 void update_magf_data(uint16_t* data, uint8_t status);
-
333 void update_gravity_data(uint16_t* data, uint8_t status);
-
334 void update_rotation_vector_data(uint16_t* data, uint8_t status);
-
335 void update_step_counter_data(uint16_t* data);
-
336 void update_raw_accelerometer_data(uint16_t* data);
-
337 void update_raw_gyro_data(uint16_t* data);
-
338 void update_raw_magf_data(uint16_t* data);
- - - - - -
344
-
345 // for debug
-
346 void print_header(bno08x_rx_packet_t* packet);
-
347 void print_packet(bno08x_rx_packet_t* packet);
-
348 bool first_boot = true;
-
349
-
350 // spi task
-
351 TaskHandle_t spi_task_hdl;
-
352 static void spi_task_trampoline(void* arg);
-
353 void spi_task();
-
354
-
355 // data processing task
-
356 TaskHandle_t data_proc_task_hdl;
-
357 static void data_proc_task_trampoline(void* arg);
-
358 void data_proc_task();
-
359
-
360 // task control
-
361 SemaphoreHandle_t sem_kill_tasks;
-
362 esp_err_t launch_tasks();
-
363 esp_err_t kill_all_tasks();
-
364
-
365 void update_report_period_trackers(uint8_t report_ID, uint32_t new_period);
-
366 static uint8_t report_ID_to_report_period_tracker_idx(uint8_t report_ID);
-
367
-
368 EventGroupHandle_t
- -
370 EventGroupHandle_t evt_grp_report_en;
-
371 EventGroupHandle_t evt_grp_task_flow;
-
372
-
373 QueueHandle_t queue_rx_data;
-
374 QueueHandle_t queue_tx_data;
-
375 QueueHandle_t queue_frs_read_data;
-
376 QueueHandle_t queue_reset_reason;
-
377
-
378 std::vector<std::function<void()>> cb_list; // Vector for storing any call-back functions added with register_cb()
-
379
-
380 uint32_t meta_data[9];
-
381
- -
383 spi_bus_config_t bus_config{};
-
384 spi_device_interface_config_t imu_spi_config{};
-
385 spi_device_handle_t spi_hdl{};
-
386 spi_transaction_t spi_transaction{};
- - -
389
-
390 // These are the raw sensor values (without Q applied) pulled from the user requested Input Report
-
391 uint32_t time_stamp;
- - - - - - - - - - - - - - - -
407 uint8_t tap_detector;
-
408 uint16_t step_count;
- - -
411 uint8_t* activity_confidences = nullptr;
- - - - - - - -
419
-
420 static void IRAM_ATTR hint_handler(void* arg);
-
421
-
422 static const constexpr uint8_t TASK_CNT = 2U;
-
423
-
424 static const constexpr uint16_t RX_DATA_LENGTH = 300U;
-
425 static const constexpr uint16_t MAX_METADATA_LENGTH = 9U;
-
426
-
427 static const constexpr TickType_t HOST_INT_TIMEOUT_DEFAULT_MS =
-
428 3000UL /
-
429 portTICK_PERIOD_MS;
-
430
-
431 static const constexpr TickType_t HARD_RESET_DELAY_MS =
-
432 100UL /
-
433 portTICK_PERIOD_MS;
-
434
-
435 static const constexpr TickType_t CMD_EXECUTION_DELAY_MS =
-
436 10UL /
-
437 portTICK_PERIOD_MS;
-
438
-
439 static const constexpr uint32_t SCLK_MAX_SPEED = 3000000UL;
-
440
-
441 // evt_grp_spi bits
-
442 static const constexpr EventBits_t EVT_GRP_SPI_RX_DONE_BIT =
-
443 (1U << 0U);
-
444 static const constexpr EventBits_t EVT_GRP_SPI_RX_VALID_PACKET_BIT =
-
445 (1U << 1U);
-
446 static const constexpr EventBits_t EVT_GRP_SPI_RX_INVALID_PACKET_BIT =
-
447 (1U << 2U);
-
448 static const constexpr EventBits_t EVT_GRP_SPI_TX_DONE_BIT = (1 << 3);
-
449
-
450 // evt_grp_report_en bits
-
451 static const constexpr EventBits_t EVT_GRP_RPT_ROTATION_VECTOR_BIT = (1 << 0);
-
452 static const constexpr EventBits_t EVT_GRP_RPT_GAME_ROTATION_VECTOR_BIT = (1 << 1);
-
453 static const constexpr EventBits_t EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BIT =
-
454 (1U << 2U);
-
455 static const constexpr EventBits_t EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BIT =
-
456 (1U << 3U);
-
457 static const constexpr EventBits_t EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BIT =
-
458 (1U << 4U);
-
459 static const constexpr EventBits_t EVT_GRP_RPT_ACCELEROMETER_BIT = (1U << 5U);
-
460 static const constexpr EventBits_t EVT_GRP_RPT_LINEAR_ACCELEROMETER_BIT = (1U << 6U);
-
461 static const constexpr EventBits_t EVT_GRP_RPT_GRAVITY_BIT = (1U << 7U);
-
462 static const constexpr EventBits_t EVT_GRP_RPT_GYRO_BIT = (1U << 8U);
-
463 static const constexpr EventBits_t EVT_GRP_RPT_GYRO_UNCALIBRATED_BIT = (1U << 9U);
-
464 static const constexpr EventBits_t EVT_GRP_RPT_MAGNETOMETER_BIT = (1U << 10U);
-
465 static const constexpr EventBits_t EVT_GRP_RPT_TAP_DETECTOR_BIT = (1U << 11U);
-
466 static const constexpr EventBits_t EVT_GRP_RPT_STEP_COUNTER_BIT = (1U << 12U);
-
467 static const constexpr EventBits_t EVT_GRP_RPT_STABILITY_CLASSIFIER_BIT = (1U << 13U);
-
468 static const constexpr EventBits_t EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BIT = (1U << 14U);
-
469 static const constexpr EventBits_t EVT_GRP_RPT_RAW_ACCELEROMETER_BIT = (1U << 15U);
-
470 static const constexpr EventBits_t EVT_GRP_RPT_RAW_GYRO_BIT = (1U << 16U);
-
471 static const constexpr EventBits_t EVT_GRP_RPT_RAW_MAGNETOMETER_BIT = (1U << 17U);
-
472
-
473 // evt_grp_task_flow bits
-
474 static const constexpr EventBits_t EVT_GRP_TSK_FLW_RUNNING_BIT =
-
475 (1U << 0U);
-
476
-
477 static const constexpr EventBits_t EVT_GRP_RPT_ALL_BITS =
- - - - - -
483
-
484 // Higher level calibration commands, used by queue_calibrate_command
-
485 static const constexpr uint8_t CALIBRATE_ACCEL = 0U;
-
486 static const constexpr uint8_t CALIBRATE_GYRO = 1U;
-
487 static const constexpr uint8_t CALIBRATE_MAG = 2U;
-
488 static const constexpr uint8_t CALIBRATE_PLANAR_ACCEL = 3U;
-
489 static const constexpr uint8_t CALIBRATE_ACCEL_GYRO_MAG =
-
490 4U;
-
491 static const constexpr uint8_t CALIBRATE_STOP = 5U;
-
492
-
493 // Command IDs (see Ref. Manual 6.4)
-
494 static const constexpr uint8_t COMMAND_ERRORS = 1U;
-
495 static const constexpr uint8_t COMMAND_COUNTER = 2U;
-
496 static const constexpr uint8_t COMMAND_TARE = 3U;
-
497 static const constexpr uint8_t COMMAND_INITIALIZE = 4U;
-
498 static const constexpr uint8_t COMMAND_DCD = 6U;
-
499 static const constexpr uint8_t COMMAND_ME_CALIBRATE = 7U;
-
500 static const constexpr uint8_t COMMAND_DCD_PERIOD_SAVE = 9U;
-
501 static const constexpr uint8_t COMMAND_OSCILLATOR = 10U;
-
502 static const constexpr uint8_t COMMAND_CLEAR_DCD = 11U;
-
503
-
504 // SHTP channel 2 control report IDs, used in communication with sensor (See Ref. Manual 6.2)
-
505 static const constexpr uint8_t SHTP_REPORT_COMMAND_RESPONSE = 0xF1U;
-
506 static const constexpr uint8_t SHTP_REPORT_COMMAND_REQUEST = 0xF2U;
-
507 static const constexpr uint8_t SHTP_REPORT_FRS_READ_RESPONSE = 0xF3U;
-
508 static const constexpr uint8_t SHTP_REPORT_FRS_READ_REQUEST = 0xF4U;
-
509 static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_RESPONSE = 0xF8U;
-
510 static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_REQUEST = 0xF9U;
-
511 static const constexpr uint8_t SHTP_REPORT_BASE_TIMESTAMP = 0xFBU;
-
512 static const constexpr uint8_t SHTP_REPORT_SET_FEATURE_COMMAND = 0xFDU;
-
513 static const constexpr uint8_t SHTP_REPORT_GET_FEATURE_RESPONSE = 0xFCU;
-
514
-
515 // Sensor report IDs, used when enabling and reading BNO08x reports
-
516 static const constexpr uint8_t SENSOR_REPORT_ID_ACCELEROMETER = 0x01U;
-
517 static const constexpr uint8_t SENSOR_REPORT_ID_GYROSCOPE = 0x02U;
-
518 static const constexpr uint8_t SENSOR_REPORT_ID_MAGNETIC_FIELD = 0x03U;
-
519 static const constexpr uint8_t SENSOR_REPORT_ID_LINEAR_ACCELERATION = 0x04U;
-
520 static const constexpr uint8_t SENSOR_REPORT_ID_ROTATION_VECTOR = 0x05U;
-
521 static const constexpr uint8_t SENSOR_REPORT_ID_GRAVITY = 0x06U;
-
522 static const constexpr uint8_t SENSOR_REPORT_ID_UNCALIBRATED_GYRO = 0x07U;
-
523 static const constexpr uint8_t SENSOR_REPORT_ID_GAME_ROTATION_VECTOR = 0x08U;
-
524 static const constexpr uint8_t SENSOR_REPORT_ID_GEOMAGNETIC_ROTATION_VECTOR = 0x09U;
-
525 static const constexpr uint8_t SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR = 0x2AU;
-
526 static const constexpr uint8_t SENSOR_REPORT_ID_TAP_DETECTOR = 0x10U;
-
527 static const constexpr uint8_t SENSOR_REPORT_ID_STEP_COUNTER = 0x11U;
-
528 static const constexpr uint8_t SENSOR_REPORT_ID_STABILITY_CLASSIFIER = 0x13U;
-
529 static const constexpr uint8_t SENSOR_REPORT_ID_RAW_ACCELEROMETER = 0x14U;
-
530 static const constexpr uint8_t SENSOR_REPORT_ID_RAW_GYROSCOPE = 0x15U;
-
531 static const constexpr uint8_t SENSOR_REPORT_ID_RAW_MAGNETOMETER = 0x16U;
-
532 static const constexpr uint8_t SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER = 0x1EU;
-
533 static const constexpr uint8_t SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR = 0x28U;
-
534 static const constexpr uint8_t SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR = 0x29U;
-
535
-
536 // Tare commands used by queue_tare_command
-
537 static const constexpr uint8_t TARE_NOW = 0U;
-
538 static const constexpr uint8_t TARE_PERSIST = 1U;
-
539 static const constexpr uint8_t TARE_SET_REORIENTATION = 2U;
-
540
-
541 static const constexpr uint8_t REPORT_CNT = 19;
-
542
- -
552
- -
554 0;
- -
556
- - -
559
-
560 static const constexpr char* TAG = "BNO08x";
-
561
-
562 friend class BNO08xTestHelper; // allow test helper to access private members for unit tests
-
563};
-
- -
BNO08xStability
BNO08xStability states returned from get_stability_classifier()
Definition BNO08x_global_types.hpp:65
-
struct bno08x_config_t bno08x_config_t
IMU configuration settings passed into constructor.
-
BNO08xResetReason
Reason for previous IMU reset (returned by get_reset_reason())
Definition BNO08x_global_types.hpp:23
-
BNO08xActivity
BNO08xActivity states returned from get_activity_classifier()
Definition BNO08x_global_types.hpp:50
-
BNO08xActivityEnable
BNO08xActivity Classifier enable bits passed to enable_activity_classifier()
Definition BNO08x_global_types.hpp:35
-
BNO08xAccuracy
Sensor accuracy returned during sensor calibration.
Definition BNO08x_global_types.hpp:13
-
BNO08x IMU driver class.
Definition BNO08x.hpp:34
-
void parse_input_report_data(bno08x_rx_packet_t *packet, uint16_t *data, uint16_t data_length)
Parses data from received input report.
Definition BNO08x.cpp:1891
-
uint16_t integrated_gyro_velocity_Y
Definition BNO08x.hpp:399
-
void disable_report(uint8_t report_ID, const EventBits_t report_evt_grp_bit)
Disables a sensor report for a given ID by setting its time interval to 0.
Definition BNO08x.cpp:1050
-
static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_RESPONSE
See SH2 Ref. Manual 6.3.2.
Definition BNO08x.hpp:509
-
void enable_gravity(uint32_t time_between_reports)
Sends command to enable gravity reading reports (See Ref. Manual 6.5.11)
Definition BNO08x.cpp:2300
-
static const constexpr uint32_t SCLK_MAX_SPEED
Max SPI SCLK speed BNO08x is capable of.
Definition BNO08x.hpp:439
-
uint16_t raw_quat_radian_accuracy
Definition BNO08x.hpp:397
-
void enable_activity_classifier(uint32_t time_between_reports, BNO08xActivityEnable activities_to_enable, uint8_t(&activity_confidence_vals)[9])
Sends command to enable activity classifier reports (See Ref. Manual 6.5.36)
Definition BNO08x.cpp:2379
-
static const constexpr uint8_t SENSOR_REPORT_ID_RAW_GYROSCOPE
See SH2 Ref. Manual 6.5.12.
Definition BNO08x.hpp:530
-
void update_personal_activity_classifier_data(bno08x_rx_packet_t *packet)
Updates activity classifier data from parsed input report.
Definition BNO08x.cpp:2170
-
static const constexpr int16_t ACCELEROMETER_Q1
Acceleration Q point (See SH-2 Ref. Manual 6.5.9)
Definition BNO08x.hpp:220
-
void print_packet(bno08x_rx_packet_t *packet)
Prints the passed SHTP packet to serial console with ESP_LOG statement.
Definition BNO08x.cpp:3565
-
static const constexpr uint8_t SENSOR_REPORT_ID_MAGNETIC_FIELD
See SH2 Ref. Manual 6.5.16.
Definition BNO08x.hpp:518
-
void get_gravity(float &x, float &y, float &z, BNO08xAccuracy &accuracy)
Get full reported gravity vector, units in m/s^2.
Definition BNO08x.cpp:2806
-
void register_cb(std::function< void()> cb_fxn)
Registers a callback to execute when new data from a report is received.
Definition BNO08x.cpp:1493
-
esp_err_t launch_tasks()
Launches spi_task and data_proc_task on constructor call.
Definition BNO08x.cpp:4003
-
uint16_t raw_bias_Z
Uncalibrated gyro reading (See SH-2 Ref. Manual 6.5.14)
Definition BNO08x.hpp:404
-
static const constexpr uint16_t FRS_RECORD_ID_MAGNETIC_FIELD_CALIBRATED
Calibrated magnetometer record ID, to be passed in metadata functions like get_Q1()
Definition BNO08x.hpp:202
-
static const constexpr uint8_t COMMAND_TARE
Command and response to tare command (See Sh2 Ref. Manual 6.4.4)
Definition BNO08x.hpp:496
-
float get_accel_Z()
Get z axis acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:3097
-
static void data_proc_task_trampoline(void *arg)
Static function used to launch data processing task.
Definition BNO08x.cpp:3940
-
static const constexpr int16_t ROTATION_VECTOR_Q1
Rotation vector Q point (See SH-2 Ref. Manual 6.5.18)
Definition BNO08x.hpp:218
-
static void spi_task_trampoline(void *arg)
Static function used to launch spi task.
Definition BNO08x.cpp:3874
-
void update_report_period_trackers(uint8_t report_ID, uint32_t new_period)
Updates period of respective report in report_period_trackers and recalculates host_int_timeout_ms ac...
Definition BNO08x.cpp:4101
-
static const constexpr EventBits_t EVT_GRP_RPT_GAME_ROTATION_VECTOR_BIT
When set, game rotation vector reports are active.
Definition BNO08x.hpp:452
-
float get_range(uint16_t record_ID)
Gets range from BNO08x FRS (flash record system).
Definition BNO08x.cpp:3676
-
float get_linear_accel_Y()
Get y axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
Definition BNO08x.cpp:3145
-
float get_magf_X()
Get X component of magnetic field vector.
Definition BNO08x.cpp:2758
-
static const constexpr uint8_t TARE_PERSIST
See SH2 Ref. Manual 6.4.4.2.
Definition BNO08x.hpp:538
-
uint8_t tap_detector
Tap detector reading (See SH-2 Ref. Manual 6.5.27)
Definition BNO08x.hpp:407
-
float get_quat_I()
Get I component of reported quaternion.
Definition BNO08x.cpp:2994
-
int16_t get_Q3(uint16_t record_ID)
Gets Q3 point from BNO08x FRS (flash record system).
Definition BNO08x.cpp:3646
-
float get_calibrated_gyro_velocity_Z()
Get calibrated gyro z axis angular velocity measurement.
Definition BNO08x.cpp:3349
-
static const constexpr EventBits_t EVT_GRP_SPI_RX_INVALID_PACKET_BIT
When this bit is set, it indicates an invalid packet has been received.
Definition BNO08x.hpp:446
-
void disable_tap_detector()
Sends command to disable tap detector reports by setting report interval to 0.
Definition BNO08x.cpp:2534
-
bool mode_sleep()
Puts BNO08x sensor into sleep/low power mode using executable channel.
Definition BNO08x.cpp:886
-
static const constexpr EventBits_t EVT_GRP_RPT_ACCELEROMETER_BIT
When set, accelerometer reports are active.
Definition BNO08x.hpp:459
-
static const constexpr EventBits_t EVT_GRP_RPT_ROTATION_VECTOR_BIT
When set, rotation vector reports are active.
Definition BNO08x.hpp:451
-
static const constexpr uint16_t RX_DATA_LENGTH
length buffer containing data received over spi
Definition BNO08x.hpp:424
-
uint8_t stability_classifier
BNO08xStability status reading (See SH-2 Ref. Manual 6.5.31)
Definition BNO08x.hpp:409
-
float get_pitch()
Get the reported rotation about y axis.
Definition BNO08x.cpp:2886
-
uint16_t parse_packet(bno08x_rx_packet_t *packet, bool &notify_users)
Parses a packet received from bno08x, updating any data according to received reports.
Definition BNO08x.cpp:1507
-
void calibrate_planar_accelerometer()
Sends command to calibrate planar accelerometer.
Definition BNO08x.cpp:1236
-
static const constexpr uint8_t SHTP_REPORT_SET_FEATURE_COMMAND
See SH2 Ref. Manual 6.5.4.
Definition BNO08x.hpp:512
-
float get_resolution(uint16_t record_ID)
Gets resolution from BNO08x FRS (flash record system).
Definition BNO08x.cpp:3659
-
static const constexpr uint8_t SHTP_REPORT_COMMAND_RESPONSE
See SH2 Ref. Manual 6.3.9.
Definition BNO08x.hpp:505
-
void disable_rotation_vector()
Sends command to disable rotation vector reports by setting report interval to 0.
Definition BNO08x.cpp:2424
-
static const constexpr uint8_t TARE_AXIS_ALL
Tare all axes (used with tare now command)
Definition BNO08x.hpp:207
-
esp_err_t deinit_gpio_inputs()
Deinitializes GPIO inputs, called from deconstructor.
Definition BNO08x.cpp:453
-
struct BNO08x::bno08x_init_status_t bno08x_init_status_t
Holds info about which functionality has been successfully initialized (used by deconstructor during ...
-
uint16_t parse_feature_get_response_report(bno08x_rx_packet_t *packet)
Parses get feature request report received from BNO08x.
Definition BNO08x.cpp:1683
-
static const constexpr uint8_t SENSOR_REPORT_ID_GYROSCOPE
See SH2 Ref. Manual 6.5.13.
Definition BNO08x.hpp:517
-
static const constexpr uint8_t TARE_GEOMAGNETIC_ROTATION_VECTOR
tare geomagnetic rotation vector
Definition BNO08x.hpp:213
-
esp_err_t deinit_spi()
Deinitializes SPI.
Definition BNO08x.cpp:562
-
BNO08xStability get_stability_classifier()
Get the current stability classifier (Seee Ref. Manual 6.5.31)
Definition BNO08x.cpp:3508
-
void enable_accelerometer(uint32_t time_between_reports)
Sends command to enable accelerometer reports (See Ref. Manual 6.5.9)
Definition BNO08x.cpp:2278
-
static uint8_t report_ID_to_report_period_tracker_idx(uint8_t report_ID)
Converts report id to respective index in report_period_trackers.
Definition BNO08x.cpp:4155
-
static const constexpr uint8_t TARE_NOW
See SH2 Ref. Manual 6.4.4.1.
Definition BNO08x.hpp:537
-
uint32_t FRS_read_word(uint16_t record_ID, uint8_t word_number)
Reads meta data word from BNO08x FRS (flash record system) given the record ID and word number....
Definition BNO08x.cpp:3697
-
float q_to_float(int16_t fixed_point_value, uint8_t q_point)
Converts a register value to a float using its associated Q point. (See https://en....
Definition BNO08x.cpp:2648
-
bool wait_for_rx_done()
Waits for data to be received over SPI, or host_int_timeout_ms to elapse.
Definition BNO08x.cpp:608
-
bool hard_reset()
Hard resets BNO08x sensor.
Definition BNO08x.cpp:737
-
uint16_t parse_product_id_report(bno08x_rx_packet_t *packet)
Parses product id report and prints device info.
Definition BNO08x.cpp:1616
-
static const constexpr uint8_t SENSOR_REPORT_ID_STEP_COUNTER
See SH2 Ref. Manual 6.5.29.
Definition BNO08x.hpp:527
-
static const constexpr uint16_t MAX_METADATA_LENGTH
max length of metadata used in frs read operations
Definition BNO08x.hpp:425
-
void send_packet(bno08x_tx_packet_t *packet)
Sends a queued SHTP packet via SPI.
Definition BNO08x.cpp:1127
-
static const constexpr char * TAG
Class tag used for serial print statements.
Definition BNO08x.hpp:560
-
float get_uncalibrated_gyro_velocity_Y()
Get uncalibrated gyro Y axis angular velocity measurement.
Definition BNO08x.cpp:3392
-
BNO08xAccuracy get_magf_accuracy()
Get accuracy of reported magnetic field vector.
Definition BNO08x.cpp:2791
-
float get_integrated_gyro_velocity_X()
Get x axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6....
Definition BNO08x.cpp:3458
-
void spi_task()
Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x.
Definition BNO08x.cpp:3885
-
static const constexpr uint8_t COMMAND_OSCILLATOR
Retrieve oscillator type command (See SH2 Ref. Manual 6.4)
Definition BNO08x.hpp:501
-
static const constexpr uint8_t COMMAND_INITIALIZE
Reinitialize sensor hub components See (SH2 Ref. Manual 6.4.5)
Definition BNO08x.hpp:497
-
static const constexpr EventBits_t EVT_GRP_SPI_RX_DONE_BIT
When this bit is set it indicates a receive procedure has completed.
Definition BNO08x.hpp:442
-
uint16_t accel_accuracy
Raw acceleration readings (See SH-2 Ref. Manual 6.5.8)
Definition BNO08x.hpp:393
-
uint16_t get_raw_mems_magf_X()
Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:3283
-
static const constexpr uint8_t SENSOR_REPORT_ID_ACCELEROMETER
See SH2 Ref. Manual 6.5.9.
Definition BNO08x.hpp:516
-
void update_stability_classifier_data(bno08x_rx_packet_t *packet)
Updates stability classifier data from parsed input report.
Definition BNO08x.cpp:2158
-
void print_header(bno08x_rx_packet_t *packet)
Prints the header of the passed SHTP packet to serial console with ESP_LOG statement.
Definition BNO08x.cpp:3538
-
static const constexpr uint16_t FRS_RECORD_ID_GYROSCOPE_CALIBRATED
Calirated gyroscope record ID, to be passed in metadata functions like get_Q1()
Definition BNO08x.hpp:200
-
uint16_t accel_lin_accuracy
Raw linear acceleration (See SH-2 Ref. Manual 6.5.10)
Definition BNO08x.hpp:395
-
uint16_t quat_accuracy
Raw quaternion reading (See SH-2 Ref. Manual 6.5.44)
Definition BNO08x.hpp:398
-
static const constexpr uint8_t SENSOR_REPORT_ID_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.18.
Definition BNO08x.hpp:520
-
static const constexpr uint8_t COMMAND_ERRORS
Definition BNO08x.hpp:494
-
static const constexpr TickType_t CMD_EXECUTION_DELAY_MS
How long to delay after queueing command to allow it to execute (for ex. after sending command to ena...
Definition BNO08x.hpp:435
-
struct BNO08x::bno08x_tx_packet_t bno08x_tx_packet_t
Holds data that is sent over spi.
-
static const constexpr EventBits_t EVT_GRP_RPT_GYRO_BIT
When set, gyro reports are active.
Definition BNO08x.hpp:462
-
void update_magf_data(uint16_t *data, uint8_t status)
Updates magnetic field data from parsed input report.
Definition BNO08x.cpp:2040
-
void enable_magnetometer(uint32_t time_between_reports)
Sends command to enable magnetometer reports (See Ref. Manual 6.5.16)
Definition BNO08x.cpp:2333
-
void get_accel(float &x, float &y, float &z, BNO08xAccuracy &accuracy)
Get full acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:3064
-
uint16_t mems_raw_gyro_X
Definition BNO08x.hpp:415
-
static const constexpr EventBits_t EVT_GRP_RPT_RAW_ACCELEROMETER_BIT
When set, raw accelerometer reports are active.
Definition BNO08x.hpp:469
-
bool FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read)
Read meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other...
Definition BNO08x.cpp:3749
-
struct BNO08x::bno08x_rx_packet_t bno08x_rx_packet_t
Holds data that is received over spi.
-
spi_device_interface_config_t imu_spi_config
SPI slave device settings.
Definition BNO08x.hpp:384
-
void disable_step_counter()
Sends command to disable step counter reports by setting report interval to 0.
Definition BNO08x.cpp:2544
-
int16_t get_Q1(uint16_t record_ID)
Gets Q1 point from BNO08x FRS (flash record system).
Definition BNO08x.cpp:3616
-
bno08x_init_status_t init_status
Initialization status of various functionality, used by deconstructor during cleanup,...
Definition BNO08x.hpp:388
-
void reset_all_data_to_defaults()
Resets all data returned by public getter APIs to initial values of 0 and low accuracy.
Definition BNO08x.cpp:2670
-
void tare_now(uint8_t axis_sel=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
Sends command to tare an axis (See Ref. Manual 6.4.4.1)
Definition BNO08x.cpp:2608
-
uint8_t get_tap_detector()
Get if tap has occured.
Definition BNO08x.cpp:3488
-
void flush_rx_packets(uint8_t flush_count)
Definition BNO08x.cpp:1144
-
float get_calibrated_gyro_velocity_Y()
Get calibrated gyro y axis angular velocity measurement.
Definition BNO08x.cpp:3339
-
BNO08xActivity get_activity_classifier()
Get the current activity classifier (Seee Ref. Manual 6.5.36)
Definition BNO08x.cpp:3527
-
uint16_t get_raw_mems_gyro_Y()
Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:3247
-
void get_linear_accel(float &x, float &y, float &z, BNO08xAccuracy &accuracy)
Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2).
Definition BNO08x.cpp:3122
-
void queue_tare_command(uint8_t command, uint8_t axis=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
Queues a packet containing a command related to zeroing sensor's axes. (See Ref. Manual 6....
Definition BNO08x.cpp:3851
-
QueueHandle_t queue_tx_data
Packet queue used to send data to be sent over SPI from sending functions to spi_task.
Definition BNO08x.hpp:374
-
void disable_calibrated_gyro()
Sends command to disable calibrated gyro reports by setting report interval to 0.
Definition BNO08x.cpp:2504
-
esp_err_t deinit_gpio()
Deinitializes GPIO, called from deconstructor.
Definition BNO08x.cpp:427
-
bool wait_for_data()
Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse.
Definition BNO08x.cpp:648
-
static const constexpr uint8_t COMMAND_CLEAR_DCD
Clear DCD & Reset command (See SH2 Ref. Manual 6.4)
Definition BNO08x.hpp:502
-
uint16_t parse_command_report(bno08x_rx_packet_t *packet)
Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)
Definition BNO08x.cpp:1943
-
void disable_activity_classifier()
Sends command to disable activity classifier reports by setting report interval to 0.
Definition BNO08x.cpp:2564
-
float get_uncalibrated_gyro_bias_Z()
Get uncalibrated gyro Z axis drift estimate.
Definition BNO08x.cpp:3432
-
uint16_t parse_frs_read_response_report(bno08x_rx_packet_t *packet)
Sends packet to be parsed to meta data function call (FRS_read_data()) through queue.
Definition BNO08x.cpp:1663
-
static const constexpr EventBits_t EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BIT
When set, gyro integrator rotation vector reports are active.
Definition BNO08x.hpp:457
-
static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_REQUEST
See SH2 Ref. Manual 6.3.1.
Definition BNO08x.hpp:510
-
static const constexpr uint8_t TASK_CNT
Total amount of tasks utilized by BNO08x driver library.
Definition BNO08x.hpp:422
-
float get_gravity_Z()
Get the reported z axis gravity.
Definition BNO08x.cpp:2839
-
void enable_ARVR_stabilized_game_rotation_vector(uint32_t time_between_reports)
Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6....
Definition BNO08x.cpp:2256
-
static const constexpr uint8_t CALIBRATE_STOP
Stop calibration command used by queue_calibrate_command.
Definition BNO08x.hpp:491
-
esp_err_t init_config_args()
Initializes required esp-idf SPI data structures with values from user passed bno08x_config_t struct.
Definition BNO08x.cpp:124
-
esp_err_t init_spi()
Initializes SPI.
Definition BNO08x.cpp:372
-
uint16_t mems_raw_accel_Z
Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.5.8)
Definition BNO08x.hpp:414
-
static const constexpr uint8_t TARE_SET_REORIENTATION
See SH2 Ref. Manual 6.4.4.3.
Definition BNO08x.hpp:539
-
void enable_step_counter(uint32_t time_between_reports)
Sends command to enable step counter reports (See Ref. Manual 6.5.29)
Definition BNO08x.cpp:2355
-
float get_quat_real()
Get real component of reported quaternion.
Definition BNO08x.cpp:3027
-
esp_err_t kill_all_tasks()
Deletes spi_task and data_proc_task safely on deconstructor call.
Definition BNO08x.cpp:4055
-
void queue_command(uint8_t command, uint8_t *commands)
Queues a packet containing a command.
Definition BNO08x.cpp:1158
-
void disable_raw_mems_gyro()
Sends command to disable raw gyro reports by setting report interval to 0.
Definition BNO08x.cpp:2585
-
void disable_gravity()
Sends command to disable gravity reports by setting report interval to 0.
Definition BNO08x.cpp:2494
-
static const constexpr EventBits_t EVT_GRP_TSK_FLW_RUNNING_BIT
When set, data_proc_task and spi_task are active, when 0 they are pending deletion or deleted.
Definition BNO08x.hpp:474
-
BNO08xAccuracy get_linear_accel_accuracy()
Get accuracy of linear acceleration.
Definition BNO08x.cpp:3165
-
TaskHandle_t spi_task_hdl
spi_task() handle
Definition BNO08x.hpp:351
-
uint16_t raw_quat_J
Definition BNO08x.hpp:397
-
float get_quat_radian_accuracy()
Get radian accuracy of reported quaternion.
Definition BNO08x.cpp:3038
-
void queue_packet(uint8_t channel_number, uint8_t data_length, uint8_t *commands)
Queues an SHTP packet to be sent via SPI.
Definition BNO08x.cpp:1098
-
void disable_raw_mems_magnetometer()
Sends command to disable raw magnetometer reports by setting report interval to 0.
Definition BNO08x.cpp:2595
-
EventGroupHandle_t evt_grp_report_en
Event group for indicating which reports are currently enabled.
Definition BNO08x.hpp:370
-
float get_yaw()
Get the reported rotation about z axis.
Definition BNO08x.cpp:2915
-
uint16_t integrated_gyro_velocity_X
Definition BNO08x.hpp:399
-
static const constexpr EventBits_t EVT_GRP_RPT_TAP_DETECTOR_BIT
When set, tap detector reports are active.
Definition BNO08x.hpp:465
-
void disable_magnetometer()
Sends command to disable magnetometer reports by setting report interval to 0.
Definition BNO08x.cpp:2524
-
uint16_t raw_calib_gyro_Y
Definition BNO08x.hpp:396
-
static const constexpr uint8_t SENSOR_REPORT_ID_GRAVITY
See SH2 Ref. Manual 6.5.11.
Definition BNO08x.hpp:521
-
~BNO08x()
BNO08x imu deconstructor.
Definition BNO08x.cpp:34
-
static const constexpr uint8_t TARE_ARVR_STABILIZED_GAME_ROTATION_VECTOR
Tare ARVR stabilized game rotation vector.
Definition BNO08x.hpp:216
-
void enable_raw_mems_magnetometer(uint32_t time_between_reports)
Sends command to enable raw MEMs magnetometer reports (See Ref. Manual 6.5.15)
Definition BNO08x.cpp:2414
-
uint16_t raw_quat_I
Definition BNO08x.hpp:397
-
void enable_raw_mems_accelerometer(uint32_t time_between_reports)
Sends command to enable raw MEMs accelerometer reports (See Ref. Manual 6.5.8)
Definition BNO08x.cpp:2392
-
std::vector< std::function< void()> > cb_list
Definition BNO08x.hpp:378
-
static const constexpr EventBits_t EVT_GRP_RPT_RAW_GYRO_BIT
When set, raw gyro reports are active.
Definition BNO08x.hpp:470
-
void disable_raw_mems_accelerometer()
Sends command to disable raw accelerometer reports by setting report interval to 0.
Definition BNO08x.cpp:2575
-
void update_raw_magf_data(uint16_t *data)
Updates raw magnetic field data from parsed input report.
Definition BNO08x.cpp:2132
-
BNO08xAccuracy get_accel_accuracy()
Get accuracy of linear acceleration.
Definition BNO08x.cpp:3107
-
float get_roll_deg()
Get the reported rotation about x axis.
Definition BNO08x.cpp:2942
-
float get_uncalibrated_gyro_velocity_X()
Get uncalibrated gyro x axis angular velocity measurement.
Definition BNO08x.cpp:3382
-
bool calibration_complete()
Returns true if calibration has completed.
Definition BNO08x.cpp:1314
-
static const constexpr uint8_t SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER
See SH2 Ref. Manual 6.5.36.
Definition BNO08x.hpp:532
-
void enable_gyro_integrated_rotation_vector(uint32_t time_between_reports)
Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6....
Definition BNO08x.cpp:2267
-
void update_lin_accelerometer_data(uint16_t *data, uint8_t status)
Updates linear accelerometer data from parsed input report.
Definition BNO08x.cpp:1991
-
float get_uncalibrated_gyro_bias_Y()
Get uncalibrated gyro Y axis drift estimate.
Definition BNO08x.cpp:3422
-
static const constexpr uint8_t SHTP_REPORT_FRS_READ_REQUEST
See SH2 Ref. Manual 6.3.6.
Definition BNO08x.hpp:508
-
uint8_t activity_classifier
BNO08xActivity status reading (See SH-2 Ref. Manual 6.5.36)
Definition BNO08x.hpp:410
-
uint16_t raw_accel_X
Definition BNO08x.hpp:392
-
float get_linear_accel_X()
Get x axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
Definition BNO08x.cpp:3135
-
void disable_game_rotation_vector()
Sends command to disable game rotation vector reports by setting report interval to 0.
Definition BNO08x.cpp:2434
-
float get_calibrated_gyro_velocity_X()
Get calibrated gyro x axis angular velocity measurement.
Definition BNO08x.cpp:3329
-
uint16_t raw_quat_K
Definition BNO08x.hpp:397
-
BNO08xAccuracy get_gravity_accuracy()
Get the reported gravity accuracy.
Definition BNO08x.cpp:2849
-
uint16_t get_raw_mems_magf_Z()
Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:3303
-
void enable_report(uint8_t report_ID, uint32_t time_between_reports, const EventBits_t report_evt_grp_bit, uint32_t special_config=0)
Enables a sensor report for a given ID.
Definition BNO08x.cpp:1016
-
static const constexpr EventBits_t EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BIT
When set, ARVR stabilized game rotation vector reports are active.
Definition BNO08x.hpp:455
-
static const constexpr uint8_t COMMAND_DCD_PERIOD_SAVE
Configure DCD periodic saving (See SH2 Ref. Manual 6.4)
Definition BNO08x.hpp:500
-
uint32_t meta_data[9]
First 9 bytes of meta data returned from FRS read operation (we don't really need the rest) (See Ref....
Definition BNO08x.hpp:380
-
uint16_t parse_gyro_integrated_rotation_vector_report(bno08x_rx_packet_t *packet)
Parses received gyro integrated rotation vector report sent by BNO08x.
Definition BNO08x.cpp:1930
-
BNO08xAccuracy get_quat_accuracy()
Get accuracy of reported quaternion.
Definition BNO08x.cpp:3049
-
bool wait_for_tx_done()
Waits for a queued packet to be sent or host_int_timeout_ms to elapse.
Definition BNO08x.cpp:704
-
QueueHandle_t queue_rx_data
Packet queue used to send data received from bno08x from spi_task to data_proc_task.
Definition BNO08x.hpp:373
-
static const constexpr EventBits_t EVT_GRP_RPT_STABILITY_CLASSIFIER_BIT
When set, stability classifier reports are active.
Definition BNO08x.hpp:467
-
void enable_uncalibrated_gyro(uint32_t time_between_reports)
Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.5.14)
Definition BNO08x.cpp:2322
-
uint32_t largest_sample_period_us
Current largest sample period of any enabled report in microseconds (used to determine timeout for hi...
Definition BNO08x.hpp:553
-
static void IRAM_ATTR hint_handler(void *arg)
HINT interrupt service routine, handles falling edge of BNO08x HINT pin.
Definition BNO08x.cpp:4209
-
static const constexpr uint8_t SENSOR_REPORT_ID_RAW_ACCELEROMETER
See SH2 Ref. Manual 6.5.8.
Definition BNO08x.hpp:529
-
static const constexpr uint8_t SENSOR_REPORT_ID_TAP_DETECTOR
See SH2 Ref. Manual 6.5.27.
Definition BNO08x.hpp:526
-
float get_magf_Y()
Get Y component of magnetic field vector.
Definition BNO08x.cpp:2769
-
static const constexpr uint8_t COMMAND_ME_CALIBRATE
Command and response to configure ME calibration (See SH2 Ref. Manual 6.4.7)
Definition BNO08x.hpp:499
-
void update_raw_accelerometer_data(uint16_t *data)
Updates raw accelerometer data from parsed input report.
Definition BNO08x.cpp:2104
-
QueueHandle_t queue_reset_reason
Queue used to send reset reason from product id report to reset_reason() function.
Definition BNO08x.hpp:376
-
uint16_t get_raw_mems_accel_Z()
Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref....
Definition BNO08x.cpp:3211
-
uint16_t raw_quat_real
Definition BNO08x.hpp:397
-
uint16_t get_raw_mems_accel_X()
Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref....
Definition BNO08x.cpp:3191
-
void get_uncalibrated_gyro_velocity(float &x, float &y, float &z, float &bx, float &by, float &bz)
Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv...
Definition BNO08x.cpp:3367
-
uint16_t raw_calib_gyro_X
Definition BNO08x.hpp:396
-
float get_gravity_X()
Get the reported x axis gravity.
Definition BNO08x.cpp:2819
-
uint16_t get_raw_mems_gyro_X()
Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:3237
-
static const constexpr EventBits_t EVT_GRP_RPT_ALL_BITS
Definition BNO08x.hpp:477
-
float get_roll()
Get the reported rotation about x axis.
Definition BNO08x.cpp:2859
-
uint16_t raw_bias_X
Definition BNO08x.hpp:403
-
float get_gravity_Y()
Get the reported y axis gravity.
Definition BNO08x.cpp:2829
-
void enable_ARVR_stabilized_rotation_vector(uint32_t time_between_reports)
Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6....
Definition BNO08x.cpp:2245
-
void enable_raw_mems_gyro(uint32_t time_between_reports)
Sends command to enable raw MEMs gyro reports (See Ref. Manual 6.5.12)
Definition BNO08x.cpp:2403
-
static const constexpr uint8_t SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.42.
Definition BNO08x.hpp:533
-
uint16_t parse_input_report(bno08x_rx_packet_t *packet)
Parses received input report sent by BNO08x.
Definition BNO08x.cpp:1794
-
esp_err_t receive_packet()
Receives a SHTP packet via SPI and sends it to data_proc_task()
Definition BNO08x.cpp:906
-
void update_uncalibrated_gyro_data(uint16_t *data, uint8_t status)
Updates uncalibrated gyro data from parsed input report.
Definition BNO08x.cpp:2022
-
static const constexpr uint8_t TARE_ROTATION_VECTOR
Tare rotation vector.
Definition BNO08x.hpp:211
-
esp_err_t init_gpio_inputs()
Initializes required gpio inputs.
Definition BNO08x.cpp:220
-
void get_integrated_gyro_velocity(float &x, float &y, float &z)
Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5....
Definition BNO08x.cpp:3446
-
static const constexpr EventBits_t EVT_GRP_RPT_MAGNETOMETER_BIT
When set, magnetometer reports are active.
Definition BNO08x.hpp:464
-
uint16_t mems_raw_magf_Z
Raw magnetometer (compass) readings from MEMS sensor (See SH-2 Ref. Manual 6.5.15)
Definition BNO08x.hpp:418
-
static const constexpr int16_t ROTATION_VECTOR_ACCURACY_Q1
Rotation vector accuracy estimate Q point (See SH-2 Ref. Manual 6.5.18)
Definition BNO08x.hpp:219
-
void get_raw_mems_magf(uint16_t &x, uint16_t &y, uint16_t &z)
Get raw magnetometer full reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:3271
-
uint16_t mems_raw_accel_X
Definition BNO08x.hpp:413
-
static const constexpr uint8_t COMMAND_COUNTER
Definition BNO08x.hpp:495
-
int16_t get_Q2(uint16_t record_ID)
Gets Q2 point from BNO08x FRS (flash record system).
Definition BNO08x.cpp:3631
-
static const constexpr uint8_t CALIBRATE_PLANAR_ACCEL
Calibrate planar acceleration command used by queue_calibrate_command.
Definition BNO08x.hpp:488
-
void update_calibrated_gyro_data(uint16_t *data, uint8_t status)
Updates linear gyro data from parsed input report.
Definition BNO08x.cpp:2007
-
static const constexpr EventBits_t EVT_GRP_SPI_RX_VALID_PACKET_BIT
When this bit is set, it indicates a valid packet has been received and processed.
Definition BNO08x.hpp:444
-
static const constexpr uint8_t REPORT_CNT
Total unique reports that can be returned by BNO08x.
Definition BNO08x.hpp:541
-
BNO08xResetReason get_reset_reason()
Requests product ID, prints the returned info over serial, and returns the reason for the most resent...
Definition BNO08x.cpp:826
-
static const constexpr EventBits_t EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BIT
When set, activity classifier reports are active.
Definition BNO08x.hpp:468
-
bool soft_reset()
Soft resets BNO08x sensor using executable channel.
Definition BNO08x.cpp:802
-
spi_bus_config_t bus_config
SPI bus GPIO configuration settings.
Definition BNO08x.hpp:383
-
QueueHandle_t queue_frs_read_data
Queue used to send packet body from data_proc_task to frs read functions.
Definition BNO08x.hpp:375
-
void calibrate_gyro()
Sends command to calibrate gyro.
Definition BNO08x.cpp:1212
-
esp_err_t deinit_hint_isr()
Deinitializes host interrupt ISR, called from deconstructor.
Definition BNO08x.cpp:526
-
void enable_calibrated_gyro(uint32_t time_between_reports)
Sends command to enable calibrated gyro reports (See Ref. Manual 6.5.13)
Definition BNO08x.cpp:2311
-
static const constexpr uint8_t SENSOR_REPORT_ID_RAW_MAGNETOMETER
See SH2 Ref. Manual 6.5.15.
Definition BNO08x.hpp:531
-
static const constexpr uint8_t TARE_GYRO_INTEGRATED_ROTATION_VECTOR
Tare gyro integrated rotation vector.
Definition BNO08x.hpp:214
-
esp_err_t receive_packet_body(bno08x_rx_packet_t *packet)
Receives a SHTP packet body via SPI.
Definition BNO08x.cpp:987
-
static const constexpr uint16_t FRS_RECORD_ID_ROTATION_VECTOR
Rotation vector record ID, to be passed in metadata functions like get_Q1()
Definition BNO08x.hpp:204
-
float get_quat_K()
Get K component of reported quaternion.
Definition BNO08x.cpp:3016
-
float get_quat_J()
Get J component of reported quaternion.
Definition BNO08x.cpp:3005
-
static const constexpr int16_t MAGNETOMETER_Q1
Magnetometer Q point (See SH-2 Ref. Manual 6.5.16)
Definition BNO08x.hpp:223
-
static const constexpr TickType_t HARD_RESET_DELAY_MS
How long RST pin is held low during hard reset (min 10ns according to datasheet, but should be longer...
Definition BNO08x.hpp:431
-
void save_calibration()
Sends command to save internal calibration data (See Ref. Manual 6.4.7).
Definition BNO08x.cpp:1339
-
esp_err_t init_hint_isr()
Initializes host interrupt ISR.
Definition BNO08x.cpp:321
-
EventGroupHandle_t evt_grp_spi
Event group for indicating when bno08x hint pin has triggered and when new data has been processed....
Definition BNO08x.hpp:369
-
void update_rotation_vector_data(uint16_t *data, uint8_t status)
Updates roation vector data from parsed input report.
Definition BNO08x.cpp:2072
-
void update_step_counter_data(uint16_t *data)
Updates step counter data from parsed input report.
Definition BNO08x.cpp:2092
-
static const constexpr int16_t GYRO_Q1
Gyro Q point (See SH-2 Ref. Manual 6.5.13)
Definition BNO08x.hpp:222
-
void disable_ARVR_stabilized_rotation_vector()
Sends command to disable ARVR stabilized rotation vector reports by setting report interval to 0.
Definition BNO08x.cpp:2444
-
float get_integrated_gyro_velocity_Z()
Get z axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6....
Definition BNO08x.cpp:3478
-
uint16_t raw_magf_X
Definition BNO08x.hpp:405
-
void get_raw_mems_accel(uint16_t &x, uint16_t &y, uint16_t &z)
Get full raw acceleration from physical accelerometer MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:3179
-
void get_calibrated_gyro_velocity(float &x, float &y, float &z)
Get full rotational velocity with drift compensation (units in Rad/s).
Definition BNO08x.cpp:3317
-
SemaphoreHandle_t sem_kill_tasks
semaphore to count amount of killed tasks
Definition BNO08x.hpp:361
-
static const constexpr EventBits_t EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BIT
When set, ARVR stabilized rotation vector reports are active.
Definition BNO08x.hpp:453
-
void disable_gyro_integrated_rotation_vector()
Sends command to disable gyro integrated rotation vector reports by setting report interval to 0.
Definition BNO08x.cpp:2464
-
uint16_t mems_raw_magf_Y
Definition BNO08x.hpp:417
-
void disable_uncalibrated_gyro()
Sends command to disable uncalibrated gyro reports by setting report interval to 0.
Definition BNO08x.cpp:2514
-
static const constexpr int16_t ANGULAR_VELOCITY_Q1
Angular velocity Q point (See SH-2 Ref. Manual 6.5.44)
Definition BNO08x.hpp:224
-
void update_integrated_gyro_rotation_vector_data(bno08x_rx_packet_t *packet)
Updates integrated gyro rotation vector data from SHTP channel 5 (CHANNEL_GYRO) special report data.
Definition BNO08x.cpp:2206
-
static const constexpr uint8_t SHTP_REPORT_COMMAND_REQUEST
See SH2 Ref. Manual 6.3.8.
Definition BNO08x.hpp:506
-
void enable_stability_classifier(uint32_t time_between_reports)
Sends command to enable activity stability classifier reports (See Ref. Manual 6.5....
Definition BNO08x.cpp:2366
-
TickType_t host_int_timeout_ms
Max wait between HINT being asserted by BNO08x before transaction is considered failed (in milisecond...
Definition BNO08x.hpp:557
-
esp_err_t deinit_gpio_outputs()
Deinitializes GPIO outputs, called from deconstructor.
Definition BNO08x.cpp:475
-
void disable_ARVR_stabilized_game_rotation_vector()
Sends command to disable ARVR stabilized game rotation vector reports by setting report interval to 0...
Definition BNO08x.cpp:2454
-
static const constexpr EventBits_t EVT_GRP_RPT_STEP_COUNTER_BIT
When set, step counter reports are active.
Definition BNO08x.hpp:466
-
void disable_stability_classifier()
Sends command to disable stability reports by setting report interval to 0.
Definition BNO08x.cpp:2554
-
void data_proc_task()
Task responsible parsing packets. Executed when SPI task sends a packet to be parsed,...
Definition BNO08x.cpp:3951
-
uint16_t raw_magf_Z
Definition BNO08x.hpp:405
-
void enable_rotation_vector(uint32_t time_between_reports)
Sends command to enable rotation vector reports (See Ref. Manual 6.5.18)
Definition BNO08x.cpp:2234
-
float get_magf_Z()
Get Z component of magnetic field vector.
Definition BNO08x.cpp:2780
-
void enable_tap_detector(uint32_t time_between_reports)
Sends command to enable tap detector reports (See Ref. Manual 6.5.27)
Definition BNO08x.cpp:2344
-
bool data_available(bool ignore_no_reports_enabled=false)
Checks if BNO08x has asserted interrupt and sent data.
Definition BNO08x.cpp:1469
-
uint16_t raw_accel_Y
Definition BNO08x.hpp:392
-
uint16_t mems_raw_magf_X
Definition BNO08x.hpp:417
-
static const constexpr uint8_t SENSOR_REPORT_ID_STABILITY_CLASSIFIER
See SH2 Ref. Manual 6.5.31.
Definition BNO08x.hpp:528
-
void queue_request_product_id_command()
Queues a packet containing the request product ID command.
Definition BNO08x.cpp:1174
-
uint16_t mems_raw_gyro_Y
Definition BNO08x.hpp:415
-
float get_uncalibrated_gyro_velocity_Z()
Get uncalibrated gyro Z axis angular velocity measurement.
Definition BNO08x.cpp:3402
-
static const constexpr EventBits_t EVT_GRP_RPT_GRAVITY_BIT
When set, gravity reports are active.
Definition BNO08x.hpp:461
-
static const constexpr uint8_t TARE_GAME_ROTATION_VECTOR
Tare game rotation vector.
Definition BNO08x.hpp:212
-
static const constexpr uint8_t SENSOR_REPORT_ID_GEOMAGNETIC_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.20.
Definition BNO08x.hpp:524
-
uint16_t raw_lin_accel_Z
Definition BNO08x.hpp:394
-
uint32_t time_stamp
Report timestamp (see datasheet 1.3.5.3)
Definition BNO08x.hpp:391
-
float get_accel_X()
Get x axis acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:3077
-
void enable_game_rotation_vector(uint32_t time_between_reports)
Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19)
Definition BNO08x.cpp:2223
-
static const constexpr uint8_t TARE_ARVR_STABILIZED_ROTATION_VECTOR
Tare ARVR stabilized rotation vector.
Definition BNO08x.hpp:215
-
static const constexpr uint8_t CALIBRATE_MAG
Calibrate magnetometer command used by queue_calibrate_command.
Definition BNO08x.hpp:487
-
channels_t
SHTP protocol channels.
Definition BNO08x.hpp:230
-
@ CHANNEL_CONTROL
Definition BNO08x.hpp:233
-
@ CHANNEL_EXECUTABLE
Definition BNO08x.hpp:232
-
@ CHANNEL_REPORTS
Definition BNO08x.hpp:234
-
@ CHANNEL_COMMAND
Definition BNO08x.hpp:231
-
@ CHANNEL_GYRO
Definition BNO08x.hpp:236
-
@ CHANNEL_WAKE_REPORTS
Definition BNO08x.hpp:235
-
spi_transaction_t spi_transaction
SPI transaction handle.
Definition BNO08x.hpp:386
-
bool mode_on()
Turns on/ brings BNO08x sensor out of sleep mode using executable channel.
Definition BNO08x.cpp:866
-
void get_raw_mems_gyro(uint16_t &x, uint16_t &y, uint16_t &z)
Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:3225
-
void calibrate_magnetometer()
Sends command to calibrate magnetometer.
Definition BNO08x.cpp:1224
-
static const constexpr EventBits_t EVT_GRP_RPT_RAW_MAGNETOMETER_BIT
When set, raw magnetometer reports are active.
Definition BNO08x.hpp:471
-
uint16_t mems_raw_gyro_Z
Raw gyro readings from MEMS sensor (See SH-2 Ref. Manual 6.5.12)
Definition BNO08x.hpp:416
-
uint16_t raw_bias_Y
Definition BNO08x.hpp:403
-
EventGroupHandle_t evt_grp_task_flow
Event group for indicating when tasks should complete and self-delete (on deconstructor call)
Definition BNO08x.hpp:371
-
uint16_t magf_accuracy
Calibrated magnetic field reading in uTesla (See SH-2 Ref. Manual 6.5.16)
Definition BNO08x.hpp:406
-
void update_tap_detector_data(bno08x_rx_packet_t *packet)
Updates tap detector data from parsed input report.
Definition BNO08x.cpp:2146
-
void end_calibration()
Sends command to end calibration procedure.
Definition BNO08x.cpp:1327
-
esp_err_t receive_packet_header(bno08x_rx_packet_t *packet)
Receives a SHTP packet header via SPI.
Definition BNO08x.cpp:955
-
static const constexpr uint8_t SENSOR_REPORT_ID_UNCALIBRATED_GYRO
See SH2 Ref. Manual 6.5.14.
Definition BNO08x.hpp:522
-
spi_device_handle_t spi_hdl
SPI device handle.
Definition BNO08x.hpp:385
-
uint16_t raw_uncalib_gyro_Y
Definition BNO08x.hpp:403
-
static const constexpr uint8_t SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.44.
Definition BNO08x.hpp:525
-
uint16_t raw_magf_Y
Definition BNO08x.hpp:405
-
static const constexpr uint8_t CALIBRATE_ACCEL
Calibrate accelerometer command used by queue_calibrate_command.
Definition BNO08x.hpp:485
-
static const constexpr uint8_t SENSOR_REPORT_ID_LINEAR_ACCELERATION
See SH2 Ref. Manual 6.5.10.
Definition BNO08x.hpp:519
-
static const constexpr uint8_t SHTP_REPORT_GET_FEATURE_RESPONSE
See SH2 Ref. Manual 6.5.5.
Definition BNO08x.hpp:513
-
void queue_calibrate_command(uint8_t _to_calibrate)
Queues a packet containing a command to calibrate the specified sensor.
Definition BNO08x.cpp:1250
-
esp_err_t init_gpio_outputs()
Initializes required gpio outputs.
Definition BNO08x.cpp:255
-
static const constexpr int16_t LINEAR_ACCELEROMETER_Q1
Linear acceleration Q point (See SH-2 Ref. Manual 6.5.10)
Definition BNO08x.hpp:221
-
void update_raw_gyro_data(uint16_t *data)
Updates raw gyro data from parsed input report.
Definition BNO08x.cpp:2118
-
uint16_t integrated_gyro_velocity_Z
Raw gyro angular velocity reading from integrated gyro rotation vector (See SH-2 Ref....
Definition BNO08x.hpp:400
-
BNO08x(bno08x_config_t imu_config=bno08x_config_t())
BNO08x imu constructor.
Definition BNO08x.cpp:12
-
uint8_t calibration_status
Calibration status of device (See SH-2 Ref. Manual 6.4.7.1 & 6.4.7.2)
Definition BNO08x.hpp:412
-
float get_uncalibrated_gyro_bias_X()
Get uncalibrated gyro x axis drift estimate.
Definition BNO08x.cpp:3412
-
void disable_accelerometer()
Sends command to disable accelerometer reports by setting report interval to 0.
Definition BNO08x.cpp:2474
-
void update_gravity_data(uint16_t *data, uint8_t status)
Updates gravity data from parsed input report.
Definition BNO08x.cpp:2056
-
static const constexpr uint16_t FRS_RECORD_ID_ACCELEROMETER
Accelerometer record ID, to be passed in metadata functions like get_Q1()
Definition BNO08x.hpp:198
-
uint16_t step_count
Step counter reading (See SH-2 Ref. Manual 6.5.29)
Definition BNO08x.hpp:408
-
uint16_t mems_raw_accel_Y
Definition BNO08x.hpp:413
-
uint16_t get_raw_mems_magf_Y()
Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:3293
-
uint32_t get_time_stamp()
Return timestamp of most recent report.
Definition BNO08x.cpp:2660
-
static const constexpr EventBits_t EVT_GRP_RPT_LINEAR_ACCELEROMETER_BIT
When set, linear accelerometer reports are active.
Definition BNO08x.hpp:460
-
static const constexpr uint8_t SENSOR_REPORT_ID_GAME_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.19.
Definition BNO08x.hpp:523
-
uint16_t get_step_count()
Get the counted amount of steps.
Definition BNO08x.cpp:3498
-
static const constexpr EventBits_t EVT_GRP_SPI_TX_DONE_BIT
When this bit is set, it indicates a queued packet has been sent.
Definition BNO08x.hpp:448
-
bool FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size)
Requests meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and o...
Definition BNO08x.cpp:3719
-
uint16_t gravity_accuracy
Gravity reading in m/s^2 (See SH-2 Ref. Manual 6.5.11)
Definition BNO08x.hpp:402
-
esp_err_t init_gpio()
Initializes required gpio.
Definition BNO08x.cpp:293
-
static const constexpr int16_t GRAVITY_Q1
Gravity Q point (See SH-2 Ref. Manual 6.5.11)
Definition BNO08x.hpp:225
-
void enable_linear_accelerometer(uint32_t time_between_reports)
Sends command to enable linear accelerometer reports (See Ref. Manual 6.5.10)
Definition BNO08x.cpp:2289
-
uint16_t raw_lin_accel_X
Definition BNO08x.hpp:394
-
uint8_t current_slowest_report_ID
ID of the currently enabled report with the largest sample period.
Definition BNO08x.hpp:555
-
bno08x_report_period_tracker_t report_period_trackers[REPORT_CNT]
Current sample period of each report in microseconds linked to report ID (0 if not enabled).
Definition BNO08x.hpp:543
-
static const constexpr uint8_t SHTP_REPORT_BASE_TIMESTAMP
See SH2 Ref. Manual 7.2.1.
Definition BNO08x.hpp:511
-
bool first_boot
true only for first execution of hard_reset(), used to suppress the printing of product ID report.
Definition BNO08x.hpp:348
-
static const constexpr TickType_t HOST_INT_TIMEOUT_DEFAULT_MS
Max wait between HINT being asserted by BNO08x before transaction is considered failed (in milisecond...
Definition BNO08x.hpp:427
-
uint16_t get_raw_mems_gyro_Z()
Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:3257
-
bool run_full_calibration_routine()
Runs full calibration routine.
Definition BNO08x.cpp:1358
-
void get_magf(float &x, float &y, float &z, BNO08xAccuracy &accuracy)
Get the full magnetic field vector.
Definition BNO08x.cpp:2745
-
struct BNO08x::bno08x_report_period_tracker_t bno08x_report_period_tracker_t
-
bool initialize()
Initializes BNO08x sensor.
Definition BNO08x.cpp:74
-
static const constexpr uint8_t CALIBRATE_GYRO
Calibrate gyro command used by queue_calibrate_command.
Definition BNO08x.hpp:486
-
static const constexpr uint8_t SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.43.
Definition BNO08x.hpp:534
-
static const constexpr uint8_t SHTP_REPORT_FRS_READ_RESPONSE
See SH2 Ref. Manual 6.3.7.
Definition BNO08x.hpp:507
-
uint16_t get_raw_mems_accel_Y()
Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref....
Definition BNO08x.cpp:3201
-
static const constexpr uint8_t TARE_AXIS_Z
Tar yaw axis only (used with tare now command)
Definition BNO08x.hpp:208
-
bno08x_config_t imu_config
IMU configuration settings.
Definition BNO08x.hpp:382
-
void calibrate_accelerometer()
Sends command to calibrate accelerometer.
Definition BNO08x.cpp:1200
-
static const constexpr uint8_t COMMAND_DCD
Save DCD command (See SH2 Ref. Manual 6.4.7)
Definition BNO08x.hpp:498
-
uint16_t gravity_Y
Definition BNO08x.hpp:401
-
uint16_t raw_accel_Z
Definition BNO08x.hpp:392
-
uint16_t gravity_X
Definition BNO08x.hpp:401
-
float get_pitch_deg()
Get the reported rotation about y axis.
Definition BNO08x.cpp:2952
-
static const constexpr uint8_t CALIBRATE_ACCEL_GYRO_MAG
Calibrate accelerometer, gyro, & magnetometer command used by queue_calibrate_command.
Definition BNO08x.hpp:489
-
uint16_t raw_calib_gyro_Z
Raw gyro reading (See SH-2 Ref. Manual 6.5.13)
Definition BNO08x.hpp:396
-
void get_quat(float &i, float &j, float &k, float &real, float &rad_accuracy, BNO08xAccuracy &accuracy)
Get the full quaternion reading.
Definition BNO08x.cpp:2979
-
void queue_feature_command(uint8_t report_ID, uint32_t time_between_reports, uint32_t specific_config=0)
Queues a packet containing a command with a request for sensor reports, reported periodically....
Definition BNO08x.cpp:3815
-
float get_yaw_deg()
Get the reported rotation about z axis.
Definition BNO08x.cpp:2962
-
static const constexpr EventBits_t EVT_GRP_RPT_GYRO_UNCALIBRATED_BIT
When set, uncalibrated gyro reports are active.
Definition BNO08x.hpp:463
-
uint8_t * activity_confidences
Confidence of read activities (See SH-2 Ref. Manual 6.5.36)
Definition BNO08x.hpp:411
-
void update_command_data(bno08x_rx_packet_t *packet)
Updates command data from parsed input report.
Definition BNO08x.cpp:2188
-
TaskHandle_t data_proc_task_hdl
data_proc_task() task handle
Definition BNO08x.hpp:356
-
uint16_t gravity_Z
Definition BNO08x.hpp:401
-
uint16_t raw_uncalib_gyro_Z
Definition BNO08x.hpp:403
-
void save_tare()
Sends command to save tare into non-volatile memory of BNO08x (See Ref. Manual 6.4....
Definition BNO08x.cpp:2620
-
void disable_linear_accelerometer()
Sends command to disable linear accelerometer reports by setting report interval to 0.
Definition BNO08x.cpp:2484
-
void calibrate_all()
Sends command to calibrate accelerometer, gyro, and magnetometer.
Definition BNO08x.cpp:1188
-
uint16_t raw_uncalib_gyro_X
Definition BNO08x.hpp:403
-
float get_accel_Y()
Get y axis acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:3087
-
float get_linear_accel_Z()
Get z axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
Definition BNO08x.cpp:3155
-
void clear_tare()
Sends command to clear persistent tare settings in non-volatile memory of BNO08x (See Ref....
Definition BNO08x.cpp:2632
-
void update_accelerometer_data(uint16_t *data, uint8_t status)
Updates accelerometer data from parsed input report.
Definition BNO08x.cpp:1975
-
uint16_t raw_lin_accel_Y
Definition BNO08x.hpp:394
-
float get_integrated_gyro_velocity_Y()
Get y axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6....
Definition BNO08x.cpp:3468
-
void request_calibration_status()
Requests ME calibration status from BNO08x (see Ref. Manual 6.4.7.2)
Definition BNO08x.cpp:1297
-
BNO08x unit test helper class.
Definition BNO08xTestHelper.hpp:16
-
Holds info about which functionality has been successfully initialized (used by deconstructor during ...
Definition BNO08x.hpp:262
-
bool data_proc_task
True if xTaskCreate has been called successfully for data_proc_task.
Definition BNO08x.hpp:268
-
bno08x_init_status_t()
Definition BNO08x.hpp:273
-
bool isr_service
True if global ISR service has been initialized.
Definition BNO08x.hpp:265
-
uint8_t task_count
How many successfully initialized tasks (max of TSK_CNT)
Definition BNO08x.hpp:267
-
bool gpio_inputs
True if GPIO inputs have been initialized.
Definition BNO08x.hpp:264
-
bool gpio_outputs
True if GPIO outputs have been initialized.
Definition BNO08x.hpp:263
-
bool spi_task
True if xTaskCreate has been called successfully for spi_task.
Definition BNO08x.hpp:269
-
bool spi_bus
True if spi_bus_initialize() has been called successfully.
Definition BNO08x.hpp:270
-
bool isr_handler
True if HINT ISR handler has been initialized.
Definition BNO08x.hpp:266
-
bool spi_device
True if spi_bus_add_device() has been called successfully.
Definition BNO08x.hpp:271
- -
uint8_t report_ID
Definition BNO08x.hpp:256
-
uint32_t period
Definition BNO08x.hpp:257
-
Holds data that is received over spi.
Definition BNO08x.hpp:241
-
uint16_t length
Body of SHTP packet.
Definition BNO08x.hpp:244
-
uint8_t header[4]
Header of SHTP packet.
Definition BNO08x.hpp:242
-
uint8_t body[300]
Definition BNO08x.hpp:243
-
Holds data that is sent over spi.
Definition BNO08x.hpp:249
-
uint8_t body[50]
Body of SHTP the packet (header + body)
Definition BNO08x.hpp:250
-
uint16_t length
Packet length in bytes.
Definition BNO08x.hpp:251
-
IMU configuration settings passed into constructor.
Definition BNO08x_global_types.hpp:74
-
-
- - - - diff --git a/documentation/html/_b_n_o08x__global__types_8hpp.html b/documentation/html/_b_n_o08x__global__types_8hpp.html deleted file mode 100644 index ea6ddcf..0000000 --- a/documentation/html/_b_n_o08x__global__types_8hpp.html +++ /dev/null @@ -1,469 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08x_global_types.hpp File Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
- -
BNO08x_global_types.hpp File Reference
-
-
-
#include <driver/gpio.h>
-#include <driver/spi_common.h>
-#include <driver/spi_master.h>
-
-Include dependency graph for BNO08x_global_types.hpp:
-
-
- - - - - - - - - -
-
-This graph shows which files directly or indirectly include this file:
-
-
- - - - - - - - - - - - - - - - - - - -
-
-

Go to the source code of this file.

- - - - - -

-Classes

struct  bno08x_config_t
 IMU configuration settings passed into constructor. More...
 
- - - - - - - - - - -

-Typedefs

using IMUAccuracy = BNO08xAccuracy
 
using IMUResetReason = BNO08xResetReason
 
typedef struct bno08x_config_t bno08x_config_t
 IMU configuration settings passed into constructor.
 
typedef bno08x_config_t imu_config_t
 
- - - - - - - - - - - - - - - - -

-Enumerations

enum class  BNO08xAccuracy { LOW = 1 -, MED -, HIGH -, UNDEFINED - }
 Sensor accuracy returned during sensor calibration. More...
 
enum class  BNO08xResetReason {
-  UNDEFINED -, POR -, INT_RST -, WTD -,
-  EXT_RST -, OTHER -
- }
 Reason for previous IMU reset (returned by get_reset_reason()) More...
 
enum class  BNO08xActivityEnable {
-  UNKNOWN = (1U << 0U) -, IN_VEHICLE = (1U << 1U) -, ON_BICYCLE = (1U << 2U) -, ON_FOOT = (1U << 3U) -,
-  STILL = (1U << 4U) -, TILTING = (1U << 5U) -, WALKING = (1U << 6U) -, RUNNING = (1U << 7U) -,
-  ON_STAIRS = (1U << 8U) -, ALL = 0x1FU -
- }
 BNO08xActivity Classifier enable bits passed to enable_activity_classifier() More...
 
enum class  BNO08xActivity {
-  UNKNOWN = 0 -, IN_VEHICLE = 1 -, ON_BICYCLE = 2 -, ON_FOOT = 3 -,
-  STILL = 4 -, TILTING = 5 -, WALKING = 6 -, RUNNING = 7 -,
-  ON_STAIRS = 8 -, UNDEFINED = 9 -
- }
 BNO08xActivity states returned from get_activity_classifier() More...
 
enum class  BNO08xStability { UNKNOWN = 0 -, ON_TABLE = 1 -, STATIONARY = 2 -, UNDEFINED = 3 - }
 BNO08xStability states returned from get_stability_classifier() More...
 
-

Detailed Description

-
Author
Myles Parfeniuk
-

Typedef Documentation

- -

◆ bno08x_config_t

- -
-
- - - - -
typedef struct bno08x_config_t bno08x_config_t
-
- -

IMU configuration settings passed into constructor.

- -
-
- -

◆ imu_config_t

- -
-
- - - - -
typedef bno08x_config_t imu_config_t
-
- -
-
- -

◆ IMUAccuracy

- -
-
- - - - -
using IMUAccuracy = BNO08xAccuracy
-
- -
-
- -

◆ IMUResetReason

- -
-
- - - - -
using IMUResetReason = BNO08xResetReason
-
- -
-
-

Enumeration Type Documentation

- -

◆ BNO08xAccuracy

- -
-
- - - - - -
- - - - -
enum class BNO08xAccuracy
-
-strong
-
- -

Sensor accuracy returned during sensor calibration.

- - - - - -
Enumerator
LOW 
MED 
HIGH 
UNDEFINED 
- -
-
- -

◆ BNO08xActivity

- -
-
- - - - - -
- - - - -
enum class BNO08xActivity
-
-strong
-
- -

BNO08xActivity states returned from get_activity_classifier()

- - - - - - - - - - - -
Enumerator
UNKNOWN 
IN_VEHICLE 
ON_BICYCLE 
ON_FOOT 
STILL 
TILTING 
WALKING 
RUNNING 
ON_STAIRS 
UNDEFINED 
- -
-
- -

◆ BNO08xActivityEnable

- -
-
- - - - - -
- - - - -
enum class BNO08xActivityEnable
-
-strong
-
- -

BNO08xActivity Classifier enable bits passed to enable_activity_classifier()

- - - - - - - - - - - -
Enumerator
UNKNOWN 
IN_VEHICLE 
ON_BICYCLE 
ON_FOOT 
STILL 
TILTING 
WALKING 
RUNNING 
ON_STAIRS 
ALL 
- -
-
- -

◆ BNO08xResetReason

- -
-
- - - - - -
- - - - -
enum class BNO08xResetReason
-
-strong
-
- -

Reason for previous IMU reset (returned by get_reset_reason())

- - - - - - - -
Enumerator
UNDEFINED 

Undefined reset reason, this should never occur and is an error.

-
POR 

Previous reset was due to power on reset.

-
INT_RST 

Previous reset was due to internal reset.

-
WTD 

Previous reset was due to watchdog timer.

-
EXT_RST 

Previous reset was due to external reset.

-
OTHER 

Previous reset was due to power other reason.

-
- -
-
- -

◆ BNO08xStability

- -
-
- - - - - -
- - - - -
enum class BNO08xStability
-
-strong
-
- -

BNO08xStability states returned from get_stability_classifier()

- - - - - -
Enumerator
UNKNOWN 
ON_TABLE 
STATIONARY 
UNDEFINED 
- -
-
-
-
- - - - diff --git a/documentation/html/_b_n_o08x__global__types_8hpp.js b/documentation/html/_b_n_o08x__global__types_8hpp.js deleted file mode 100644 index e171b24..0000000 --- a/documentation/html/_b_n_o08x__global__types_8hpp.js +++ /dev/null @@ -1,52 +0,0 @@ -var _b_n_o08x__global__types_8hpp = -[ - [ "bno08x_config_t", "structbno08x__config__t.html", "structbno08x__config__t" ], - [ "bno08x_config_t", "_b_n_o08x__global__types_8hpp.html#a648bbdbf22731476890dd8da977d7503", null ], - [ "imu_config_t", "_b_n_o08x__global__types_8hpp.html#aae502b3d91ddf903bba797646fd28d00", null ], - [ "IMUAccuracy", "_b_n_o08x__global__types_8hpp.html#a03fbbd71180a19088ce30d57ab050a22", null ], - [ "IMUResetReason", "_b_n_o08x__global__types_8hpp.html#aeee029e15be2a7d6d8134cabcc7c752b", null ], - [ "BNO08xAccuracy", "_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0", [ - [ "LOW", "_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88", null ], - [ "MED", "_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c", null ], - [ "HIGH", "_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c", null ], - [ "UNDEFINED", "_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3", null ] - ] ], - [ "BNO08xActivity", "_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187", [ - [ "UNKNOWN", "_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3", null ], - [ "IN_VEHICLE", "_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4", null ], - [ "ON_BICYCLE", "_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4", null ], - [ "ON_FOOT", "_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58", null ], - [ "STILL", "_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6", null ], - [ "TILTING", "_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c", null ], - [ "WALKING", "_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3", null ], - [ "RUNNING", "_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd", null ], - [ "ON_STAIRS", "_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515", null ], - [ "UNDEFINED", "_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3", null ] - ] ], - [ "BNO08xActivityEnable", "_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0f", [ - [ "UNKNOWN", "_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3", null ], - [ "IN_VEHICLE", "_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4", null ], - [ "ON_BICYCLE", "_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4", null ], - [ "ON_FOOT", "_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58", null ], - [ "STILL", "_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6", null ], - [ "TILTING", "_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c", null ], - [ "WALKING", "_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3", null ], - [ "RUNNING", "_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd", null ], - [ "ON_STAIRS", "_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515", null ], - [ "ALL", "_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d", null ] - ] ], - [ "BNO08xResetReason", "_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147", [ - [ "UNDEFINED", "_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a0db45d2a4141101bdfe48e3314cfbca3", null ], - [ "POR", "_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92", null ], - [ "INT_RST", "_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f", null ], - [ "WTD", "_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36", null ], - [ "EXT_RST", "_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5", null ], - [ "OTHER", "_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb", null ] - ] ], - [ "BNO08xStability", "_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5", [ - [ "UNKNOWN", "_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3", null ], - [ "ON_TABLE", "_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a", null ], - [ "STATIONARY", "_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146", null ], - [ "UNDEFINED", "_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3", null ] - ] ] -]; \ No newline at end of file diff --git a/documentation/html/_b_n_o08x__global__types_8hpp__dep__incl.map b/documentation/html/_b_n_o08x__global__types_8hpp__dep__incl.map deleted file mode 100644 index eaf5c22..0000000 --- a/documentation/html/_b_n_o08x__global__types_8hpp__dep__incl.map +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_b_n_o08x__global__types_8hpp__dep__incl.md5 b/documentation/html/_b_n_o08x__global__types_8hpp__dep__incl.md5 deleted file mode 100644 index c5c51ce..0000000 --- a/documentation/html/_b_n_o08x__global__types_8hpp__dep__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -e110ea5e0b3c2b55f8b0b5c728e78d3c \ No newline at end of file diff --git a/documentation/html/_b_n_o08x__global__types_8hpp__dep__incl.png b/documentation/html/_b_n_o08x__global__types_8hpp__dep__incl.png deleted file mode 100644 index 1a372fc..0000000 Binary files a/documentation/html/_b_n_o08x__global__types_8hpp__dep__incl.png and /dev/null differ diff --git a/documentation/html/_b_n_o08x__global__types_8hpp__incl.map b/documentation/html/_b_n_o08x__global__types_8hpp__incl.map deleted file mode 100644 index 42a18f5..0000000 --- a/documentation/html/_b_n_o08x__global__types_8hpp__incl.map +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/_b_n_o08x__global__types_8hpp__incl.md5 b/documentation/html/_b_n_o08x__global__types_8hpp__incl.md5 deleted file mode 100644 index 567ddb9..0000000 --- a/documentation/html/_b_n_o08x__global__types_8hpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -6307718186d33aeef219aebf20b375cb \ No newline at end of file diff --git a/documentation/html/_b_n_o08x__global__types_8hpp__incl.png b/documentation/html/_b_n_o08x__global__types_8hpp__incl.png deleted file mode 100644 index 46d37f6..0000000 Binary files a/documentation/html/_b_n_o08x__global__types_8hpp__incl.png and /dev/null differ diff --git a/documentation/html/_b_n_o08x__global__types_8hpp_source.html b/documentation/html/_b_n_o08x__global__types_8hpp_source.html deleted file mode 100644 index b4341de..0000000 --- a/documentation/html/_b_n_o08x__global__types_8hpp_source.html +++ /dev/null @@ -1,278 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08x_global_types.hpp Source File - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
BNO08x_global_types.hpp
-
-
-Go to the documentation of this file.
1
-
5#pragma once
-
6
-
7#include <driver/gpio.h>
-
8#include <driver/spi_common.h>
-
9#include <driver/spi_master.h>
-
10
-
- -
13{
-
14 LOW = 1,
-
15 MED,
-
16 HIGH,
- -
18};
-
-
19using IMUAccuracy = BNO08xAccuracy; // legacy version compatibility
-
20
-
- -
23{
-
24 UNDEFINED,
-
25 POR,
-
26 INT_RST,
-
27 WTD,
-
28 EXT_RST,
-
29 OTHER
-
30};
-
-
31using IMUResetReason = BNO08xResetReason; // legacy version compatibility
-
32
-
- -
35{
-
36 UNKNOWN = (1U << 0U),
-
37 IN_VEHICLE = (1U << 1U),
-
38 ON_BICYCLE = (1U << 2U),
-
39 ON_FOOT = (1U << 3U),
-
40 STILL = (1U << 4U),
-
41 TILTING = (1U << 5U),
-
42 WALKING = (1U << 6U),
-
43 RUNNING = (1U << 7U),
-
44 ON_STAIRS = (1U << 8U),
-
45 ALL = 0x1FU
-
46};
-
-
47
-
- -
50{
-
51 UNKNOWN = 0, // 0 = unknown
-
52 IN_VEHICLE = 1, // 1 = in vehicle
-
53 ON_BICYCLE = 2, // 2 = on bicycle
-
54 ON_FOOT = 3, // 3 = on foot
-
55 STILL = 4, // 4 = still
-
56 TILTING = 5, // 5 = tilting
-
57 WALKING = 6, // 6 = walking
-
58 RUNNING = 7, // 7 = running
-
59 ON_STAIRS = 8, // 8 = on stairs
-
60 UNDEFINED = 9 // used for unit tests
-
61};
-
-
62
-
- -
65{
-
66 UNKNOWN = 0, // 0 = unknown
-
67 ON_TABLE = 1, // 1 = on table
-
68 STATIONARY = 2, // 2 = stationary
-
69 UNDEFINED = 3 // used for unit tests
-
70};
-
-
71
-
-
73typedef struct bno08x_config_t
-
74{
-
75 spi_host_device_t spi_peripheral;
-
76 gpio_num_t io_mosi;
-
77 gpio_num_t io_miso;
-
78 gpio_num_t io_sclk;
-
79 gpio_num_t io_cs;
-
80 gpio_num_t io_int;
-
81 gpio_num_t io_rst;
-
82 gpio_num_t io_wake;
-
83 uint32_t sclk_speed;
- -
85
-
- -
90 : spi_peripheral((spi_host_device_t) CONFIG_ESP32_BNO08x_SPI_HOST)
-
91 , io_mosi(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_DI)) // default: 23
-
92 , io_miso(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_SDA)) // default: 19
-
93 , io_sclk(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_SCL)) // default: 18
-
94 , io_cs(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_CS)) // default: 33
-
95 , io_int(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_HINT)) // default: 26
-
96 , io_rst(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_RST)) // default: 32
-
97 , io_wake(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_WAKE)) // default: -1 (unused)
-
98 , sclk_speed(static_cast<uint32_t>(CONFIG_ESP32_BNO08X_SCL_SPEED_HZ)) // default: 2MHz
- -
100
-
101 {
-
102 }
-
-
103
-
-
105 bno08x_config_t(spi_host_device_t spi_peripheral, gpio_num_t io_mosi, gpio_num_t io_miso, gpio_num_t io_sclk, gpio_num_t io_cs,
-
106 gpio_num_t io_int, gpio_num_t io_rst, gpio_num_t io_wake, uint32_t sclk_speed, bool install_isr_service = true)
- - - - -
111 , io_cs(io_cs)
-
112 , io_int(io_int)
-
113 , io_rst(io_rst)
- - - -
117 {
-
118 }
-
- -
-
120
-
121typedef bno08x_config_t imu_config_t; // legacy version compatibility
-
BNO08xStability
BNO08xStability states returned from get_stability_classifier()
Definition BNO08x_global_types.hpp:65
- - -
struct bno08x_config_t bno08x_config_t
IMU configuration settings passed into constructor.
-
bno08x_config_t imu_config_t
Definition BNO08x_global_types.hpp:121
-
BNO08xResetReason
Reason for previous IMU reset (returned by get_reset_reason())
Definition BNO08x_global_types.hpp:23
-
@ OTHER
Previous reset was due to power other reason.
-
@ WTD
Previous reset was due to watchdog timer.
-
@ POR
Previous reset was due to power on reset.
-
@ EXT_RST
Previous reset was due to external reset.
-
@ INT_RST
Previous reset was due to internal reset.
-
BNO08xActivity
BNO08xActivity states returned from get_activity_classifier()
Definition BNO08x_global_types.hpp:50
-
BNO08xActivityEnable
BNO08xActivity Classifier enable bits passed to enable_activity_classifier()
Definition BNO08x_global_types.hpp:35
- - - - - - - - - - -
BNO08xAccuracy
Sensor accuracy returned during sensor calibration.
Definition BNO08x_global_types.hpp:13
- - - - -
IMU configuration settings passed into constructor.
Definition BNO08x_global_types.hpp:74
-
spi_host_device_t spi_peripheral
SPI peripheral to be used.
Definition BNO08x_global_types.hpp:75
-
bool install_isr_service
Indicates whether the ISR service for the HINT should be installed at IMU initialization,...
Definition BNO08x_global_types.hpp:84
-
uint32_t sclk_speed
Desired SPI SCLK speed in Hz (max 3MHz)
Definition BNO08x_global_types.hpp:83
-
bno08x_config_t(spi_host_device_t spi_peripheral, gpio_num_t io_mosi, gpio_num_t io_miso, gpio_num_t io_sclk, gpio_num_t io_cs, gpio_num_t io_int, gpio_num_t io_rst, gpio_num_t io_wake, uint32_t sclk_speed, bool install_isr_service=true)
Overloaded IMU configuration settings constructor for custom pin settings.
Definition BNO08x_global_types.hpp:105
-
gpio_num_t io_int
Chip select pin (connects to BNO08x CS pin)
Definition BNO08x_global_types.hpp:80
-
gpio_num_t io_rst
Host interrupt pin (connects to BNO08x INT pin)
Definition BNO08x_global_types.hpp:81
-
gpio_num_t io_sclk
SCLK pin (connects to BNO08x SCL pin)
Definition BNO08x_global_types.hpp:78
-
bno08x_config_t(bool install_isr_service=true)
Default IMU configuration settings constructor. To modify default GPIO pins, run "idf....
Definition BNO08x_global_types.hpp:89
-
gpio_num_t io_mosi
MOSI GPIO pin (connects to BNO08x DI pin)
Definition BNO08x_global_types.hpp:76
-
gpio_num_t io_wake
Reset pin (connects to BNO08x RST pin)
Definition BNO08x_global_types.hpp:82
-
gpio_num_t io_miso
MISO GPIO pin (connects to BNO08x SDA pin)
Definition BNO08x_global_types.hpp:77
-
gpio_num_t io_cs
Definition BNO08x_global_types.hpp:79
-
-
- - - - diff --git a/documentation/html/_b_n_o08x__macros_8hpp.html b/documentation/html/_b_n_o08x__macros_8hpp.html deleted file mode 100644 index c390e7c..0000000 --- a/documentation/html/_b_n_o08x__macros_8hpp.html +++ /dev/null @@ -1,1134 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08x_macros.hpp File Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
- -
BNO08x_macros.hpp File Reference
-
-
-
#include <inttypes.h>
-#include <freertos/FreeRTOS.h>
-#include <freertos/event_groups.h>
-
-Include dependency graph for BNO08x_macros.hpp:
-
-
- - - - - - - - - -
-
-This graph shows which files directly or indirectly include this file:
-
-
- - - - - -
-
-

Go to the source code of this file.

- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

-Macros

#define CHECK_TASKS_RUNNING(evt_grp_task_flow, running_bit)   ((xEventGroupGetBits(evt_grp_task_flow) & (running_bit)) != 0)
 Clears the most significant byte of a 16-bit value.
 
#define UINT16_CLR_MSB(val_16bit)   ((val_16bit) & 0x00FFU)
 Clears the most significant byte of a 16-bit value.
 
#define UINT16_CLR_LSB(val_16bit)   ((val_16bit) & 0xFF00U)
 Clears the least significant byte of a 16-bit value.
 
#define UINT32_CLR_BYTE(val_32bit, byte2clear)   ((val_32bit) & ~(0xFFUL << (byte2clear * 8UL)))
 Clears a specified byte in a 32-bit value.
 
#define UINT32_MSK_BYTE(val_32bit, byte2mask)   ((val_32bit) & (0xFFUL << (byte2mask * 8UL)))
 Masks a specified byte in a 32-bit value.
 
#define PARSE_PACKET_LENGTH(packet_ptr)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet_ptr->header[1]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet_ptr->header[0])))
 Parse length from SHTP packet header.
 
#define PARSE_PACKET_TIMESTAMP(packet_ptr)
 Parse timestamp from SHTP packet.
 
#define PARSE_PRODUCT_ID_REPORT_RESET_REASON(packet_ptr)   UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[1]), 0UL)
 Parse reset reason from SHTP packet containing product ID report.
 
#define PARSE_PRODUCT_ID_REPORT_SW_PART_NO(packet_ptr)
 Parse sw part number from SHTP packet containing product ID report.
 
#define PARSE_PRODUCT_ID_REPORT_SW_BUILD_NO(packet_ptr)
 Parse sw build number from SHTP packet containing product ID report.
 
#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_PATCH(packet_ptr)    (UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[13]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[12]), 0UL))
 Parse sw version patch from SHTP packet containing product ID report.
 
#define PARSE_PRODUCT_ID_REPORT_PRODUCT_ID(packet_ptr)   UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[0]), 0UL)
 Parse product ID SHTP packet containing product ID report.
 
#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_MAJOR(packet_ptr)   UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[2]), 0UL)
 Parse product sw version major containing product ID report.
 
#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_MINOR(packet_ptr)   UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[3]), 0UL)
 Parse product sw version minor containing product ID report.
 
#define PARSE_GYRO_REPORT_RAW_QUAT_I(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[1]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[0])))
 Parse quat I data from integrated gyro rotation vector report.
 
#define PARSE_GYRO_REPORT_RAW_QUAT_J(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[3]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[2])))
 Parse quat J data from integrated gyro rotation vector report.
 
#define PARSE_GYRO_REPORT_RAW_QUAT_K(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[4])))
 Parse quat K data from integrated gyro rotation vector report.
 
#define PARSE_GYRO_REPORT_RAW_QUAT_REAL(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[7]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[6])))
 Parse quat real data from integrated gyro rotation vector report.
 
#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_X(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[9]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[8])))
 Parse x axis velocity data from integrated gyro rotation vector report.
 
#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_Y(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[11]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[10])))
 Parse y axis velocity data from integrated gyro rotation vector report.
 
#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_Z(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[13]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[12])))
 Parse z axis velocity data from integrated gyro rotation vector report.
 
#define PARSE_INPUT_REPORT_STATUS_BITS(packet)   (packet->body[5 + 2] & 0x03U)
 Parse status bits from input report.
 
#define PARSE_INPUT_REPORT_REPORT_ID(packet)   UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5]))
 Parse report ID from input report.
 
#define PARSE_INPUT_REPORT_DATA_1(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 5]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 4])))
 Parse first data block from input report.
 
#define PARSE_INPUT_REPORT_DATA_2(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 7]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 6])))
 Parse second data block from input report.
 
#define PARSE_INPUT_REPORT_DATA_3(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 9]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 8])))
 Parse third data block from input report.
 
#define PARSE_INPUT_REPORT_DATA_4(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 11]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 10])))
 Parse fourth data block from input report.
 
#define PARSE_INPUT_REPORT_DATA_5(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 13]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 12])))
 Parse fifth data block from input report.
 
#define PARSE_INPUT_REPORT_DATA_6(packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 15]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 14])))
 Parse sixth data block from input report.
 
#define IS_ROTATION_VECTOR_REPORT(packet)
 Checks if packet containing input report is a rotation vector report.
 
#define PARSE_FRS_READ_RESPONSE_REPORT_RECORD_ID(packet_body)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet_body[13]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet_body[12])))
 Parse FRS record ID from FRS read response report.
 
#define PARSE_FRS_READ_RESPONSE_REPORT_DATA_1(packet_body)
 Parse data block 1 from FRS read response report.
 
#define PARSE_FRS_READ_RESPONSE_REPORT_DATA_2(packet_body)
 Parse data block 2 from FRS read response report.
 
-

Detailed Description

-
Author
Myles Parfeniuk
-

Macro Definition Documentation

- -

◆ CHECK_TASKS_RUNNING

- -
-
- - - - - - - - - - - -
#define CHECK_TASKS_RUNNING( evt_grp_task_flow,
running_bit )   ((xEventGroupGetBits(evt_grp_task_flow) & (running_bit)) != 0)
-
- -

Clears the most significant byte of a 16-bit value.

-
Parameters
- - - -
evt_grp_task_flowTask flow event group handle.
running_bitEVT_GRP_TSK_FLW_RUNNING_BIT
-
-
-
Returns
The value with the MSB cleared.
- -
-
- -

◆ IS_ROTATION_VECTOR_REPORT

- -
-
- - - - - - - -
#define IS_ROTATION_VECTOR_REPORT( packet)
-
-Value:
((packet)->body[5] == SENSOR_REPORT_ID_ROTATION_VECTOR || (packet)->body[5] == SENSOR_REPORT_ID_GAME_ROTATION_VECTOR || \
-
(packet)->body[5] == SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR || \
-
(packet)->body[5] == SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR)
-
-

Checks if packet containing input report is a rotation vector report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
True if contained input report is rotation vector report.
- -
-
- -

◆ PARSE_FRS_READ_RESPONSE_REPORT_DATA_1

- -
-
- - - - - - - -
#define PARSE_FRS_READ_RESPONSE_REPORT_DATA_1( packet_body)
-
-Value:
(UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[7]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[6]) << 16UL, 2UL) | \
-
UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[5]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[4]), 0UL))
-
#define UINT32_MSK_BYTE(val_32bit, byte2mask)
Masks a specified byte in a 32-bit value.
Definition BNO08x_macros.hpp:58
-
-

Parse data block 1 from FRS read response report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
FRS read response data block 1.
- -
-
- -

◆ PARSE_FRS_READ_RESPONSE_REPORT_DATA_2

- -
-
- - - - - - - -
#define PARSE_FRS_READ_RESPONSE_REPORT_DATA_2( packet_body)
-
-Value:
(UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[11]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[10]) << 16UL, 2UL) | \
-
UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[9]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[8]), 0UL))
-
-

Parse data block 2 from FRS read response report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
FRS read response data block 2.
- -
-
- -

◆ PARSE_FRS_READ_RESPONSE_REPORT_RECORD_ID

- -
-
- - - - - - - -
#define PARSE_FRS_READ_RESPONSE_REPORT_RECORD_ID( packet_body)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet_body[13]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet_body[12])))
-
- -

Parse FRS record ID from FRS read response report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
FRS record ID.
- -
-
- -

◆ PARSE_GYRO_REPORT_RAW_GYRO_VEL_X

- -
-
- - - - - - - -
#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_X( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[9]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[8])))
-
- -

Parse x axis velocity data from integrated gyro rotation vector report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
x velocity data.
- -
-
- -

◆ PARSE_GYRO_REPORT_RAW_GYRO_VEL_Y

- -
-
- - - - - - - -
#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_Y( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[11]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[10])))
-
- -

Parse y axis velocity data from integrated gyro rotation vector report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
y velocity data.
- -
-
- -

◆ PARSE_GYRO_REPORT_RAW_GYRO_VEL_Z

- -
-
- - - - - - - -
#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_Z( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[13]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[12])))
-
- -

Parse z axis velocity data from integrated gyro rotation vector report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
z velocity data.
- -
-
- -

◆ PARSE_GYRO_REPORT_RAW_QUAT_I

- -
-
- - - - - - - -
#define PARSE_GYRO_REPORT_RAW_QUAT_I( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[1]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[0])))
-
- -

Parse quat I data from integrated gyro rotation vector report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
Quat I data.
- -
-
- -

◆ PARSE_GYRO_REPORT_RAW_QUAT_J

- -
-
- - - - - - - -
#define PARSE_GYRO_REPORT_RAW_QUAT_J( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[3]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[2])))
-
- -

Parse quat J data from integrated gyro rotation vector report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
Quat J data.
- -
-
- -

◆ PARSE_GYRO_REPORT_RAW_QUAT_K

- -
-
- - - - - - - -
#define PARSE_GYRO_REPORT_RAW_QUAT_K( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[4])))
-
- -

Parse quat K data from integrated gyro rotation vector report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
Quat K data.
- -
-
- -

◆ PARSE_GYRO_REPORT_RAW_QUAT_REAL

- -
-
- - - - - - - -
#define PARSE_GYRO_REPORT_RAW_QUAT_REAL( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[7]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[6])))
-
- -

Parse quat real data from integrated gyro rotation vector report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
Quat real data.
- -
-
- -

◆ PARSE_INPUT_REPORT_DATA_1

- -
-
- - - - - - - -
#define PARSE_INPUT_REPORT_DATA_1( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 5]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 4])))
-
- -

Parse first data block from input report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
First data block of input report.
- -
-
- -

◆ PARSE_INPUT_REPORT_DATA_2

- -
-
- - - - - - - -
#define PARSE_INPUT_REPORT_DATA_2( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 7]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 6])))
-
- -

Parse second data block from input report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
Second data block of input report.
- -
-
- -

◆ PARSE_INPUT_REPORT_DATA_3

- -
-
- - - - - - - -
#define PARSE_INPUT_REPORT_DATA_3( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 9]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 8])))
-
- -

Parse third data block from input report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
third data block of input report.
- -
-
- -

◆ PARSE_INPUT_REPORT_DATA_4

- -
-
- - - - - - - -
#define PARSE_INPUT_REPORT_DATA_4( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 11]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 10])))
-
- -

Parse fourth data block from input report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
fourth data block of input report.
- -
-
- -

◆ PARSE_INPUT_REPORT_DATA_5

- -
-
- - - - - - - -
#define PARSE_INPUT_REPORT_DATA_5( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 13]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 12])))
-
- -

Parse fifth data block from input report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
fifth data block of input report.
- -
-
- -

◆ PARSE_INPUT_REPORT_DATA_6

- -
-
- - - - - - - -
#define PARSE_INPUT_REPORT_DATA_6( packet)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 15]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 14])))
-
- -

Parse sixth data block from input report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
sixth data block of input report.
- -
-
- -

◆ PARSE_INPUT_REPORT_REPORT_ID

- -
-
- - - - - - - -
#define PARSE_INPUT_REPORT_REPORT_ID( packet)   UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5]))
-
- -

Parse report ID from input report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
Report ID.
- -
-
- -

◆ PARSE_INPUT_REPORT_STATUS_BITS

- -
-
- - - - - - - -
#define PARSE_INPUT_REPORT_STATUS_BITS( packet)   (packet->body[5 + 2] & 0x03U)
-
- -

Parse status bits from input report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
Input report status bits.
- -
-
- -

◆ PARSE_PACKET_LENGTH

- -
-
- - - - - - - -
#define PARSE_PACKET_LENGTH( packet_ptr)    (UINT16_CLR_LSB(static_cast<uint16_t>(packet_ptr->header[1]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet_ptr->header[0])))
-
- -

Parse length from SHTP packet header.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
Length of SHTP packet.
- -
-
- -

◆ PARSE_PACKET_TIMESTAMP

- -
-
- - - - - - - -
#define PARSE_PACKET_TIMESTAMP( packet_ptr)
-
-Value:
(UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[4]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[3]) << 16UL, 2UL) | \
-
UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[2]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[1]), 0UL))
-
-

Parse timestamp from SHTP packet.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
Packet timestamp.
- -
-
- -

◆ PARSE_PRODUCT_ID_REPORT_PRODUCT_ID

- -
-
- - - - - - - -
#define PARSE_PRODUCT_ID_REPORT_PRODUCT_ID( packet_ptr)   UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[0]), 0UL)
-
- -

Parse product ID SHTP packet containing product ID report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
Product ID.
- -
-
- -

◆ PARSE_PRODUCT_ID_REPORT_RESET_REASON

- -
-
- - - - - - - -
#define PARSE_PRODUCT_ID_REPORT_RESET_REASON( packet_ptr)   UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[1]), 0UL)
-
- -

Parse reset reason from SHTP packet containing product ID report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
Reset reason.
- -
-
- -

◆ PARSE_PRODUCT_ID_REPORT_SW_BUILD_NO

- -
-
- - - - - - - -
#define PARSE_PRODUCT_ID_REPORT_SW_BUILD_NO( packet_ptr)
-
-Value:
UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[11]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[10]) << 16UL, 2UL) | \
-
UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[9]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[8]), 0UL)
-
-

Parse sw build number from SHTP packet containing product ID report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
sw build number.
- -
-
- -

◆ PARSE_PRODUCT_ID_REPORT_SW_PART_NO

- -
-
- - - - - - - -
#define PARSE_PRODUCT_ID_REPORT_SW_PART_NO( packet_ptr)
-
-Value:
(UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[7]) << 24UL, 3UL) | \
-
UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[6]) << 16UL, 2UL) | \
-
UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[5]) << 8UL, 1UL) | \
-
UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[4]), 0UL))
-
-

Parse sw part number from SHTP packet containing product ID report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
sw part number.
- -
-
- -

◆ PARSE_PRODUCT_ID_REPORT_SW_VERSION_MAJOR

- -
-
- - - - - - - -
#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_MAJOR( packet_ptr)   UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[2]), 0UL)
-
- -

Parse product sw version major containing product ID report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
sw version major.
- -
-
- -

◆ PARSE_PRODUCT_ID_REPORT_SW_VERSION_MINOR

- -
-
- - - - - - - -
#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_MINOR( packet_ptr)   UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[3]), 0UL)
-
- -

Parse product sw version minor containing product ID report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
sw version minor.
- -
-
- -

◆ PARSE_PRODUCT_ID_REPORT_SW_VERSION_PATCH

- -
-
- - - - - - - -
#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_PATCH( packet_ptr)    (UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[13]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[12]), 0UL))
-
- -

Parse sw version patch from SHTP packet containing product ID report.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t containing data.
-
-
-
Returns
sw version patch.
- -
-
- -

◆ UINT16_CLR_LSB

- -
-
- - - - - - - -
#define UINT16_CLR_LSB( val_16bit)   ((val_16bit) & 0xFF00U)
-
- -

Clears the least significant byte of a 16-bit value.

-
Parameters
- - -
val_16bitThe 16-bit value to modify.
-
-
-
Returns
The value with the MSB cleared.
- -
-
- -

◆ UINT16_CLR_MSB

- -
-
- - - - - - - -
#define UINT16_CLR_MSB( val_16bit)   ((val_16bit) & 0x00FFU)
-
- -

Clears the most significant byte of a 16-bit value.

-
Parameters
- - -
val_16bitThe 16-bit value to modify.
-
-
-
Returns
The value with the MSB cleared.
- -
-
- -

◆ UINT32_CLR_BYTE

- -
-
- - - - - - - - - - - -
#define UINT32_CLR_BYTE( val_32bit,
byte2clear )   ((val_32bit) & ~(0xFFUL << (byte2clear * 8UL)))
-
- -

Clears a specified byte in a 32-bit value.

-
Parameters
- - - -
val_32bitThe 32-bit value to modify.
byte2clearThe byte index to clear (0 = LSB, 3 = MSB).
-
-
-
Returns
The value with the specified byte cleared.
- -
-
- -

◆ UINT32_MSK_BYTE

- -
-
- - - - - - - - - - - -
#define UINT32_MSK_BYTE( val_32bit,
byte2mask )   ((val_32bit) & (0xFFUL << (byte2mask * 8UL)))
-
- -

Masks a specified byte in a 32-bit value.

-
Parameters
- - - -
val_32bitThe 32-bit value to modify.
byte2maskThe byte index to mask (0 = LSB, 3 = MSB).
-
-
-
Returns
The value with the specified byte masked.
- -
-
-
-
- - - - diff --git a/documentation/html/_b_n_o08x__macros_8hpp.js b/documentation/html/_b_n_o08x__macros_8hpp.js deleted file mode 100644 index 240270e..0000000 --- a/documentation/html/_b_n_o08x__macros_8hpp.js +++ /dev/null @@ -1,36 +0,0 @@ -var _b_n_o08x__macros_8hpp = -[ - [ "CHECK_TASKS_RUNNING", "_b_n_o08x__macros_8hpp.html#a59dd17f0673fdd60f6a65bba104a6f80", null ], - [ "IS_ROTATION_VECTOR_REPORT", "_b_n_o08x__macros_8hpp.html#a84602d112b6000375ad608904de5b0e3", null ], - [ "PARSE_FRS_READ_RESPONSE_REPORT_DATA_1", "_b_n_o08x__macros_8hpp.html#ac70cde2db98355de4f0e56c8650556fe", null ], - [ "PARSE_FRS_READ_RESPONSE_REPORT_DATA_2", "_b_n_o08x__macros_8hpp.html#a2fcd254e9531069d6982795f575cb17a", null ], - [ "PARSE_FRS_READ_RESPONSE_REPORT_RECORD_ID", "_b_n_o08x__macros_8hpp.html#aa23c7c4d9748ce5551fcc0e5734e0a40", null ], - [ "PARSE_GYRO_REPORT_RAW_GYRO_VEL_X", "_b_n_o08x__macros_8hpp.html#a7aed5272074b2ee03da81b6fb7222813", null ], - [ "PARSE_GYRO_REPORT_RAW_GYRO_VEL_Y", "_b_n_o08x__macros_8hpp.html#a823d8c92faf40d07f5b0bb324f2a51bd", null ], - [ "PARSE_GYRO_REPORT_RAW_GYRO_VEL_Z", "_b_n_o08x__macros_8hpp.html#afcc41ef70ba1860c3178072e13ccf512", null ], - [ "PARSE_GYRO_REPORT_RAW_QUAT_I", "_b_n_o08x__macros_8hpp.html#a1f20ab3d051d5acb254e5a5e7b4505de", null ], - [ "PARSE_GYRO_REPORT_RAW_QUAT_J", "_b_n_o08x__macros_8hpp.html#afe721365113756a8b38a5db255f9d061", null ], - [ "PARSE_GYRO_REPORT_RAW_QUAT_K", "_b_n_o08x__macros_8hpp.html#a3ae7fd4e8febc54026e59e1ac544db84", null ], - [ "PARSE_GYRO_REPORT_RAW_QUAT_REAL", "_b_n_o08x__macros_8hpp.html#a73d50f6a746370f614161ee6b9b08424", null ], - [ "PARSE_INPUT_REPORT_DATA_1", "_b_n_o08x__macros_8hpp.html#a4664b5298e0059c173f71bb73a87d239", null ], - [ "PARSE_INPUT_REPORT_DATA_2", "_b_n_o08x__macros_8hpp.html#a455a8649345748be2d5f35036052f78a", null ], - [ "PARSE_INPUT_REPORT_DATA_3", "_b_n_o08x__macros_8hpp.html#a7d38fbfe154c526c822748fc812e7d52", null ], - [ "PARSE_INPUT_REPORT_DATA_4", "_b_n_o08x__macros_8hpp.html#a3d6971a39ce4858314247bdbbb754b33", null ], - [ "PARSE_INPUT_REPORT_DATA_5", "_b_n_o08x__macros_8hpp.html#afd61b5f28723a3f20874097b1bd46e1a", null ], - [ "PARSE_INPUT_REPORT_DATA_6", "_b_n_o08x__macros_8hpp.html#ae66870a6ac704d1ee582f4f7bd2ba6a7", null ], - [ "PARSE_INPUT_REPORT_REPORT_ID", "_b_n_o08x__macros_8hpp.html#a5be1d9a953a0657a4b8df88681b211bc", null ], - [ "PARSE_INPUT_REPORT_STATUS_BITS", "_b_n_o08x__macros_8hpp.html#ac4cad93c425c38fd5cd90d0982897611", null ], - [ "PARSE_PACKET_LENGTH", "_b_n_o08x__macros_8hpp.html#a432e15325e64ab36d5a3b30b65a71bf1", null ], - [ "PARSE_PACKET_TIMESTAMP", "_b_n_o08x__macros_8hpp.html#afa3b6d75bbe499250e69043547a39208", null ], - [ "PARSE_PRODUCT_ID_REPORT_PRODUCT_ID", "_b_n_o08x__macros_8hpp.html#a37c86278c2de384fe3b9304b8d2d3370", null ], - [ "PARSE_PRODUCT_ID_REPORT_RESET_REASON", "_b_n_o08x__macros_8hpp.html#a4c1a6f80fc6ab0ab5d6f803bc175b3e1", null ], - [ "PARSE_PRODUCT_ID_REPORT_SW_BUILD_NO", "_b_n_o08x__macros_8hpp.html#a24ff2498d4883f329d70fb2a6f10e04a", null ], - [ "PARSE_PRODUCT_ID_REPORT_SW_PART_NO", "_b_n_o08x__macros_8hpp.html#a5e6be52a05421d50c4b3600c35868540", null ], - [ "PARSE_PRODUCT_ID_REPORT_SW_VERSION_MAJOR", "_b_n_o08x__macros_8hpp.html#af59b362a169fe8c11a0b679ca99383ee", null ], - [ "PARSE_PRODUCT_ID_REPORT_SW_VERSION_MINOR", "_b_n_o08x__macros_8hpp.html#ad9773ac824ab751df0e331a7c16080a1", null ], - [ "PARSE_PRODUCT_ID_REPORT_SW_VERSION_PATCH", "_b_n_o08x__macros_8hpp.html#a23baa3c8a71f3b3021f135bef27a8ed9", null ], - [ "UINT16_CLR_LSB", "_b_n_o08x__macros_8hpp.html#ac89a0ae0c3d3067f02e9fa275521606b", null ], - [ "UINT16_CLR_MSB", "_b_n_o08x__macros_8hpp.html#ad98f2fa811436866ff297a8288e34f40", null ], - [ "UINT32_CLR_BYTE", "_b_n_o08x__macros_8hpp.html#a7de5c0b84ba545981105e1216925d8e9", null ], - [ "UINT32_MSK_BYTE", "_b_n_o08x__macros_8hpp.html#a6f459cc2cce1722c63d22a9556f06bc8", null ] -]; \ No newline at end of file diff --git a/documentation/html/_b_n_o08x__macros_8hpp__dep__incl.map b/documentation/html/_b_n_o08x__macros_8hpp__dep__incl.map deleted file mode 100644 index 68efdf2..0000000 --- a/documentation/html/_b_n_o08x__macros_8hpp__dep__incl.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/_b_n_o08x__macros_8hpp__dep__incl.md5 b/documentation/html/_b_n_o08x__macros_8hpp__dep__incl.md5 deleted file mode 100644 index b4a6be1..0000000 --- a/documentation/html/_b_n_o08x__macros_8hpp__dep__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -00b34b0458274eeed68f6361cf36c1ab \ No newline at end of file diff --git a/documentation/html/_b_n_o08x__macros_8hpp__dep__incl.png b/documentation/html/_b_n_o08x__macros_8hpp__dep__incl.png deleted file mode 100644 index de61616..0000000 Binary files a/documentation/html/_b_n_o08x__macros_8hpp__dep__incl.png and /dev/null differ diff --git a/documentation/html/_b_n_o08x__macros_8hpp__incl.map b/documentation/html/_b_n_o08x__macros_8hpp__incl.map deleted file mode 100644 index 098009c..0000000 --- a/documentation/html/_b_n_o08x__macros_8hpp__incl.map +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/_b_n_o08x__macros_8hpp__incl.md5 b/documentation/html/_b_n_o08x__macros_8hpp__incl.md5 deleted file mode 100644 index ddfcd94..0000000 --- a/documentation/html/_b_n_o08x__macros_8hpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -e68037c36c449193c84e3993bb364565 \ No newline at end of file diff --git a/documentation/html/_b_n_o08x__macros_8hpp__incl.png b/documentation/html/_b_n_o08x__macros_8hpp__incl.png deleted file mode 100644 index 32f714c..0000000 Binary files a/documentation/html/_b_n_o08x__macros_8hpp__incl.png and /dev/null differ diff --git a/documentation/html/_b_n_o08x__macros_8hpp_source.html b/documentation/html/_b_n_o08x__macros_8hpp_source.html deleted file mode 100644 index 1bc332d..0000000 --- a/documentation/html/_b_n_o08x__macros_8hpp_source.html +++ /dev/null @@ -1,275 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08x_macros.hpp Source File - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
BNO08x_macros.hpp
-
-
-Go to the documentation of this file.
1
-
5#pragma once
-
6
-
7// standard library includes
-
8#include <inttypes.h>
-
9
-
10// esp-idf includes
-
11#include <freertos/FreeRTOS.h>
-
12#include <freertos/event_groups.h>
-
13
-
22#define CHECK_TASKS_RUNNING(evt_grp_task_flow, running_bit) ((xEventGroupGetBits(evt_grp_task_flow) & (running_bit)) != 0)
-
23
-
24// packet parsing macros
-
25
-
32#define UINT16_CLR_MSB(val_16bit) ((val_16bit) & 0x00FFU)
-
33
-
40#define UINT16_CLR_LSB(val_16bit) ((val_16bit) & 0xFF00U)
-
41
-
49#define UINT32_CLR_BYTE(val_32bit, byte2clear) ((val_32bit) & ~(0xFFUL << (byte2clear * 8UL)))
-
50
-
58#define UINT32_MSK_BYTE(val_32bit, byte2mask) ((val_32bit) & (0xFFUL << (byte2mask * 8UL)))
-
59
-
60// parsing universal to any packet
-
61
-
-
68#define PARSE_PACKET_LENGTH(packet_ptr) \
-
69 (UINT16_CLR_LSB(static_cast<uint16_t>(packet_ptr->header[1]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet_ptr->header[0])))
-
-
70
-
-
77#define PARSE_PACKET_TIMESTAMP(packet_ptr) \
-
78 (UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[4]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[3]) << 16UL, 2UL) | \
-
79 UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[2]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[1]), 0UL))
-
-
80
-
81// product id report parsing
-
82
-
89#define PARSE_PRODUCT_ID_REPORT_RESET_REASON(packet_ptr) UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[1]), 0UL)
-
90
-
-
97#define PARSE_PRODUCT_ID_REPORT_SW_PART_NO(packet_ptr) \
-
98 (UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[7]) << 24UL, 3UL) | \
-
99 UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[6]) << 16UL, 2UL) | \
-
100 UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[5]) << 8UL, 1UL) | \
-
101 UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[4]), 0UL))
-
-
102
-
-
109#define PARSE_PRODUCT_ID_REPORT_SW_BUILD_NO(packet_ptr) \
-
110 UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[11]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[10]) << 16UL, 2UL) | \
-
111 UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[9]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[8]), 0UL)
-
-
112
-
-
119#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_PATCH(packet_ptr) \
-
120 (UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[13]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[12]), 0UL))
-
-
121
-
128#define PARSE_PRODUCT_ID_REPORT_PRODUCT_ID(packet_ptr) UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[0]), 0UL)
-
129
-
136#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_MAJOR(packet_ptr) UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[2]), 0UL)
-
137
-
144#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_MINOR(packet_ptr) UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[3]), 0UL)
-
145
-
146// gyro report parsing
-
147
-
-
154#define PARSE_GYRO_REPORT_RAW_QUAT_I(packet) \
-
155 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[1]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[0])))
-
-
156
-
-
163#define PARSE_GYRO_REPORT_RAW_QUAT_J(packet) \
-
164 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[3]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[2])))
-
-
165
-
-
172#define PARSE_GYRO_REPORT_RAW_QUAT_K(packet) \
-
173 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[4])))
-
-
174
-
-
181#define PARSE_GYRO_REPORT_RAW_QUAT_REAL(packet) \
-
182 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[7]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[6])))
-
-
183
-
-
190#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_X(packet) \
-
191 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[9]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[8])))
-
-
192
-
-
199#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_Y(packet) \
-
200 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[11]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[10])))
-
-
201
-
-
208#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_Z(packet) \
-
209 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[13]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[12])))
-
-
210
-
211// input report parsing
-
212
-
219#define PARSE_INPUT_REPORT_STATUS_BITS(packet) (packet->body[5 + 2] & 0x03U)
-
220
-
227#define PARSE_INPUT_REPORT_REPORT_ID(packet) UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5]))
-
228
-
-
235#define PARSE_INPUT_REPORT_DATA_1(packet) \
-
236 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 5]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 4])))
-
-
237
-
-
244#define PARSE_INPUT_REPORT_DATA_2(packet) \
-
245 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 7]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 6])))
-
-
246
-
-
253#define PARSE_INPUT_REPORT_DATA_3(packet) \
-
254 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 9]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 8])))
-
-
255
-
-
262#define PARSE_INPUT_REPORT_DATA_4(packet) \
-
263 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 11]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 10])))
-
-
264
-
-
271#define PARSE_INPUT_REPORT_DATA_5(packet) \
-
272 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 13]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 12])))
-
-
273
-
-
280#define PARSE_INPUT_REPORT_DATA_6(packet) \
-
281 (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 15]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 14])))
-
-
282
-
-
289#define IS_ROTATION_VECTOR_REPORT(packet) \
-
290 ((packet)->body[5] == SENSOR_REPORT_ID_ROTATION_VECTOR || (packet)->body[5] == SENSOR_REPORT_ID_GAME_ROTATION_VECTOR || \
-
291 (packet)->body[5] == SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR || \
-
292 (packet)->body[5] == SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR)
-
-
293
-
294// frs read response report parsing
-
295
-
-
302#define PARSE_FRS_READ_RESPONSE_REPORT_RECORD_ID(packet_body) \
-
303 (UINT16_CLR_LSB(static_cast<uint16_t>(packet_body[13]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet_body[12])))
-
-
304
-
-
311#define PARSE_FRS_READ_RESPONSE_REPORT_DATA_1(packet_body) \
-
312 (UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[7]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[6]) << 16UL, 2UL) | \
-
313 UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[5]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[4]), 0UL))
-
-
314
-
-
321#define PARSE_FRS_READ_RESPONSE_REPORT_DATA_2(packet_body) \
-
322 (UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[11]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[10]) << 16UL, 2UL) | \
-
323 UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[9]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[8]), 0UL))
-
-
-
- - - - diff --git a/documentation/html/_b_n_o08x_test_helper_8hpp.html b/documentation/html/_b_n_o08x_test_helper_8hpp.html deleted file mode 100644 index aeebc99..0000000 --- a/documentation/html/_b_n_o08x_test_helper_8hpp.html +++ /dev/null @@ -1,193 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08xTestHelper.hpp File Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
- -
BNO08xTestHelper.hpp File Reference
-
-
-
#include "stdio.h"
-#include "BNO08x.hpp"
-
-Include dependency graph for BNO08xTestHelper.hpp:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-This graph shows which files directly or indirectly include this file:
-
-
- - - - - - - - - - - - - -
-
-

Go to the source code of this file.

- - - - - - - - -

-Classes

class  BNO08xTestHelper
 BNO08x unit test helper class. More...
 
struct  BNO08xTestHelper::imu_report_data_t
 IMU configuration settings passed into constructor. More...
 
-

Detailed Description

-
Author
Myles Parfeniuk
-
-
- - - - diff --git a/documentation/html/_b_n_o08x_test_helper_8hpp.js b/documentation/html/_b_n_o08x_test_helper_8hpp.js deleted file mode 100644 index 0628923..0000000 --- a/documentation/html/_b_n_o08x_test_helper_8hpp.js +++ /dev/null @@ -1,5 +0,0 @@ -var _b_n_o08x_test_helper_8hpp = -[ - [ "BNO08xTestHelper", "class_b_n_o08x_test_helper.html", "class_b_n_o08x_test_helper" ], - [ "BNO08xTestHelper::imu_report_data_t", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html", "struct_b_n_o08x_test_helper_1_1imu__report__data__t" ] -]; \ No newline at end of file diff --git a/documentation/html/_b_n_o08x_test_helper_8hpp__dep__incl.map b/documentation/html/_b_n_o08x_test_helper_8hpp__dep__incl.map deleted file mode 100644 index b28ed94..0000000 --- a/documentation/html/_b_n_o08x_test_helper_8hpp__dep__incl.map +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/documentation/html/_b_n_o08x_test_helper_8hpp__dep__incl.md5 b/documentation/html/_b_n_o08x_test_helper_8hpp__dep__incl.md5 deleted file mode 100644 index 2409af0..0000000 --- a/documentation/html/_b_n_o08x_test_helper_8hpp__dep__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -7c045f55b15b7efe09be4db57983753a \ No newline at end of file diff --git a/documentation/html/_b_n_o08x_test_helper_8hpp__dep__incl.png b/documentation/html/_b_n_o08x_test_helper_8hpp__dep__incl.png deleted file mode 100644 index 7696ef9..0000000 Binary files a/documentation/html/_b_n_o08x_test_helper_8hpp__dep__incl.png and /dev/null differ diff --git a/documentation/html/_b_n_o08x_test_helper_8hpp__incl.map b/documentation/html/_b_n_o08x_test_helper_8hpp__incl.map deleted file mode 100644 index 9c17e21..0000000 --- a/documentation/html/_b_n_o08x_test_helper_8hpp__incl.map +++ /dev/null @@ -1,44 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_b_n_o08x_test_helper_8hpp__incl.md5 b/documentation/html/_b_n_o08x_test_helper_8hpp__incl.md5 deleted file mode 100644 index 3ba9045..0000000 --- a/documentation/html/_b_n_o08x_test_helper_8hpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -143e4d04830ff9fbc07d6d1d4e2b0003 \ No newline at end of file diff --git a/documentation/html/_b_n_o08x_test_helper_8hpp__incl.png b/documentation/html/_b_n_o08x_test_helper_8hpp__incl.png deleted file mode 100644 index 89144d2..0000000 Binary files a/documentation/html/_b_n_o08x_test_helper_8hpp__incl.png and /dev/null differ diff --git a/documentation/html/_b_n_o08x_test_helper_8hpp_source.html b/documentation/html/_b_n_o08x_test_helper_8hpp_source.html deleted file mode 100644 index 1e5bb86..0000000 --- a/documentation/html/_b_n_o08x_test_helper_8hpp_source.html +++ /dev/null @@ -1,844 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08xTestHelper.hpp Source File - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
BNO08xTestHelper.hpp
-
-
-Go to the documentation of this file.
1
-
5#pragma once
-
6
-
7#include "stdio.h"
-
8#include "BNO08x.hpp"
-
9
-
- -
16{
-
17 private:
-
18 inline static BNO08x* test_imu = nullptr;
-
19 inline static bno08x_config_t imu_cfg;
-
20
-
21 static const constexpr char* TAG = "BNO08xTestHelper";
-
22
-
23 public:
- -
80
-
-
88 static void print_test_start_banner(const char* TEST_TAG)
-
89 {
-
90 printf("------------------------ BEGIN TEST: %s ------------------------\n\r", TEST_TAG);
-
91 }
-
-
92
-
-
100 static void print_test_end_banner(const char* TEST_TAG)
-
101 {
-
102 printf("------------------------ END TEST: %s ------------------------\n\r", TEST_TAG);
-
103 }
-
-
104
-
-
113 static void print_test_msg(const char* TEST_TAG, const char* msg)
-
114 {
-
115 printf("%s: %s: %s\n\r", TAG, TEST_TAG, msg);
-
116 }
-
-
117
-
- -
126 {
-
127 imu_cfg = cfg;
-
128 }
-
-
129
-
-
135 static void create_test_imu()
-
136 {
-
137 if (test_imu != nullptr)
- -
139
-
140 test_imu = new BNO08x();
-
141 }
-
-
142
-
-
148 static void destroy_test_imu()
-
149 {
-
150 if (test_imu != nullptr)
-
151 {
-
152 delete test_imu;
-
153 test_imu = nullptr;
-
154 }
-
155 }
-
-
156
-
- -
163 {
-
164 return test_imu;
-
165 }
-
-
166
-
-
172 static esp_err_t call_init_config_args()
-
173 {
-
174 if (test_imu == nullptr)
-
175 return ESP_FAIL;
-
176
-
177 return test_imu->init_config_args();
-
178 }
-
-
179
-
-
185 static esp_err_t call_init_gpio()
-
186 {
-
187 if (test_imu == nullptr)
-
188 return ESP_FAIL;
-
189
-
190 return test_imu->init_gpio();
-
191 }
-
-
192
-
-
198 static esp_err_t call_init_hint_isr()
-
199 {
-
200 if (test_imu == nullptr)
-
201 return ESP_FAIL;
-
202
-
203 return test_imu->init_hint_isr();
-
204 }
-
-
205
-
-
211 static esp_err_t call_init_spi()
-
212 {
-
213 if (test_imu == nullptr)
-
214 return ESP_FAIL;
-
215
-
216 return test_imu->init_spi();
-
217 }
-
-
218
-
-
224 static esp_err_t call_launch_tasks()
-
225 {
-
226 if (test_imu == nullptr)
-
227 return ESP_FAIL;
-
228
-
229 return test_imu->launch_tasks();
-
230 }
-
-
231
-
- -
241 {
-
242 bool new_data = false;
-
243
-
244 // prev report should always contain the default test values as per test structure
-
245 if (report_data->quat_I != default_report_data->quat_I)
-
246 new_data = true;
-
247
-
248 if (report_data->quat_J != default_report_data->quat_J)
-
249 new_data = true;
-
250
-
251 if (report_data->quat_K != default_report_data->quat_K)
-
252 new_data = true;
-
253
-
254 if (report_data->quat_real != default_report_data->quat_real)
-
255 new_data = true;
-
256
-
257 if (report_data->quat_accuracy != default_report_data->quat_accuracy)
-
258 new_data = true;
-
259
-
260 if (report_data->quat_radian_accuracy != default_report_data->quat_radian_accuracy)
-
261 new_data = true;
-
262
-
263 return new_data;
-
264 }
-
-
265
-
- -
275 {
-
276 bool new_data = false;
-
277
-
278 if (report_data->quat_I != default_report_data->quat_I)
-
279 new_data = true;
-
280
-
281 if (report_data->quat_J != default_report_data->quat_J)
-
282 new_data = true;
-
283
-
284 if (report_data->quat_K != default_report_data->quat_K)
-
285 new_data = true;
-
286
-
287 if (report_data->quat_real != default_report_data->quat_real)
-
288 new_data = true;
-
289
-
290 if (report_data->integrated_gyro_vel_x != default_report_data->integrated_gyro_vel_x)
-
291 new_data = true;
-
292
-
293 if (report_data->integrated_gyro_vel_y != default_report_data->integrated_gyro_vel_y)
-
294 new_data = true;
-
295
-
296 if (report_data->integrated_gyro_vel_z != default_report_data->integrated_gyro_vel_z)
-
297 new_data = true;
-
298
-
299 return new_data;
-
300 }
-
-
301
-
- -
311 {
-
312 bool new_data = false;
-
313
-
314 if (report_data->uncalib_gyro_vel_x != default_report_data->uncalib_gyro_vel_x)
-
315 new_data = true;
-
316
-
317 if (report_data->uncalib_gyro_vel_y != default_report_data->uncalib_gyro_vel_y)
-
318 new_data = true;
-
319
-
320 if (report_data->uncalib_gyro_vel_z != default_report_data->uncalib_gyro_vel_z)
-
321 new_data = true;
-
322
-
323 if (report_data->uncalib_gyro_drift_x != default_report_data->uncalib_gyro_drift_x)
-
324 new_data = true;
-
325
-
326 if (report_data->uncalib_gyro_drift_y != default_report_data->uncalib_gyro_drift_y)
-
327 new_data = true;
-
328
-
329 if (report_data->uncalib_gyro_drift_z != default_report_data->uncalib_gyro_drift_z)
-
330 new_data = true;
-
331
-
332 return new_data;
-
333 }
-
-
334
-
- -
344 {
-
345 bool new_data = false;
-
346
-
347 if (report_data->calib_gyro_vel_x != default_report_data->calib_gyro_vel_x)
-
348 new_data = true;
-
349
-
350 if (report_data->calib_gyro_vel_y != default_report_data->calib_gyro_vel_y)
-
351 new_data = true;
-
352
-
353 if (report_data->calib_gyro_vel_z != default_report_data->calib_gyro_vel_z)
-
354 new_data = true;
-
355
-
356 return new_data;
-
357 }
-
-
358
-
- -
368 {
-
369 bool new_data = false;
-
370
-
371 if (report_data->accel_x != default_report_data->accel_x)
-
372 new_data = true;
-
373
-
374 if (report_data->accel_y != default_report_data->accel_y)
-
375 new_data = true;
-
376
-
377 if (report_data->accel_z != default_report_data->accel_z)
-
378 new_data = true;
-
379
-
380 if (report_data->accel_accuracy != default_report_data->accel_accuracy)
-
381 new_data = true;
-
382
-
383 return new_data;
-
384 }
-
-
385
-
- -
395 {
-
396 bool new_data = false;
-
397
-
398 if (report_data->lin_accel_x != default_report_data->lin_accel_x)
-
399 new_data = true;
-
400
-
401 if (report_data->lin_accel_y != default_report_data->lin_accel_y)
-
402 new_data = true;
-
403
-
404 if (report_data->lin_accel_z != default_report_data->lin_accel_z)
-
405 new_data = true;
-
406
-
407 if (report_data->lin_accel_accuracy != default_report_data->lin_accel_accuracy)
-
408 new_data = true;
-
409
-
410 return new_data;
-
411 }
-
-
412
-
- -
422 {
-
423 bool new_data = false;
-
424
-
425 if (report_data->grav_x != default_report_data->grav_x)
-
426 new_data = true;
-
427
-
428 if (report_data->grav_y != default_report_data->grav_y)
-
429 new_data = true;
-
430
-
431 if (report_data->grav_z != default_report_data->grav_z)
-
432 new_data = true;
-
433
-
434 if (report_data->grav_accuracy != default_report_data->grav_accuracy)
-
435 new_data = true;
-
436
-
437 return new_data;
-
438 }
-
-
439
-
- -
449 {
-
450 bool new_data = false;
-
451
-
452 if (report_data->magf_x != default_report_data->magf_x)
-
453 new_data = true;
-
454
-
455 if (report_data->magf_y != default_report_data->magf_y)
-
456 new_data = true;
-
457
-
458 if (report_data->magf_z != default_report_data->magf_z)
-
459 new_data = true;
-
460
-
461 if (report_data->magf_accuracy != default_report_data->magf_accuracy)
-
462 new_data = true;
-
463
-
464 return new_data;
-
465 }
-
-
466
-
- -
476 {
-
477 bool new_data = false;
-
478
-
479 if (report_data->step_count != default_report_data->step_count)
-
480 new_data = true;
-
481
-
482 return new_data;
-
483 }
-
-
484
-
- -
494 {
-
495 bool new_data = false;
-
496
-
497 if (report_data->stability_classifier != default_report_data->stability_classifier)
-
498 new_data = true;
-
499
-
500 return new_data;
-
501 }
-
-
502
-
- -
512 {
-
513 bool new_data = false;
-
514
-
515 if (report_data->activity_classifier != default_report_data->activity_classifier)
-
516 new_data = true;
-
517
-
518 return new_data;
-
519 }
-
-
520
-
- -
529 {
-
530
- - - - - - - - - - - - - - - - -
547 }
-
-
548
-
- -
555 {
-
556 static const constexpr uint16_t TEST_VAL_UINT16 = 65535U;
-
557 static const constexpr uint16_t TEST_VAL_UINT8 = 255;
-
558 test_imu->time_stamp = 0UL;
-
559
-
560 test_imu->raw_accel_X = TEST_VAL_UINT16;
-
561 test_imu->raw_accel_Y = TEST_VAL_UINT16;
-
562 test_imu->raw_accel_Z = TEST_VAL_UINT16;
-
563 test_imu->accel_accuracy = static_cast<uint16_t>(BNO08xAccuracy::UNDEFINED);
-
564
-
565 test_imu->raw_lin_accel_X = TEST_VAL_UINT16;
-
566 test_imu->raw_lin_accel_Y = TEST_VAL_UINT16;
-
567 test_imu->raw_lin_accel_Z = TEST_VAL_UINT16;
-
568 test_imu->accel_lin_accuracy = static_cast<uint16_t>(BNO08xAccuracy::UNDEFINED);
-
569
-
570 test_imu->raw_calib_gyro_X = TEST_VAL_UINT16;
-
571 test_imu->raw_calib_gyro_Y = TEST_VAL_UINT16;
-
572 test_imu->raw_calib_gyro_Z = TEST_VAL_UINT16;
-
573
-
574 // reset quaternion to nan
-
575 test_imu->raw_quat_I = TEST_VAL_UINT16;
-
576 test_imu->raw_quat_J = TEST_VAL_UINT16;
-
577 test_imu->raw_quat_K = TEST_VAL_UINT16;
-
578 test_imu->raw_quat_real = TEST_VAL_UINT16;
- -
580 test_imu->quat_accuracy = static_cast<uint16_t>(BNO08xAccuracy::UNDEFINED);
-
581
-
582 test_imu->integrated_gyro_velocity_X = TEST_VAL_UINT16;
-
583 test_imu->integrated_gyro_velocity_Y = TEST_VAL_UINT16;
-
584 test_imu->integrated_gyro_velocity_Z = TEST_VAL_UINT16;
-
585
-
586 test_imu->gravity_X = TEST_VAL_UINT16;
-
587 test_imu->gravity_Y = TEST_VAL_UINT16;
-
588 test_imu->gravity_Z = TEST_VAL_UINT16;
-
589 test_imu->gravity_accuracy = static_cast<uint16_t>(BNO08xAccuracy::UNDEFINED);
-
590
-
591 test_imu->raw_uncalib_gyro_X = TEST_VAL_UINT16;
-
592 test_imu->raw_uncalib_gyro_Y = TEST_VAL_UINT16;
-
593 test_imu->raw_uncalib_gyro_Z = TEST_VAL_UINT16;
-
594 test_imu->raw_bias_X = TEST_VAL_UINT16;
-
595 test_imu->raw_bias_Y = TEST_VAL_UINT16;
-
596 test_imu->raw_bias_Z = TEST_VAL_UINT16;
-
597
-
598 test_imu->raw_magf_X = TEST_VAL_UINT16;
-
599 test_imu->raw_magf_Y = TEST_VAL_UINT16;
-
600 test_imu->raw_magf_Z = TEST_VAL_UINT16;
-
601 test_imu->magf_accuracy = static_cast<uint16_t>(BNO08xAccuracy::UNDEFINED);
-
602
-
603 test_imu->tap_detector = TEST_VAL_UINT8;
-
604 test_imu->step_count = TEST_VAL_UINT16;
- - -
607
-
608 test_imu->mems_raw_accel_X = TEST_VAL_UINT16;
-
609 test_imu->mems_raw_accel_Y = TEST_VAL_UINT16;
-
610 test_imu->mems_raw_accel_Z = TEST_VAL_UINT16;
-
611
-
612 test_imu->mems_raw_gyro_X = TEST_VAL_UINT16;
-
613 test_imu->mems_raw_gyro_Y = TEST_VAL_UINT16;
-
614 test_imu->mems_raw_gyro_Z = TEST_VAL_UINT16;
-
615
-
616 test_imu->mems_raw_magf_X = TEST_VAL_UINT16;
-
617 test_imu->mems_raw_magf_Y = TEST_VAL_UINT16;
-
618 test_imu->mems_raw_magf_Z = TEST_VAL_UINT16;
-
619 }
-
-
620
-
-
628 static const char* BNO08xAccuracy_to_str(BNO08xAccuracy accuracy)
-
629 {
-
630 switch (accuracy)
-
631 {
- -
633 return "LOW";
- -
635 return "MED";
- -
637 return "HIGH";
- -
639 return "UNDEFINED";
-
640 default:
-
641 return "INVALID";
-
642 }
-
643 };
-
-
644
-
-
652 static const char* BNO08xStability_to_str(BNO08xStability stability)
-
653 {
-
654 switch (stability)
-
655 {
- -
657 return "UNKNOWN";
- -
659 return "ON TABLE";
- -
661 return "STATIONARY";
- -
663 return "UNDEFINED";
-
664 default:
-
665 return "INVALID";
-
666 }
-
667 }
-
-
668
-
-
676 static const char* BNO08xActivity_to_str(BNO08xActivity activity)
-
677 {
-
678 switch (activity)
-
679 {
- -
681 return "UNKNOWN";
- -
683 return "IN VEHICLE";
- -
685 return "ON BICYCLE";
- -
687 return "ON FOOT";
- -
689 return "STILL";
- -
691 return "TILTING";
- -
693 return "WALKING";
- -
695 return "RUNNING";
- -
697 return "ON STAIRS";
- -
699 return "UNDEFINED";
-
700 default:
-
701 return "INVALID";
-
702 }
-
703 }
-
-
704};
-
- -
BNO08xStability
BNO08xStability states returned from get_stability_classifier()
Definition BNO08x_global_types.hpp:65
- - - - -
BNO08xActivity
BNO08xActivity states returned from get_activity_classifier()
Definition BNO08x_global_types.hpp:50
- - - - - - - - - - -
BNO08xAccuracy
Sensor accuracy returned during sensor calibration.
Definition BNO08x_global_types.hpp:13
- - - - -
BNO08xTestHelper::imu_report_data_t report_data
Definition CallbackTests.cpp:21
-
bool new_data
Definition CallbackTests.cpp:25
-
BNO08x IMU driver class.
Definition BNO08x.hpp:34
-
uint16_t integrated_gyro_velocity_Y
Definition BNO08x.hpp:399
-
uint16_t raw_quat_radian_accuracy
Definition BNO08x.hpp:397
-
void get_gravity(float &x, float &y, float &z, BNO08xAccuracy &accuracy)
Get full reported gravity vector, units in m/s^2.
Definition BNO08x.cpp:2806
-
esp_err_t launch_tasks()
Launches spi_task and data_proc_task on constructor call.
Definition BNO08x.cpp:4003
-
uint16_t raw_bias_Z
Uncalibrated gyro reading (See SH-2 Ref. Manual 6.5.14)
Definition BNO08x.hpp:404
-
uint8_t tap_detector
Tap detector reading (See SH-2 Ref. Manual 6.5.27)
Definition BNO08x.hpp:407
-
uint8_t stability_classifier
BNO08xStability status reading (See SH-2 Ref. Manual 6.5.31)
Definition BNO08x.hpp:409
-
BNO08xStability get_stability_classifier()
Get the current stability classifier (Seee Ref. Manual 6.5.31)
Definition BNO08x.cpp:3508
-
uint16_t accel_accuracy
Raw acceleration readings (See SH-2 Ref. Manual 6.5.8)
Definition BNO08x.hpp:393
-
uint16_t accel_lin_accuracy
Raw linear acceleration (See SH-2 Ref. Manual 6.5.10)
Definition BNO08x.hpp:395
-
uint16_t quat_accuracy
Raw quaternion reading (See SH-2 Ref. Manual 6.5.44)
Definition BNO08x.hpp:398
-
void get_accel(float &x, float &y, float &z, BNO08xAccuracy &accuracy)
Get full acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:3064
-
uint16_t mems_raw_gyro_X
Definition BNO08x.hpp:415
-
BNO08xActivity get_activity_classifier()
Get the current activity classifier (Seee Ref. Manual 6.5.36)
Definition BNO08x.cpp:3527
-
void get_linear_accel(float &x, float &y, float &z, BNO08xAccuracy &accuracy)
Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2).
Definition BNO08x.cpp:3122
-
esp_err_t init_config_args()
Initializes required esp-idf SPI data structures with values from user passed bno08x_config_t struct.
Definition BNO08x.cpp:124
-
esp_err_t init_spi()
Initializes SPI.
Definition BNO08x.cpp:372
-
uint16_t mems_raw_accel_Z
Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.5.8)
Definition BNO08x.hpp:414
-
uint16_t raw_quat_J
Definition BNO08x.hpp:397
-
uint16_t integrated_gyro_velocity_X
Definition BNO08x.hpp:399
-
uint16_t raw_calib_gyro_Y
Definition BNO08x.hpp:396
-
uint16_t raw_quat_I
Definition BNO08x.hpp:397
-
uint8_t activity_classifier
BNO08xActivity status reading (See SH-2 Ref. Manual 6.5.36)
Definition BNO08x.hpp:410
-
uint16_t raw_accel_X
Definition BNO08x.hpp:392
-
uint16_t raw_quat_K
Definition BNO08x.hpp:397
-
uint16_t raw_quat_real
Definition BNO08x.hpp:397
-
void get_uncalibrated_gyro_velocity(float &x, float &y, float &z, float &bx, float &by, float &bz)
Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv...
Definition BNO08x.cpp:3367
-
uint16_t raw_calib_gyro_X
Definition BNO08x.hpp:396
-
uint16_t raw_bias_X
Definition BNO08x.hpp:403
-
void get_integrated_gyro_velocity(float &x, float &y, float &z)
Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5....
Definition BNO08x.cpp:3446
-
uint16_t mems_raw_magf_Z
Raw magnetometer (compass) readings from MEMS sensor (See SH-2 Ref. Manual 6.5.15)
Definition BNO08x.hpp:418
-
uint16_t mems_raw_accel_X
Definition BNO08x.hpp:413
-
esp_err_t init_hint_isr()
Initializes host interrupt ISR.
Definition BNO08x.cpp:321
-
uint16_t raw_magf_X
Definition BNO08x.hpp:405
-
void get_calibrated_gyro_velocity(float &x, float &y, float &z)
Get full rotational velocity with drift compensation (units in Rad/s).
Definition BNO08x.cpp:3317
-
uint16_t mems_raw_magf_Y
Definition BNO08x.hpp:417
-
uint16_t raw_magf_Z
Definition BNO08x.hpp:405
-
uint16_t raw_accel_Y
Definition BNO08x.hpp:392
-
uint16_t mems_raw_magf_X
Definition BNO08x.hpp:417
-
uint16_t mems_raw_gyro_Y
Definition BNO08x.hpp:415
-
uint16_t raw_lin_accel_Z
Definition BNO08x.hpp:394
-
uint32_t time_stamp
Report timestamp (see datasheet 1.3.5.3)
Definition BNO08x.hpp:391
-
void get_raw_mems_gyro(uint16_t &x, uint16_t &y, uint16_t &z)
Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:3225
-
uint16_t mems_raw_gyro_Z
Raw gyro readings from MEMS sensor (See SH-2 Ref. Manual 6.5.12)
Definition BNO08x.hpp:416
-
uint16_t raw_bias_Y
Definition BNO08x.hpp:403
-
uint16_t magf_accuracy
Calibrated magnetic field reading in uTesla (See SH-2 Ref. Manual 6.5.16)
Definition BNO08x.hpp:406
-
uint16_t raw_uncalib_gyro_Y
Definition BNO08x.hpp:403
-
uint16_t raw_magf_Y
Definition BNO08x.hpp:405
-
uint16_t integrated_gyro_velocity_Z
Raw gyro angular velocity reading from integrated gyro rotation vector (See SH-2 Ref....
Definition BNO08x.hpp:400
-
uint16_t step_count
Step counter reading (See SH-2 Ref. Manual 6.5.29)
Definition BNO08x.hpp:408
-
uint16_t mems_raw_accel_Y
Definition BNO08x.hpp:413
-
uint16_t get_step_count()
Get the counted amount of steps.
Definition BNO08x.cpp:3498
-
uint16_t gravity_accuracy
Gravity reading in m/s^2 (See SH-2 Ref. Manual 6.5.11)
Definition BNO08x.hpp:402
-
esp_err_t init_gpio()
Initializes required gpio.
Definition BNO08x.cpp:293
-
uint16_t raw_lin_accel_X
Definition BNO08x.hpp:394
-
void get_magf(float &x, float &y, float &z, BNO08xAccuracy &accuracy)
Get the full magnetic field vector.
Definition BNO08x.cpp:2745
-
uint16_t gravity_Y
Definition BNO08x.hpp:401
-
uint16_t raw_accel_Z
Definition BNO08x.hpp:392
-
uint16_t gravity_X
Definition BNO08x.hpp:401
-
uint16_t raw_calib_gyro_Z
Raw gyro reading (See SH-2 Ref. Manual 6.5.13)
Definition BNO08x.hpp:396
-
void get_quat(float &i, float &j, float &k, float &real, float &rad_accuracy, BNO08xAccuracy &accuracy)
Get the full quaternion reading.
Definition BNO08x.cpp:2979
-
uint16_t gravity_Z
Definition BNO08x.hpp:401
-
uint16_t raw_uncalib_gyro_Z
Definition BNO08x.hpp:403
-
uint16_t raw_uncalib_gyro_X
Definition BNO08x.hpp:403
-
uint16_t raw_lin_accel_Y
Definition BNO08x.hpp:394
-
BNO08x unit test helper class.
Definition BNO08xTestHelper.hpp:16
-
static bno08x_config_t imu_cfg
Definition BNO08xTestHelper.hpp:19
-
static void print_test_start_banner(const char *TEST_TAG)
Prints test begin banner.
Definition BNO08xTestHelper.hpp:88
-
static bool calibrated_gyro_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)
Checks if report_data matches the default states stored within prev_report_data data for respective r...
Definition BNO08xTestHelper.hpp:343
-
struct BNO08xTestHelper::imu_report_data_t imu_report_data_t
IMU configuration settings passed into constructor.
-
static bool magnetometer_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)
Checks if report_data matches the default states stored within prev_report_data data for respective r...
Definition BNO08xTestHelper.hpp:448
-
static void print_test_end_banner(const char *TEST_TAG)
Prints end begin banner.
Definition BNO08xTestHelper.hpp:100
-
static BNO08x * test_imu
Definition BNO08xTestHelper.hpp:18
-
static bool gravity_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)
Checks if report_data matches the default states stored within prev_report_data data for respective r...
Definition BNO08xTestHelper.hpp:421
-
static BNO08x * get_test_imu()
Deletes test IMU calling deconstructor and releases heap allocated memory.
Definition BNO08xTestHelper.hpp:162
-
static esp_err_t call_init_gpio()
Used to call private BNO08x::init_gpio() member for tests.
Definition BNO08xTestHelper.hpp:185
-
static void create_test_imu()
Calls BNO08x constructor and creates new test IMU on heap.
Definition BNO08xTestHelper.hpp:135
-
static esp_err_t call_init_config_args()
Used to call private BNO08x::init_config_args() member for tests.
Definition BNO08xTestHelper.hpp:172
-
static esp_err_t call_init_spi()
Used to call private BNO08x::init_spi() member for tests.
Definition BNO08xTestHelper.hpp:211
-
static void print_test_msg(const char *TEST_TAG, const char *msg)
Prints a message during a test.
Definition BNO08xTestHelper.hpp:113
-
static esp_err_t call_init_hint_isr()
Used to call private BNO08x::init_hint_isr() member for tests.
Definition BNO08xTestHelper.hpp:198
-
static const char * BNO08xAccuracy_to_str(BNO08xAccuracy accuracy)
Converts BNO08xAccuracy enum class object to string.
Definition BNO08xTestHelper.hpp:628
-
static bool stability_classifier_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)
Checks if report_data matches the default states stored within prev_report_data data for respective r...
Definition BNO08xTestHelper.hpp:493
-
static void set_test_imu_cfg(bno08x_config_t cfg)
Set test imu configuration used with create_test_imu()
Definition BNO08xTestHelper.hpp:125
-
static const constexpr char * TAG
Definition BNO08xTestHelper.hpp:21
-
static bool step_counter_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)
Checks if report_data matches the default states stored within prev_report_data data for respective r...
Definition BNO08xTestHelper.hpp:475
-
static bool gyro_integrated_rotation_vector_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)
Checks if report_data matches the default states stored within prev_report_data data for respective r...
Definition BNO08xTestHelper.hpp:274
-
static void update_report_data(imu_report_data_t *report_data)
Updates report data with calls relevant test_imu methods.
Definition BNO08xTestHelper.hpp:528
-
static const char * BNO08xActivity_to_str(BNO08xActivity activity)
Converts BNO08xActivity enum class object to string.
Definition BNO08xTestHelper.hpp:676
-
static bool linear_accelerometer_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)
Checks if report_data matches the default states stored within prev_report_data data for respective r...
Definition BNO08xTestHelper.hpp:394
-
static bool uncalibrated_gyro_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)
Checks if report_data matches the default states stored within prev_report_data data for respective r...
Definition BNO08xTestHelper.hpp:310
-
static void reset_all_imu_data_to_test_defaults()
Resets internal test imu data with test defaults.
Definition BNO08xTestHelper.hpp:554
-
static bool accelerometer_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)
Checks if report_data matches the default states stored within prev_report_data data for respective r...
Definition BNO08xTestHelper.hpp:367
-
static esp_err_t call_launch_tasks()
Used to call private BNO08x::launch_tasks() member for tests.
Definition BNO08xTestHelper.hpp:224
-
static void destroy_test_imu()
Deletes test IMU calling deconstructor and releases heap allocated memory.
Definition BNO08xTestHelper.hpp:148
-
static const char * BNO08xStability_to_str(BNO08xStability stability)
Converts BNO08xStability enum class object to string.
Definition BNO08xTestHelper.hpp:652
-
static bool rotation_vector_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)
Checks if report_data matches the default states stored within prev_report_data data for respective r...
Definition BNO08xTestHelper.hpp:240
-
static bool activity_classifier_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)
Checks if report_data matches the default states stored within prev_report_data data for respective r...
Definition BNO08xTestHelper.hpp:511
-
IMU configuration settings passed into constructor.
Definition BNO08xTestHelper.hpp:26
-
BNO08xActivity activity_classifier
Definition BNO08xTestHelper.hpp:77
-
float integrated_gyro_vel_x
Definition BNO08xTestHelper.hpp:36
-
BNO08xAccuracy magf_accuracy
Definition BNO08xTestHelper.hpp:69
-
float magf_x
Definition BNO08xTestHelper.hpp:66
-
float grav_y
Definition BNO08xTestHelper.hpp:51
-
float integrated_gyro_vel_z
Definition BNO08xTestHelper.hpp:38
-
float quat_J
Definition BNO08xTestHelper.hpp:30
-
float uncalib_gyro_drift_z
Definition BNO08xTestHelper.hpp:64
-
float uncalib_gyro_vel_x
Definition BNO08xTestHelper.hpp:59
-
float uncalib_gyro_drift_y
Definition BNO08xTestHelper.hpp:63
-
float lin_accel_x
Definition BNO08xTestHelper.hpp:45
-
float quat_K
Definition BNO08xTestHelper.hpp:31
-
BNO08xAccuracy lin_accel_accuracy
Definition BNO08xTestHelper.hpp:48
-
float magf_z
Definition BNO08xTestHelper.hpp:68
-
float lin_accel_y
Definition BNO08xTestHelper.hpp:46
-
float lin_accel_z
Definition BNO08xTestHelper.hpp:47
-
float accel_x
Definition BNO08xTestHelper.hpp:40
-
BNO08xAccuracy grav_accuracy
Definition BNO08xTestHelper.hpp:53
-
float calib_gyro_vel_z
Definition BNO08xTestHelper.hpp:57
-
float accel_y
Definition BNO08xTestHelper.hpp:41
-
uint16_t raw_mems_gyro_y
Definition BNO08xTestHelper.hpp:72
-
float quat_real
Definition BNO08xTestHelper.hpp:32
-
BNO08xStability stability_classifier
Definition BNO08xTestHelper.hpp:76
-
float magf_y
Definition BNO08xTestHelper.hpp:67
-
float calib_gyro_vel_x
Definition BNO08xTestHelper.hpp:55
-
float quat_I
Definition BNO08xTestHelper.hpp:29
-
uint16_t raw_mems_gyro_x
Definition BNO08xTestHelper.hpp:71
-
uint16_t raw_mems_gyro_z
Definition BNO08xTestHelper.hpp:73
-
BNO08xAccuracy quat_accuracy
Definition BNO08xTestHelper.hpp:34
-
float uncalib_gyro_vel_z
Definition BNO08xTestHelper.hpp:61
-
BNO08xAccuracy accel_accuracy
Definition BNO08xTestHelper.hpp:43
-
float uncalib_gyro_drift_x
Definition BNO08xTestHelper.hpp:62
-
float grav_x
Definition BNO08xTestHelper.hpp:50
-
float uncalib_gyro_vel_y
Definition BNO08xTestHelper.hpp:60
-
float quat_radian_accuracy
Definition BNO08xTestHelper.hpp:33
-
uint32_t time_stamp
Definition BNO08xTestHelper.hpp:27
-
uint16_t step_count
Definition BNO08xTestHelper.hpp:75
-
float accel_z
Definition BNO08xTestHelper.hpp:42
-
float grav_z
Definition BNO08xTestHelper.hpp:52
-
float integrated_gyro_vel_y
Definition BNO08xTestHelper.hpp:37
-
float calib_gyro_vel_y
Definition BNO08xTestHelper.hpp:56
-
IMU configuration settings passed into constructor.
Definition BNO08x_global_types.hpp:74
-
-
- - - - diff --git a/documentation/html/_b_n_o08x_test_suite_8hpp.html b/documentation/html/_b_n_o08x_test_suite_8hpp.html deleted file mode 100644 index 65990fb..0000000 --- a/documentation/html/_b_n_o08x_test_suite_8hpp.html +++ /dev/null @@ -1,182 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08xTestSuite.hpp File Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
- -
BNO08xTestSuite.hpp File Reference
-
-
-
#include <stdio.h>
-#include <string.h>
-#include "unity.h"
-#include "BNO08xTestHelper.hpp"
-
-Include dependency graph for BNO08xTestSuite.hpp:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-

Go to the source code of this file.

- - - - - -

-Classes

class  BNO08xTestSuite
 BNO08x unit test launch point class. More...
 
-

Detailed Description

-
Author
Myles Parfeniuk
-
Warning
YOU MUST ADD THE FOLLOWING LINE TO YOUR MAIN PROJECTS CMakeLists.txt IN ORDER FOR THIS TEST SUITE TO BE BUILT WITH PROJECT: set(TEST_COMPONENTS "esp32_BNO08x" CACHE STRING "Components to test.")
-
-
- - - - diff --git a/documentation/html/_b_n_o08x_test_suite_8hpp.js b/documentation/html/_b_n_o08x_test_suite_8hpp.js deleted file mode 100644 index e09a71e..0000000 --- a/documentation/html/_b_n_o08x_test_suite_8hpp.js +++ /dev/null @@ -1,4 +0,0 @@ -var _b_n_o08x_test_suite_8hpp = -[ - [ "BNO08xTestSuite", "class_b_n_o08x_test_suite.html", "class_b_n_o08x_test_suite" ] -]; \ No newline at end of file diff --git a/documentation/html/_b_n_o08x_test_suite_8hpp__incl.map b/documentation/html/_b_n_o08x_test_suite_8hpp__incl.map deleted file mode 100644 index 1db5ccd..0000000 --- a/documentation/html/_b_n_o08x_test_suite_8hpp__incl.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_b_n_o08x_test_suite_8hpp__incl.md5 b/documentation/html/_b_n_o08x_test_suite_8hpp__incl.md5 deleted file mode 100644 index af24afb..0000000 --- a/documentation/html/_b_n_o08x_test_suite_8hpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -cbe15c59e2c01479a472681297f79770 \ No newline at end of file diff --git a/documentation/html/_b_n_o08x_test_suite_8hpp__incl.png b/documentation/html/_b_n_o08x_test_suite_8hpp__incl.png deleted file mode 100644 index e2169d7..0000000 Binary files a/documentation/html/_b_n_o08x_test_suite_8hpp__incl.png and /dev/null differ diff --git a/documentation/html/_b_n_o08x_test_suite_8hpp_source.html b/documentation/html/_b_n_o08x_test_suite_8hpp_source.html deleted file mode 100644 index 03621ab..0000000 --- a/documentation/html/_b_n_o08x_test_suite_8hpp_source.html +++ /dev/null @@ -1,231 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08xTestSuite.hpp Source File - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
BNO08xTestSuite.hpp
-
-
-Go to the documentation of this file.
1
-
9#pragma once
-
10
-
11#include <stdio.h>
-
12#include <string.h>
-
13#include "unity.h"
-
14#include "BNO08xTestHelper.hpp"
-
15
-
- -
22{
-
23 private:
-
-
24 static void print_begin_tests_banner(const char* test_set_name)
-
25 {
-
26 printf("####################### BEGIN TESTS: %s #######################\n\r", test_set_name);
-
27 }
-
-
28
-
-
29 static void print_end_tests_banner(const char* test_set_name)
-
30 {
-
31 printf("####################### END TESTS: %s #######################\n\r", test_set_name);
-
32 }
-
-
33
-
34 public:
-
-
35 static void run_all_tests()
-
36 {
-
37 UNITY_BEGIN();
- - - -
41 run_callback_tests(false);
-
42 UNITY_END();
-
43 }
-
-
44
-
-
45 static void run_init_deinit_tests(bool call_unity_end_begin = true)
-
46 {
-
47 print_begin_tests_banner("init_denit_tests");
-
48
-
49 if (call_unity_end_begin)
-
50 UNITY_BEGIN();
-
51
-
52 unity_run_tests_by_tag("[InitComprehensive]", false);
-
53 unity_run_tests_by_tag("[InitDenit]", false);
-
54
-
55 if (call_unity_end_begin)
-
56 UNITY_END();
-
57
-
58 print_end_tests_banner("init_denit_tests");
-
59 }
-
-
60
-
-
61 static void run_single_report_tests(bool call_unity_end_begin = true)
-
62 {
-
63 print_begin_tests_banner("single_report_tests");
-
64
-
65 if (call_unity_end_begin)
-
66 UNITY_BEGIN();
-
67
-
68 unity_run_tests_by_tag("[SingleReportEnableDisable]", false);
-
69
-
70 if (call_unity_end_begin)
-
71 UNITY_END();
-
72
-
73 print_end_tests_banner("single_report_tests");
-
74 }
-
-
75
-
-
76 static void run_multi_report_tests(bool call_unity_end_begin = true)
-
77 {
-
78 print_begin_tests_banner("multi_report_tests");
-
79
-
80 if (call_unity_end_begin)
-
81 UNITY_BEGIN();
-
82
-
83 unity_run_tests_by_tag("[MultiReportEnableDisable]", false);
-
84
-
85 if (call_unity_end_begin)
-
86 UNITY_END();
-
87
-
88 print_end_tests_banner("multi_report_tests");
-
89 }
-
-
90
-
-
91 static void run_callback_tests(bool call_unity_end_begin = true)
-
92 {
-
93 print_begin_tests_banner("run_callback_tests");
-
94
-
95 if (call_unity_end_begin)
-
96 UNITY_BEGIN();
-
97
-
98 unity_run_tests_by_tag("[CallbackTests]", false);
-
99
-
100 if (call_unity_end_begin)
-
101 UNITY_END();
-
102
-
103 print_end_tests_banner("run_callback_tests");
-
104 }
-
-
105};
-
- -
BNO08x unit test launch point class.
Definition BNO08xTestSuite.hpp:22
-
static void print_begin_tests_banner(const char *test_set_name)
Definition BNO08xTestSuite.hpp:24
-
static void run_single_report_tests(bool call_unity_end_begin=true)
Definition BNO08xTestSuite.hpp:61
-
static void run_init_deinit_tests(bool call_unity_end_begin=true)
Definition BNO08xTestSuite.hpp:45
-
static void print_end_tests_banner(const char *test_set_name)
Definition BNO08xTestSuite.hpp:29
-
static void run_callback_tests(bool call_unity_end_begin=true)
Definition BNO08xTestSuite.hpp:91
-
static void run_multi_report_tests(bool call_unity_end_begin=true)
Definition BNO08xTestSuite.hpp:76
-
static void run_all_tests()
Definition BNO08xTestSuite.hpp:35
-
-
- - - - diff --git a/documentation/html/_callback_tests_8cpp.html b/documentation/html/_callback_tests_8cpp.html deleted file mode 100644 index 7150246..0000000 --- a/documentation/html/_callback_tests_8cpp.html +++ /dev/null @@ -1,936 +0,0 @@ - - - - - - - -esp32_BNO08x: CallbackTests.cpp File Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
- -
CallbackTests.cpp File Reference
-
-
-
#include "unity.h"
-#include "../include/BNO08xTestHelper.hpp"
-
-Include dependency graph for CallbackTests.cpp:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
- - - - - - - - - - - - - - - - - - - - - - - -

-Functions

 TEST_CASE ("BNO08x Driver Creation for [CallbackTests] Tests", "[CallbackTests]")
 
imu register_cb ([&imu, &new_data, &report_data, &prev_report_data, &msg_buff]() { static int cb_execution_cnt=0;cb_execution_cnt++;BNO08xTestHelper::update_report_data(&report_data);if(BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) { new_data=true;sprintf(msg_buff, "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " "%.2lf Accuracy %s", cb_execution_cnt, report_data.accel_x, report_data.accel_y, report_data.accel_z, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy));BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff);} })
 
imu enable_accelerometer (REPORT_PERIOD)
 
 for (int i=0;i< RX_REPORT_TRIAL_CNT;i++)
 
imu disable_accelerometer ()
 
imu register_cb ([&imu, &new_data, &report_data, &prev_report_data, &msg_buff]() { static int cb_execution_cnt=0;cb_execution_cnt++;BNO08xTestHelper::update_report_data(&report_data);if(BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) { new_data[0]=true;sprintf(msg_buff, "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " "%.2lf Accuracy %s", cb_execution_cnt, report_data.accel_x, report_data.accel_y, report_data.accel_z, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy));BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff);} if(BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) { new_data[1]=true;sprintf(msg_buff, "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " "%.2lf Accuracy: %s",(cb_execution_cnt+1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy));BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff);} })
 
imu enable_linear_accelerometer (REPORT_PERIOD)
 
 TEST_ASSERT_EQUAL (true, new_data[0])
 
 TEST_ASSERT_EQUAL (true, new_data[1])
 
imu disable_linear_accelerometer ()
 
 TEST_CASE ("BNO08x Driver Cleanup for [CallbackTests] Tests", "[CallbackTests]")
 
- - - - - - - - - - - - - - - - - -

-Variables

BNO08ximu = nullptr
 
BNO08xTestHelper::imu_report_data_t report_data
 
BNO08xTestHelper::imu_report_data_t prev_report_data
 
const constexpr uint8_t RX_REPORT_TRIAL_CNT = 5
 
const constexpr uint32_t REPORT_PERIOD = 100000UL
 
bool new_data = false
 
char msg_buff [200] = {}
 
const constexpr uint8_t ENABLED_REPORT_CNT = 2
 
-

Function Documentation

- -

◆ disable_accelerometer()

- -
-
- - - - - - - -
imu disable_accelerometer ()
-
- -
-
- -

◆ disable_linear_accelerometer()

- -
-
- - - - - - - -
imu disable_linear_accelerometer ()
-
- -
-
- -

◆ enable_accelerometer()

- -
-
- - - - - - - -
imu enable_accelerometer (REPORT_PERIOD )
-
- -
-
- -

◆ enable_linear_accelerometer()

- -
-
- - - - - - - -
imu enable_linear_accelerometer (REPORT_PERIOD )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ for()

- -
-
- - - - - - - -
for ()
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ register_cb() [1/2]

- -
-
- - - - - - - -
imu register_cb ([&imu, &new_data, &report_data, &prev_report_data, &msg_buff] () { static int cb_execution_cnt=0;cb_execution_cnt++;BNO08xTestHelper::update_report_data(&report_data);if(BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) { new_data=true;sprintf(msg_buff, "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " "%.2lf Accuracy %s", cb_execution_cnt, report_data.accel_x, report_data.accel_y, report_data.accel_z, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy));BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff);} } )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ register_cb() [2/2]

- -
-
- - - - - - - -
imu register_cb ([&imu, &new_data, &report_data, &prev_report_data, &msg_buff] () { static int cb_execution_cnt=0;cb_execution_cnt++;BNO08xTestHelper::update_report_data(&report_data);if(BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) { new_data[0]=true;sprintf(msg_buff, "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " "%.2lf Accuracy %s", cb_execution_cnt, report_data.accel_x, report_data.accel_y, report_data.accel_z, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy));BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff);} if(BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) { new_data[1]=true;sprintf(msg_buff, "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " "%.2lf Accuracy: %s",(cb_execution_cnt+1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy));BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff);} } )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_ASSERT_EQUAL() [1/2]

- -
-
- - - - - - - - - - - -
TEST_ASSERT_EQUAL (true ,
new_data [0] )
-
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_ASSERT_EQUAL() [2/2]

- -
-
- - - - - - - - - - - -
TEST_ASSERT_EQUAL (true ,
new_data [1] )
-
- -
-
- -

◆ TEST_CASE() [1/2]

- -
-
- - - - - - - - - - - -
TEST_CASE ("BNO08x Driver Cleanup for Tests" [CallbackTests],
"" [CallbackTests] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ TEST_CASE() [2/2]

- -
-
- - - - - - - - - - - -
TEST_CASE ("BNO08x Driver Creation for Tests" [CallbackTests],
"" [CallbackTests] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
-

Variable Documentation

- -

◆ ENABLED_REPORT_CNT

- -
-
- - - - - -
- - - - -
const constexpr uint8_t ENABLED_REPORT_CNT = 2
-
-constexpr
-
- -
-
- -

◆ imu

- -
-
- - - - -
BNO08x * imu = nullptr
-
- -
-
- -

◆ msg_buff

- -
-
- - - - -
char msg_buff = {}
-
- -
-
- -

◆ new_data

- -
-
- - - - -
bool new_data = false
-
- -
-
- -

◆ prev_report_data

- -
-
- - - - -
BNO08xTestHelper::imu_report_data_t prev_report_data
-
- -
-
- -

◆ report_data

- -
-
- - - - -
BNO08xTestHelper::update_report_data & report_data
-
- -
-
- -

◆ REPORT_PERIOD

- -
-
- - - - - -
- - - - -
const constexpr uint32_t REPORT_PERIOD = 100000UL
-
-constexpr
-
- -
-
- -

◆ RX_REPORT_TRIAL_CNT

- -
-
- - - - - -
- - - - -
const constexpr uint8_t RX_REPORT_TRIAL_CNT = 5
-
-constexpr
-
- -
-
-
-
- - - - diff --git a/documentation/html/_callback_tests_8cpp.js b/documentation/html/_callback_tests_8cpp.js deleted file mode 100644 index c2e85c5..0000000 --- a/documentation/html/_callback_tests_8cpp.js +++ /dev/null @@ -1,22 +0,0 @@ -var _callback_tests_8cpp = -[ - [ "disable_accelerometer", "_callback_tests_8cpp.html#a79547a2396efd083faeba3e54d94360d", null ], - [ "disable_linear_accelerometer", "_callback_tests_8cpp.html#a5cc5f7e6658e3b1634d99b73dbfd06ab", null ], - [ "enable_accelerometer", "_callback_tests_8cpp.html#a0f2cacda77ab92640f739aca52b1f99f", null ], - [ "enable_linear_accelerometer", "_callback_tests_8cpp.html#a3e937c8c4a4c07b81fb20077ee984fc0", null ], - [ "for", "_callback_tests_8cpp.html#a4ac223c58b5ab6a6c5203661fafa1caa", null ], - [ "register_cb", "_callback_tests_8cpp.html#a6df8508e34beaeb28f34554ce0e20573", null ], - [ "register_cb", "_callback_tests_8cpp.html#a8dba989b01b464871f3232223050ec73", null ], - [ "TEST_ASSERT_EQUAL", "_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3", null ], - [ "TEST_ASSERT_EQUAL", "_callback_tests_8cpp.html#aa6754207db4cfba956441680c7a6a97d", null ], - [ "TEST_CASE", "_callback_tests_8cpp.html#a574f179a8295301510bc8b5475f02ba8", null ], - [ "TEST_CASE", "_callback_tests_8cpp.html#ac18b9cb122499f587331d82a538f23aa", null ], - [ "ENABLED_REPORT_CNT", "_callback_tests_8cpp.html#aafbc34af64f3c93123dce5a8238efd38", null ], - [ "imu", "_callback_tests_8cpp.html#ac36e56130d5d806898f3545d4cdf0f70", null ], - [ "msg_buff", "_callback_tests_8cpp.html#a4e7be0e1e700243053709d7544201596", null ], - [ "new_data", "_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876", null ], - [ "prev_report_data", "_callback_tests_8cpp.html#a8c57d66969fed0b55bdee9b57f6ed0a7", null ], - [ "report_data", "_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9", null ], - [ "REPORT_PERIOD", "_callback_tests_8cpp.html#a4b80e39a1f48d801615a1f7baa210071", null ], - [ "RX_REPORT_TRIAL_CNT", "_callback_tests_8cpp.html#a20cd776c25ed6d39b2dcb95d155cfbda", null ] -]; \ No newline at end of file diff --git a/documentation/html/_callback_tests_8cpp__incl.map b/documentation/html/_callback_tests_8cpp__incl.map deleted file mode 100644 index 09c1ca1..0000000 --- a/documentation/html/_callback_tests_8cpp__incl.map +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_callback_tests_8cpp__incl.md5 b/documentation/html/_callback_tests_8cpp__incl.md5 deleted file mode 100644 index bf465b9..0000000 --- a/documentation/html/_callback_tests_8cpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -7b498e0d0ad77cc03801e11b287f9b0d \ No newline at end of file diff --git a/documentation/html/_callback_tests_8cpp__incl.png b/documentation/html/_callback_tests_8cpp__incl.png deleted file mode 100644 index 19a2fc6..0000000 Binary files a/documentation/html/_callback_tests_8cpp__incl.png and /dev/null differ diff --git a/documentation/html/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.map b/documentation/html/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.map deleted file mode 100644 index cfe21b9..0000000 --- a/documentation/html/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.map +++ /dev/null @@ -1,44 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.md5 b/documentation/html/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.md5 deleted file mode 100644 index 0f8f68d..0000000 --- a/documentation/html/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -835ac906ec53cdaad191e625af11ecab \ No newline at end of file diff --git a/documentation/html/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.png b/documentation/html/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.png deleted file mode 100644 index d0b56f6..0000000 Binary files a/documentation/html/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.png and /dev/null differ diff --git a/documentation/html/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.map b/documentation/html/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.map deleted file mode 100644 index df27299..0000000 --- a/documentation/html/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.map +++ /dev/null @@ -1,46 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.md5 b/documentation/html/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.md5 deleted file mode 100644 index dcc5ca3..0000000 --- a/documentation/html/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -427cdc65693254a8f7d86d5c129973ba \ No newline at end of file diff --git a/documentation/html/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.png b/documentation/html/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.png deleted file mode 100644 index f0181d7..0000000 Binary files a/documentation/html/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.png and /dev/null differ diff --git a/documentation/html/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.map b/documentation/html/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.map deleted file mode 100644 index 1591bdf..0000000 --- a/documentation/html/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.md5 b/documentation/html/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.md5 deleted file mode 100644 index d2fd7a6..0000000 --- a/documentation/html/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -20530a0195add9876a81f3eca1f08dca \ No newline at end of file diff --git a/documentation/html/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.png b/documentation/html/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.png deleted file mode 100644 index 193fc0f..0000000 Binary files a/documentation/html/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.png and /dev/null differ diff --git a/documentation/html/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.map b/documentation/html/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.map deleted file mode 100644 index feba2e6..0000000 --- a/documentation/html/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.map +++ /dev/null @@ -1,44 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.md5 b/documentation/html/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.md5 deleted file mode 100644 index d33d893..0000000 --- a/documentation/html/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2550d060896a16cbcdd8f86f8db4194b \ No newline at end of file diff --git a/documentation/html/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.png b/documentation/html/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.png deleted file mode 100644 index b568af2..0000000 Binary files a/documentation/html/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.png and /dev/null differ diff --git a/documentation/html/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.map b/documentation/html/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.map deleted file mode 100644 index cfccf10..0000000 --- a/documentation/html/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.map +++ /dev/null @@ -1,46 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.md5 b/documentation/html/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.md5 deleted file mode 100644 index a2a0ac7..0000000 --- a/documentation/html/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a1643d70149876d952e9f6ddc331bc7e \ No newline at end of file diff --git a/documentation/html/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.png b/documentation/html/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.png deleted file mode 100644 index f39ce4c..0000000 Binary files a/documentation/html/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.png and /dev/null differ diff --git a/documentation/html/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.map b/documentation/html/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.map deleted file mode 100644 index 3388e24..0000000 --- a/documentation/html/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.map +++ /dev/null @@ -1,61 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.md5 b/documentation/html/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.md5 deleted file mode 100644 index df9b1e0..0000000 --- a/documentation/html/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -63c0e8b27ef5c63411df199109689b0c \ No newline at end of file diff --git a/documentation/html/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.png b/documentation/html/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.png deleted file mode 100644 index 793aebc..0000000 Binary files a/documentation/html/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.png and /dev/null differ diff --git a/documentation/html/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.map b/documentation/html/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.map deleted file mode 100644 index 2d0ed09..0000000 --- a/documentation/html/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.map +++ /dev/null @@ -1,101 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.md5 b/documentation/html/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.md5 deleted file mode 100644 index 04150ea..0000000 --- a/documentation/html/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b3c196a6ebab141b340f0e0a7846097c \ No newline at end of file diff --git a/documentation/html/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.png b/documentation/html/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.png deleted file mode 100644 index e0e351a..0000000 Binary files a/documentation/html/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.png and /dev/null differ diff --git a/documentation/html/_init_deinit_tests_8cpp.html b/documentation/html/_init_deinit_tests_8cpp.html deleted file mode 100644 index c066f8c..0000000 --- a/documentation/html/_init_deinit_tests_8cpp.html +++ /dev/null @@ -1,652 +0,0 @@ - - - - - - - -esp32_BNO08x: InitDeinitTests.cpp File Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
- -
InitDeinitTests.cpp File Reference
-
-
-
#include "unity.h"
-#include "../include/BNO08xTestHelper.hpp"
-
-Include dependency graph for InitDeinitTests.cpp:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
- - - - - - - - - - - - - - - -

-Functions

 TEST_CASE ("Init Config Args", "[InitComprehensive]")
 
 TEST_CASE ("Init GPIO", "[InitComprehensive]")
 
 TEST_CASE ("Init HINT ISR", "[InitComprehensive]")
 
 TEST_CASE ("Init SPI", "[InitComprehensive]")
 
 TEST_CASE ("InitComprehensive Tasks", "[InitComprehensive]")
 
 TEST_CASE ("Finish Init", "[InitComprehensive]")
 
 TEST_CASE ("Init & Deinit", "[InitDenit]")
 
-

Function Documentation

- -

◆ TEST_CASE() [1/7]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Finish Init" ,
"" [InitComprehensive] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [2/7]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Init & Deinit" ,
"" [InitDenit] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [3/7]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Init Config Args" ,
"" [InitComprehensive] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [4/7]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Init GPIO" ,
"" [InitComprehensive] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [5/7]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Init HINT ISR" ,
"" [InitComprehensive] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [6/7]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Init SPI" ,
"" [InitComprehensive] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [7/7]

- -
-
- - - - - - - - - - - -
TEST_CASE ("InitComprehensive Tasks" ,
"" [InitComprehensive] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
-
-
- - - - diff --git a/documentation/html/_init_deinit_tests_8cpp.js b/documentation/html/_init_deinit_tests_8cpp.js deleted file mode 100644 index f05829a..0000000 --- a/documentation/html/_init_deinit_tests_8cpp.js +++ /dev/null @@ -1,10 +0,0 @@ -var _init_deinit_tests_8cpp = -[ - [ "TEST_CASE", "_init_deinit_tests_8cpp.html#a69680e2934e7ec3c6a1771270dc59f05", null ], - [ "TEST_CASE", "_init_deinit_tests_8cpp.html#ac4fb371054271d54830b58cc164dc0f6", null ], - [ "TEST_CASE", "_init_deinit_tests_8cpp.html#a6ed5310154fb7e7f290e619e6fbed708", null ], - [ "TEST_CASE", "_init_deinit_tests_8cpp.html#a96d79e5c8f3096a207d806be926af15b", null ], - [ "TEST_CASE", "_init_deinit_tests_8cpp.html#ab8015ecd4179bc39223921d6eef1165a", null ], - [ "TEST_CASE", "_init_deinit_tests_8cpp.html#ad71fea7e4a2e587d48d2bf7fadd711cc", null ], - [ "TEST_CASE", "_init_deinit_tests_8cpp.html#a9f7d58c894a252a5d5f4926f43c1da05", null ] -]; \ No newline at end of file diff --git a/documentation/html/_init_deinit_tests_8cpp__incl.map b/documentation/html/_init_deinit_tests_8cpp__incl.map deleted file mode 100644 index 14857cf..0000000 --- a/documentation/html/_init_deinit_tests_8cpp__incl.map +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_init_deinit_tests_8cpp__incl.md5 b/documentation/html/_init_deinit_tests_8cpp__incl.md5 deleted file mode 100644 index e6fb90a..0000000 --- a/documentation/html/_init_deinit_tests_8cpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -16d2f71c23d2ba4bf9ce8a27e1d3f2a0 \ No newline at end of file diff --git a/documentation/html/_init_deinit_tests_8cpp__incl.png b/documentation/html/_init_deinit_tests_8cpp__incl.png deleted file mode 100644 index fcdff0f..0000000 Binary files a/documentation/html/_init_deinit_tests_8cpp__incl.png and /dev/null differ diff --git a/documentation/html/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.map b/documentation/html/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.map deleted file mode 100644 index f32e2f5..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.map +++ /dev/null @@ -1,29 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.md5 b/documentation/html/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.md5 deleted file mode 100644 index b073c61..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -64d3863693f55fb40e5c863d899c319c \ No newline at end of file diff --git a/documentation/html/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.png b/documentation/html/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.png deleted file mode 100644 index 2c40b0f..0000000 Binary files a/documentation/html/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.png and /dev/null differ diff --git a/documentation/html/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.map b/documentation/html/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.map deleted file mode 100644 index 65f74e6..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.map +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.md5 b/documentation/html/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.md5 deleted file mode 100644 index 4d63be8..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -39b96ab0a1e474640b1b44c7d7f7b204 \ No newline at end of file diff --git a/documentation/html/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.png b/documentation/html/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.png deleted file mode 100644 index 6c83596..0000000 Binary files a/documentation/html/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.png and /dev/null differ diff --git a/documentation/html/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.map b/documentation/html/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.map deleted file mode 100644 index 3c9a547..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.map +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.md5 b/documentation/html/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.md5 deleted file mode 100644 index 97b6bbf..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0c439ca96468053d82fd88a4544d028a \ No newline at end of file diff --git a/documentation/html/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.png b/documentation/html/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.png deleted file mode 100644 index 81074bd..0000000 Binary files a/documentation/html/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.png and /dev/null differ diff --git a/documentation/html/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.map b/documentation/html/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.map deleted file mode 100644 index e055405..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.map +++ /dev/null @@ -1,81 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.md5 b/documentation/html/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.md5 deleted file mode 100644 index b377c95..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -24522c05ba59e36f919ab7878909d19f \ No newline at end of file diff --git a/documentation/html/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.png b/documentation/html/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.png deleted file mode 100644 index d644fc7..0000000 Binary files a/documentation/html/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.png and /dev/null differ diff --git a/documentation/html/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.map b/documentation/html/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.map deleted file mode 100644 index 5d06214..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.md5 b/documentation/html/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.md5 deleted file mode 100644 index 56eed1b..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fe162be952e3e656b6e0a54693b04436 \ No newline at end of file diff --git a/documentation/html/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.png b/documentation/html/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.png deleted file mode 100644 index 35c0ab9..0000000 Binary files a/documentation/html/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.png and /dev/null differ diff --git a/documentation/html/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.map b/documentation/html/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.map deleted file mode 100644 index 4377358..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.map +++ /dev/null @@ -1,102 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.md5 b/documentation/html/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.md5 deleted file mode 100644 index c580d6a..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d7ee9ec6bd7e5f28476e39c92e0249c9 \ No newline at end of file diff --git a/documentation/html/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.png b/documentation/html/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.png deleted file mode 100644 index ea23c00..0000000 Binary files a/documentation/html/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.png and /dev/null differ diff --git a/documentation/html/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.map b/documentation/html/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.map deleted file mode 100644 index add4689..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.md5 b/documentation/html/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.md5 deleted file mode 100644 index 4fd65c4..0000000 --- a/documentation/html/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -203f70af5cf963caa778454f6e9f7069 \ No newline at end of file diff --git a/documentation/html/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.png b/documentation/html/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.png deleted file mode 100644 index 8b43dd6..0000000 Binary files a/documentation/html/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.png and /dev/null differ diff --git a/documentation/html/_multi_report_tests_8cpp.html b/documentation/html/_multi_report_tests_8cpp.html deleted file mode 100644 index 0771fb4..0000000 --- a/documentation/html/_multi_report_tests_8cpp.html +++ /dev/null @@ -1,858 +0,0 @@ - - - - - - - -esp32_BNO08x: MultiReportTests.cpp File Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
- -
MultiReportTests.cpp File Reference
-
-
-
#include "unity.h"
-#include "../include/BNO08xTestHelper.hpp"
-
-Include dependency graph for MultiReportTests.cpp:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
- - - - - - - - - - - - - -

-Functions

 TEST_CASE ("BNO08x Driver Creation for [MultiReportEnableDisable] Tests", "[MultiReportEnableDisable]")
 
 TEST_CASE ("Dual Report Enable/Disable", "[MultiReportEnableDisable]")
 
 TEST_CASE ("Tri Report Enable/Disable", "[MultiReportEnableDisable]")
 
 TEST_CASE ("Quad Report Enable/Disable", "[MultiReportEnableDisable]")
 
 TEST_CASE ("Hex Report Enable", "[MultiReportEnableDisable]")
 
 TEST_CASE ("BNO08x Driver Cleanup for [MultiReportEnableDisable] Tests", "[MultiReportEnableDisable]")
 
-

Function Documentation

- -

◆ TEST_CASE() [1/6]

- -
-
- - - - - - - - - - - -
TEST_CASE ("BNO08x Driver Cleanup for Tests" [MultiReportEnableDisable],
"" [MultiReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ TEST_CASE() [2/6]

- -
-
- - - - - - - - - - - -
TEST_CASE ("BNO08x Driver Creation for Tests" [MultiReportEnableDisable],
"" [MultiReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [3/6]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Dual Report Enable/Disable" ,
"" [MultiReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [4/6]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Hex Report Enable" ,
"" [MultiReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [5/6]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Quad Report Enable/Disable" ,
"" [MultiReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [6/6]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Tri Report Enable/Disable" ,
"" [MultiReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
-
-
- - - - diff --git a/documentation/html/_multi_report_tests_8cpp.js b/documentation/html/_multi_report_tests_8cpp.js deleted file mode 100644 index cc751a5..0000000 --- a/documentation/html/_multi_report_tests_8cpp.js +++ /dev/null @@ -1,9 +0,0 @@ -var _multi_report_tests_8cpp = -[ - [ "TEST_CASE", "_multi_report_tests_8cpp.html#ac92ec06fe64f7bedbbe37dee3e64c090", null ], - [ "TEST_CASE", "_multi_report_tests_8cpp.html#a1fd7b6a0d4dbb7f91fd5691b5b054bda", null ], - [ "TEST_CASE", "_multi_report_tests_8cpp.html#aa9e0389fa75046b52d13286af2c3b2a7", null ], - [ "TEST_CASE", "_multi_report_tests_8cpp.html#ad96cfd7c30e8693897688ce24bb53996", null ], - [ "TEST_CASE", "_multi_report_tests_8cpp.html#a1438f6b8587b635b6096dda2927fa9a1", null ], - [ "TEST_CASE", "_multi_report_tests_8cpp.html#a915d6c272bf95057a8bb22abfb307882", null ] -]; \ No newline at end of file diff --git a/documentation/html/_multi_report_tests_8cpp__incl.map b/documentation/html/_multi_report_tests_8cpp__incl.map deleted file mode 100644 index 89a8064..0000000 --- a/documentation/html/_multi_report_tests_8cpp__incl.map +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_multi_report_tests_8cpp__incl.md5 b/documentation/html/_multi_report_tests_8cpp__incl.md5 deleted file mode 100644 index 32f4ae0..0000000 --- a/documentation/html/_multi_report_tests_8cpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -c6c68b5c50d92d36b5658b81191b1e92 \ No newline at end of file diff --git a/documentation/html/_multi_report_tests_8cpp__incl.png b/documentation/html/_multi_report_tests_8cpp__incl.png deleted file mode 100644 index 366296e..0000000 Binary files a/documentation/html/_multi_report_tests_8cpp__incl.png and /dev/null differ diff --git a/documentation/html/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.map b/documentation/html/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.map deleted file mode 100644 index c72afc6..0000000 --- a/documentation/html/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.map +++ /dev/null @@ -1,106 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.md5 b/documentation/html/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.md5 deleted file mode 100644 index b85efda..0000000 --- a/documentation/html/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f627e93d5b7fb68fba5a14f3fcf36a3c \ No newline at end of file diff --git a/documentation/html/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.png b/documentation/html/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.png deleted file mode 100644 index e5d6bda..0000000 Binary files a/documentation/html/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.png and /dev/null differ diff --git a/documentation/html/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.map b/documentation/html/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.map deleted file mode 100644 index 2d0ed09..0000000 --- a/documentation/html/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.map +++ /dev/null @@ -1,101 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.md5 b/documentation/html/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.md5 deleted file mode 100644 index 04150ea..0000000 --- a/documentation/html/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b3c196a6ebab141b340f0e0a7846097c \ No newline at end of file diff --git a/documentation/html/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.png b/documentation/html/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.png deleted file mode 100644 index e0e351a..0000000 Binary files a/documentation/html/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.png and /dev/null differ diff --git a/documentation/html/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.map b/documentation/html/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.map deleted file mode 100644 index f186c06..0000000 --- a/documentation/html/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.map +++ /dev/null @@ -1,98 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.md5 b/documentation/html/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.md5 deleted file mode 100644 index 4c65b04..0000000 --- a/documentation/html/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c6384cdaafebb377711bee2f391ceeb1 \ No newline at end of file diff --git a/documentation/html/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.png b/documentation/html/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.png deleted file mode 100644 index 123eebb..0000000 Binary files a/documentation/html/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.png and /dev/null differ diff --git a/documentation/html/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.map b/documentation/html/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.map deleted file mode 100644 index f39ad3e..0000000 --- a/documentation/html/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.map +++ /dev/null @@ -1,90 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.md5 b/documentation/html/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.md5 deleted file mode 100644 index 036128c..0000000 --- a/documentation/html/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -12ecd4053e04e7c98394098fb2d4b90e \ No newline at end of file diff --git a/documentation/html/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.png b/documentation/html/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.png deleted file mode 100644 index 08ec9c4..0000000 Binary files a/documentation/html/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.png and /dev/null differ diff --git a/documentation/html/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.map b/documentation/html/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.map deleted file mode 100644 index 1591bdf..0000000 --- a/documentation/html/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.md5 b/documentation/html/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.md5 deleted file mode 100644 index d2fd7a6..0000000 --- a/documentation/html/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -20530a0195add9876a81f3eca1f08dca \ No newline at end of file diff --git a/documentation/html/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.png b/documentation/html/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.png deleted file mode 100644 index 193fc0f..0000000 Binary files a/documentation/html/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.png and /dev/null differ diff --git a/documentation/html/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.map b/documentation/html/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.map deleted file mode 100644 index 044d017..0000000 --- a/documentation/html/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.map +++ /dev/null @@ -1,118 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.md5 b/documentation/html/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.md5 deleted file mode 100644 index e7ee86b..0000000 --- a/documentation/html/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -43bf049e5eb2b93620e1fa14ee332eb8 \ No newline at end of file diff --git a/documentation/html/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.png b/documentation/html/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.png deleted file mode 100644 index e0f99df..0000000 Binary files a/documentation/html/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.png and /dev/null differ diff --git a/documentation/html/_r_e_a_d_m_e_8md.html b/documentation/html/_r_e_a_d_m_e_8md.html deleted file mode 100644 index e1437f4..0000000 --- a/documentation/html/_r_e_a_d_m_e_8md.html +++ /dev/null @@ -1,108 +0,0 @@ - - - - - - - -esp32_BNO08x: README.md File Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
README.md File Reference
-
-
-
-
- - - - diff --git a/documentation/html/_single_report_tests_8cpp.html b/documentation/html/_single_report_tests_8cpp.html deleted file mode 100644 index 1022069..0000000 --- a/documentation/html/_single_report_tests_8cpp.html +++ /dev/null @@ -1,2087 +0,0 @@ - - - - - - - -esp32_BNO08x: SingleReportTests.cpp File Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
- -
SingleReportTests.cpp File Reference
-
-
-
#include "unity.h"
-#include "../include/BNO08xTestHelper.hpp"
-
-Include dependency graph for SingleReportTests.cpp:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

-Functions

 TEST_CASE ("BNO08x Driver Creation for [SingleReportEnableDisable] Tests", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable Incorrect Report", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable Rotation Vector", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable Game Rotation Vector", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable ARVR Stabilized Rotation Vector", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable ARVR Stabilized Game Rotation Vector", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable Gyro Integrated Rotation Vector", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable Uncalibrated Gyro", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable Calibrated Gyro", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable Accelerometer", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable Linear Accelerometer", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable Gravity", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable Magnetometer", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable Step Counter", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable Stability Classifier", "[SingleReportEnableDisable]")
 
 TEST_CASE ("Enable/Disable Activity Classifier", "[SingleReportEnableDisable]")
 
 TEST_CASE ("BNO08x Driver Cleanup for [SingleReportEnableDisable] Tests", "[SingleReportEnableDisable]")
 
- - - - - -

-Variables

static const constexpr uint8_t RX_REPORT_TRIAL_CNT = 5
 
static const constexpr uint32_t REPORT_PERIOD = 100000UL
 
-

Function Documentation

- -

◆ TEST_CASE() [1/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("BNO08x Driver Cleanup for Tests" [SingleReportEnableDisable],
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ TEST_CASE() [2/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("BNO08x Driver Creation for Tests" [SingleReportEnableDisable],
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [3/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable Incorrect Report" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [4/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable Accelerometer" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [5/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable Activity Classifier" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [6/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable ARVR Stabilized Game Rotation Vector" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [7/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable ARVR Stabilized Rotation Vector" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [8/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable Calibrated Gyro" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [9/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable Game Rotation Vector" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [10/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable Gravity" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [11/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable Gyro Integrated Rotation Vector" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [12/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable Linear Accelerometer" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [13/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable Magnetometer" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [14/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable Rotation Vector" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [15/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable Stability Classifier" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [16/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable Step Counter" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ TEST_CASE() [17/17]

- -
-
- - - - - - - - - - - -
TEST_CASE ("Enable/Disable Uncalibrated Gyro" ,
"" [SingleReportEnableDisable] )
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
-

Variable Documentation

- -

◆ REPORT_PERIOD

- -
-
- - - - - -
- - - - -
const constexpr uint32_t REPORT_PERIOD = 100000UL
-
-staticconstexpr
-
- -
-
- -

◆ RX_REPORT_TRIAL_CNT

- -
-
- - - - - -
- - - - -
const constexpr uint8_t RX_REPORT_TRIAL_CNT = 5
-
-staticconstexpr
-
- -
-
-
-
- - - - diff --git a/documentation/html/_single_report_tests_8cpp.js b/documentation/html/_single_report_tests_8cpp.js deleted file mode 100644 index 1f871f0..0000000 --- a/documentation/html/_single_report_tests_8cpp.js +++ /dev/null @@ -1,22 +0,0 @@ -var _single_report_tests_8cpp = -[ - [ "TEST_CASE", "_single_report_tests_8cpp.html#a697ac897c8756d7553854e52229d36f5", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#aac644123799c1f836d379c9789a064ab", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#af30c5c1549bda77b45a1e6fb5f76844a", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#aaefa1a1d4b3c190b7f46bb7f42512949", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#a098111e0f361615318674b5b1b05ece4", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#a35b0417a053d9fbf61a91a2110c3495c", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#af9d07441bd8651bc21743664b7f99bb8", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#ace1544ccc126d0b9eadd433f9cb41486", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#a90980a9fc26b3a692ab2529c9f8e4747", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#ab9b4ae43e33572d90c4c889452cd91ee", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#a713376354af2a970230882e2a487050e", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#ae4d70e11995e36808b6390b171aba0e8", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#a429f6e7897a9609ddd093d66b6f7b1ff", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#ae436161f7f0085f01ce63d9373944ae8", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#acf249e215fca056266de6e833875925e", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#a9f2e049a5b61721869c5f4757e313502", null ], - [ "TEST_CASE", "_single_report_tests_8cpp.html#a3cce613b379b768244a176a32b37667c", null ], - [ "REPORT_PERIOD", "_single_report_tests_8cpp.html#a4b80e39a1f48d801615a1f7baa210071", null ], - [ "RX_REPORT_TRIAL_CNT", "_single_report_tests_8cpp.html#a20cd776c25ed6d39b2dcb95d155cfbda", null ] -]; \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp__incl.map b/documentation/html/_single_report_tests_8cpp__incl.map deleted file mode 100644 index cf7248c..0000000 --- a/documentation/html/_single_report_tests_8cpp__incl.map +++ /dev/null @@ -1,48 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp__incl.md5 b/documentation/html/_single_report_tests_8cpp__incl.md5 deleted file mode 100644 index 039a0e7..0000000 --- a/documentation/html/_single_report_tests_8cpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -ff0e15842242466ec02502d08007aa50 \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp__incl.png b/documentation/html/_single_report_tests_8cpp__incl.png deleted file mode 100644 index 2f7bd61..0000000 Binary files a/documentation/html/_single_report_tests_8cpp__incl.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.map b/documentation/html/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.map deleted file mode 100644 index a8d95f7..0000000 --- a/documentation/html/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.map +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.md5 deleted file mode 100644 index 7f2d875..0000000 --- a/documentation/html/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3f30ef68de9d206f1e938979330ce274 \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.png b/documentation/html/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.png deleted file mode 100644 index 8175d41..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.map b/documentation/html/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.map deleted file mode 100644 index 1a893be..0000000 --- a/documentation/html/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.map +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.md5 deleted file mode 100644 index b06b87a..0000000 --- a/documentation/html/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ef7cff5373ef979221e07539968bdc8c \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.png b/documentation/html/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.png deleted file mode 100644 index 7fb86b0..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.map b/documentation/html/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.map deleted file mode 100644 index 2d784e9..0000000 --- a/documentation/html/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.map +++ /dev/null @@ -1,84 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.md5 deleted file mode 100644 index 63851e0..0000000 --- a/documentation/html/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -95ad4f6bbccb5f36243233942dfd986a \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.png b/documentation/html/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.png deleted file mode 100644 index d01cde3..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.map b/documentation/html/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.map deleted file mode 100644 index f028e56..0000000 --- a/documentation/html/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.map +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.md5 deleted file mode 100644 index 066728e..0000000 --- a/documentation/html/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5a9b84d395ab098a5609179a19b7bce4 \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.png b/documentation/html/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.png deleted file mode 100644 index 201d644..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.map b/documentation/html/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.map deleted file mode 100644 index 1591bdf..0000000 --- a/documentation/html/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.md5 deleted file mode 100644 index d2fd7a6..0000000 --- a/documentation/html/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -20530a0195add9876a81f3eca1f08dca \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.png b/documentation/html/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.png deleted file mode 100644 index 193fc0f..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.map b/documentation/html/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.map deleted file mode 100644 index b2300e1..0000000 --- a/documentation/html/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.map +++ /dev/null @@ -1,84 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.md5 deleted file mode 100644 index a7f5506..0000000 --- a/documentation/html/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5de701c659bf1e2a2990a770643aefe4 \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.png b/documentation/html/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.png deleted file mode 100644 index 371d1c0..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.map b/documentation/html/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.map deleted file mode 100644 index 0c686f2..0000000 --- a/documentation/html/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.map +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.md5 deleted file mode 100644 index 22155fb..0000000 --- a/documentation/html/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b00257ab69c3e94e6a6df68ab082542d \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.png b/documentation/html/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.png deleted file mode 100644 index 7209a1b..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.map b/documentation/html/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.map deleted file mode 100644 index 85c7c8b..0000000 --- a/documentation/html/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.map +++ /dev/null @@ -1,84 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.md5 deleted file mode 100644 index 39471a5..0000000 --- a/documentation/html/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -342ec5885a18f610f8c6f8e49d2a6b12 \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.png b/documentation/html/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.png deleted file mode 100644 index 8288652..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.map b/documentation/html/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.map deleted file mode 100644 index 2d0ed09..0000000 --- a/documentation/html/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.map +++ /dev/null @@ -1,101 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.md5 deleted file mode 100644 index 04150ea..0000000 --- a/documentation/html/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b3c196a6ebab141b340f0e0a7846097c \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.png b/documentation/html/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.png deleted file mode 100644 index e0e351a..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.map b/documentation/html/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.map deleted file mode 100644 index 700f069..0000000 --- a/documentation/html/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.map +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.md5 deleted file mode 100644 index d938c39..0000000 --- a/documentation/html/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -048a29047414617a0ba7789c5d340be2 \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.png b/documentation/html/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.png deleted file mode 100644 index 48de0d1..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.map b/documentation/html/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.map deleted file mode 100644 index df9f971..0000000 --- a/documentation/html/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.map +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.md5 deleted file mode 100644 index 04fc0ba..0000000 --- a/documentation/html/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7646156bc91d37c70d94d8d627db522e \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.png b/documentation/html/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.png deleted file mode 100644 index cce5836..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.map b/documentation/html/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.map deleted file mode 100644 index 21611e3..0000000 --- a/documentation/html/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.map +++ /dev/null @@ -1,84 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.md5 deleted file mode 100644 index e6d64b3..0000000 --- a/documentation/html/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -89b7d982d3c44ca90f98d4e81212e9a6 \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.png b/documentation/html/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.png deleted file mode 100644 index ac6e528..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.map b/documentation/html/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.map deleted file mode 100644 index 9c1c365..0000000 --- a/documentation/html/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.map +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.md5 deleted file mode 100644 index ed3c5b6..0000000 --- a/documentation/html/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -73a5aa84e51232886ea55d0dc22bccdc \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.png b/documentation/html/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.png deleted file mode 100644 index 2ea8d2f..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.map b/documentation/html/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.map deleted file mode 100644 index c8781cc..0000000 --- a/documentation/html/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.map +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.md5 deleted file mode 100644 index 23bc82f..0000000 --- a/documentation/html/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fafb649c715c381cae1e073d2a1fd02b \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.png b/documentation/html/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.png deleted file mode 100644 index 4f9f512..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.map b/documentation/html/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.map deleted file mode 100644 index 196b223..0000000 --- a/documentation/html/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.map +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.md5 deleted file mode 100644 index e015f26..0000000 --- a/documentation/html/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b6f71bdc3fd103a39b5be1925050b513 \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.png b/documentation/html/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.png deleted file mode 100644 index b01e8ca..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.map b/documentation/html/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.map deleted file mode 100644 index acd8a56..0000000 --- a/documentation/html/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.map +++ /dev/null @@ -1,84 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.md5 deleted file mode 100644 index dd01047..0000000 --- a/documentation/html/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4abe46cb78ef7f47650ba168436777ae \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.png b/documentation/html/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.png deleted file mode 100644 index 0ef8b21..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.png and /dev/null differ diff --git a/documentation/html/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.map b/documentation/html/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.map deleted file mode 100644 index 5068517..0000000 --- a/documentation/html/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.map +++ /dev/null @@ -1,86 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.md5 b/documentation/html/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.md5 deleted file mode 100644 index 559a748..0000000 --- a/documentation/html/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f1c914e2c21ecc806403a6d35e215aeb \ No newline at end of file diff --git a/documentation/html/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.png b/documentation/html/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.png deleted file mode 100644 index cf8cd6c..0000000 Binary files a/documentation/html/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.png and /dev/null differ diff --git a/documentation/html/annotated.html b/documentation/html/annotated.html deleted file mode 100644 index 0f1b5a3..0000000 --- a/documentation/html/annotated.html +++ /dev/null @@ -1,120 +0,0 @@ - - - - - - - -esp32_BNO08x: Class List - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Class List
-
-
-
Here are the classes, structs, unions and interfaces with brief descriptions:
-
[detail level 12]
- - - - - - - - - -
 CBNO08xBNO08x IMU driver class
 Cbno08x_init_status_tHolds info about which functionality has been successfully initialized (used by deconstructor during cleanup)
 Cbno08x_report_period_tracker_t
 Cbno08x_rx_packet_tHolds data that is received over spi
 Cbno08x_tx_packet_tHolds data that is sent over spi
 Cbno08x_config_tIMU configuration settings passed into constructor
 CBNO08xTestHelperBNO08x unit test helper class
 Cimu_report_data_tIMU configuration settings passed into constructor
 CBNO08xTestSuiteBNO08x unit test launch point class
-
-
-
- - - - diff --git a/documentation/html/annotated_dup.js b/documentation/html/annotated_dup.js deleted file mode 100644 index 96af5a6..0000000 --- a/documentation/html/annotated_dup.js +++ /dev/null @@ -1,7 +0,0 @@ -var annotated_dup = -[ - [ "BNO08x", "class_b_n_o08x.html", "class_b_n_o08x" ], - [ "bno08x_config_t", "structbno08x__config__t.html", "structbno08x__config__t" ], - [ "BNO08xTestHelper", "class_b_n_o08x_test_helper.html", "class_b_n_o08x_test_helper" ], - [ "BNO08xTestSuite", "class_b_n_o08x_test_suite.html", "class_b_n_o08x_test_suite" ] -]; \ No newline at end of file diff --git a/documentation/html/bc_s.png b/documentation/html/bc_s.png deleted file mode 100644 index 224b29a..0000000 Binary files a/documentation/html/bc_s.png and /dev/null differ diff --git a/documentation/html/bc_sd.png b/documentation/html/bc_sd.png deleted file mode 100644 index 31ca888..0000000 Binary files a/documentation/html/bc_sd.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x-members.html b/documentation/html/class_b_n_o08x-members.html deleted file mode 100644 index d121ba9..0000000 --- a/documentation/html/class_b_n_o08x-members.html +++ /dev/null @@ -1,490 +0,0 @@ - - - - - - - -esp32_BNO08x: Member List - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
BNO08x Member List
-
-
- -

This is the complete list of members for BNO08x, including all inherited members.

- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
accel_accuracyBNO08xprivate
accel_lin_accuracyBNO08xprivate
ACCELEROMETER_Q1BNO08xstatic
activity_classifierBNO08xprivate
activity_confidencesBNO08xprivate
ANGULAR_VELOCITY_Q1BNO08xstatic
BNO08x(bno08x_config_t imu_config=bno08x_config_t())BNO08x
bno08x_init_status_t typedefBNO08xprivate
bno08x_report_period_tracker_t typedefBNO08xprivate
bno08x_rx_packet_t typedefBNO08xprivate
bno08x_tx_packet_t typedefBNO08xprivate
BNO08xTestHelperBNO08xfriend
bus_configBNO08xprivate
CALIBRATE_ACCELBNO08xprivatestatic
CALIBRATE_ACCEL_GYRO_MAGBNO08xprivatestatic
calibrate_accelerometer()BNO08x
calibrate_all()BNO08x
CALIBRATE_GYROBNO08xprivatestatic
calibrate_gyro()BNO08x
CALIBRATE_MAGBNO08xprivatestatic
calibrate_magnetometer()BNO08x
CALIBRATE_PLANAR_ACCELBNO08xprivatestatic
calibrate_planar_accelerometer()BNO08x
CALIBRATE_STOPBNO08xprivatestatic
calibration_complete()BNO08x
calibration_statusBNO08xprivate
cb_listBNO08xprivate
CHANNEL_COMMAND enum valueBNO08xprivate
CHANNEL_CONTROL enum valueBNO08xprivate
CHANNEL_EXECUTABLE enum valueBNO08xprivate
CHANNEL_GYRO enum valueBNO08xprivate
CHANNEL_REPORTS enum valueBNO08xprivate
CHANNEL_WAKE_REPORTS enum valueBNO08xprivate
channels_t enum nameBNO08xprivate
clear_tare()BNO08x
CMD_EXECUTION_DELAY_MSBNO08xprivatestatic
COMMAND_CLEAR_DCDBNO08xprivatestatic
COMMAND_COUNTERBNO08xprivatestatic
COMMAND_DCDBNO08xprivatestatic
COMMAND_DCD_PERIOD_SAVEBNO08xprivatestatic
COMMAND_ERRORSBNO08xprivatestatic
COMMAND_INITIALIZEBNO08xprivatestatic
COMMAND_ME_CALIBRATEBNO08xprivatestatic
COMMAND_OSCILLATORBNO08xprivatestatic
COMMAND_TAREBNO08xprivatestatic
current_slowest_report_IDBNO08xprivate
data_available(bool ignore_no_reports_enabled=false)BNO08x
data_proc_task()BNO08xprivate
data_proc_task_hdlBNO08xprivate
data_proc_task_trampoline(void *arg)BNO08xprivatestatic
deinit_gpio()BNO08xprivate
deinit_gpio_inputs()BNO08xprivate
deinit_gpio_outputs()BNO08xprivate
deinit_hint_isr()BNO08xprivate
deinit_spi()BNO08xprivate
disable_accelerometer()BNO08x
disable_activity_classifier()BNO08x
disable_ARVR_stabilized_game_rotation_vector()BNO08x
disable_ARVR_stabilized_rotation_vector()BNO08x
disable_calibrated_gyro()BNO08x
disable_game_rotation_vector()BNO08x
disable_gravity()BNO08x
disable_gyro_integrated_rotation_vector()BNO08x
disable_linear_accelerometer()BNO08x
disable_magnetometer()BNO08x
disable_raw_mems_accelerometer()BNO08x
disable_raw_mems_gyro()BNO08x
disable_raw_mems_magnetometer()BNO08x
disable_report(uint8_t report_ID, const EventBits_t report_evt_grp_bit)BNO08xprivate
disable_rotation_vector()BNO08x
disable_stability_classifier()BNO08x
disable_step_counter()BNO08x
disable_tap_detector()BNO08x
disable_uncalibrated_gyro()BNO08x
enable_accelerometer(uint32_t time_between_reports)BNO08x
enable_activity_classifier(uint32_t time_between_reports, BNO08xActivityEnable activities_to_enable, uint8_t(&activity_confidence_vals)[9])BNO08x
enable_ARVR_stabilized_game_rotation_vector(uint32_t time_between_reports)BNO08x
enable_ARVR_stabilized_rotation_vector(uint32_t time_between_reports)BNO08x
enable_calibrated_gyro(uint32_t time_between_reports)BNO08x
enable_game_rotation_vector(uint32_t time_between_reports)BNO08x
enable_gravity(uint32_t time_between_reports)BNO08x
enable_gyro_integrated_rotation_vector(uint32_t time_between_reports)BNO08x
enable_linear_accelerometer(uint32_t time_between_reports)BNO08x
enable_magnetometer(uint32_t time_between_reports)BNO08x
enable_raw_mems_accelerometer(uint32_t time_between_reports)BNO08x
enable_raw_mems_gyro(uint32_t time_between_reports)BNO08x
enable_raw_mems_magnetometer(uint32_t time_between_reports)BNO08x
enable_report(uint8_t report_ID, uint32_t time_between_reports, const EventBits_t report_evt_grp_bit, uint32_t special_config=0)BNO08xprivate
enable_rotation_vector(uint32_t time_between_reports)BNO08x
enable_stability_classifier(uint32_t time_between_reports)BNO08x
enable_step_counter(uint32_t time_between_reports)BNO08x
enable_tap_detector(uint32_t time_between_reports)BNO08x
enable_uncalibrated_gyro(uint32_t time_between_reports)BNO08x
end_calibration()BNO08x
evt_grp_report_enBNO08xprivate
EVT_GRP_RPT_ACCELEROMETER_BITBNO08xprivatestatic
EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BITBNO08xprivatestatic
EVT_GRP_RPT_ALL_BITSBNO08xprivatestatic
EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BITBNO08xprivatestatic
EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BITBNO08xprivatestatic
EVT_GRP_RPT_GAME_ROTATION_VECTOR_BITBNO08xprivatestatic
EVT_GRP_RPT_GRAVITY_BITBNO08xprivatestatic
EVT_GRP_RPT_GYRO_BITBNO08xprivatestatic
EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BITBNO08xprivatestatic
EVT_GRP_RPT_GYRO_UNCALIBRATED_BITBNO08xprivatestatic
EVT_GRP_RPT_LINEAR_ACCELEROMETER_BITBNO08xprivatestatic
EVT_GRP_RPT_MAGNETOMETER_BITBNO08xprivatestatic
EVT_GRP_RPT_RAW_ACCELEROMETER_BITBNO08xprivatestatic
EVT_GRP_RPT_RAW_GYRO_BITBNO08xprivatestatic
EVT_GRP_RPT_RAW_MAGNETOMETER_BITBNO08xprivatestatic
EVT_GRP_RPT_ROTATION_VECTOR_BITBNO08xprivatestatic
EVT_GRP_RPT_STABILITY_CLASSIFIER_BITBNO08xprivatestatic
EVT_GRP_RPT_STEP_COUNTER_BITBNO08xprivatestatic
EVT_GRP_RPT_TAP_DETECTOR_BITBNO08xprivatestatic
evt_grp_spiBNO08xprivate
EVT_GRP_SPI_RX_DONE_BITBNO08xprivatestatic
EVT_GRP_SPI_RX_INVALID_PACKET_BITBNO08xprivatestatic
EVT_GRP_SPI_RX_VALID_PACKET_BITBNO08xprivatestatic
EVT_GRP_SPI_TX_DONE_BITBNO08xprivatestatic
evt_grp_task_flowBNO08xprivate
EVT_GRP_TSK_FLW_RUNNING_BITBNO08xprivatestatic
first_bootBNO08xprivate
flush_rx_packets(uint8_t flush_count)BNO08xprivate
FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read)BNO08x
FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size)BNO08x
FRS_read_word(uint16_t record_ID, uint8_t word_number)BNO08x
FRS_RECORD_ID_ACCELEROMETERBNO08xstatic
FRS_RECORD_ID_GYROSCOPE_CALIBRATEDBNO08xstatic
FRS_RECORD_ID_MAGNETIC_FIELD_CALIBRATEDBNO08xstatic
FRS_RECORD_ID_ROTATION_VECTORBNO08xstatic
get_accel(float &x, float &y, float &z, BNO08xAccuracy &accuracy)BNO08x
get_accel_accuracy()BNO08x
get_accel_X()BNO08x
get_accel_Y()BNO08x
get_accel_Z()BNO08x
get_activity_classifier()BNO08x
get_calibrated_gyro_velocity(float &x, float &y, float &z)BNO08x
get_calibrated_gyro_velocity_X()BNO08x
get_calibrated_gyro_velocity_Y()BNO08x
get_calibrated_gyro_velocity_Z()BNO08x
get_gravity(float &x, float &y, float &z, BNO08xAccuracy &accuracy)BNO08x
get_gravity_accuracy()BNO08x
get_gravity_X()BNO08x
get_gravity_Y()BNO08x
get_gravity_Z()BNO08x
get_integrated_gyro_velocity(float &x, float &y, float &z)BNO08x
get_integrated_gyro_velocity_X()BNO08x
get_integrated_gyro_velocity_Y()BNO08x
get_integrated_gyro_velocity_Z()BNO08x
get_linear_accel(float &x, float &y, float &z, BNO08xAccuracy &accuracy)BNO08x
get_linear_accel_accuracy()BNO08x
get_linear_accel_X()BNO08x
get_linear_accel_Y()BNO08x
get_linear_accel_Z()BNO08x
get_magf(float &x, float &y, float &z, BNO08xAccuracy &accuracy)BNO08x
get_magf_accuracy()BNO08x
get_magf_X()BNO08x
get_magf_Y()BNO08x
get_magf_Z()BNO08x
get_pitch()BNO08x
get_pitch_deg()BNO08x
get_Q1(uint16_t record_ID)BNO08x
get_Q2(uint16_t record_ID)BNO08x
get_Q3(uint16_t record_ID)BNO08x
get_quat(float &i, float &j, float &k, float &real, float &rad_accuracy, BNO08xAccuracy &accuracy)BNO08x
get_quat_accuracy()BNO08x
get_quat_I()BNO08x
get_quat_J()BNO08x
get_quat_K()BNO08x
get_quat_radian_accuracy()BNO08x
get_quat_real()BNO08x
get_range(uint16_t record_ID)BNO08x
get_raw_mems_accel(uint16_t &x, uint16_t &y, uint16_t &z)BNO08x
get_raw_mems_accel_X()BNO08x
get_raw_mems_accel_Y()BNO08x
get_raw_mems_accel_Z()BNO08x
get_raw_mems_gyro(uint16_t &x, uint16_t &y, uint16_t &z)BNO08x
get_raw_mems_gyro_X()BNO08x
get_raw_mems_gyro_Y()BNO08x
get_raw_mems_gyro_Z()BNO08x
get_raw_mems_magf(uint16_t &x, uint16_t &y, uint16_t &z)BNO08x
get_raw_mems_magf_X()BNO08x
get_raw_mems_magf_Y()BNO08x
get_raw_mems_magf_Z()BNO08x
get_reset_reason()BNO08x
get_resolution(uint16_t record_ID)BNO08x
get_roll()BNO08x
get_roll_deg()BNO08x
get_stability_classifier()BNO08x
get_step_count()BNO08x
get_tap_detector()BNO08x
get_time_stamp()BNO08x
get_uncalibrated_gyro_bias_X()BNO08x
get_uncalibrated_gyro_bias_Y()BNO08x
get_uncalibrated_gyro_bias_Z()BNO08x
get_uncalibrated_gyro_velocity(float &x, float &y, float &z, float &bx, float &by, float &bz)BNO08x
get_uncalibrated_gyro_velocity_X()BNO08x
get_uncalibrated_gyro_velocity_Y()BNO08x
get_uncalibrated_gyro_velocity_Z()BNO08x
get_yaw()BNO08x
get_yaw_deg()BNO08x
gravity_accuracyBNO08xprivate
GRAVITY_Q1BNO08xstatic
gravity_XBNO08xprivate
gravity_YBNO08xprivate
gravity_ZBNO08xprivate
GYRO_Q1BNO08xstatic
hard_reset()BNO08x
HARD_RESET_DELAY_MSBNO08xprivatestatic
hint_handler(void *arg)BNO08xprivatestatic
HOST_INT_TIMEOUT_DEFAULT_MSBNO08xprivatestatic
host_int_timeout_msBNO08xprivate
imu_configBNO08xprivate
imu_spi_configBNO08xprivate
init_config_args()BNO08xprivate
init_gpio()BNO08xprivate
init_gpio_inputs()BNO08xprivate
init_gpio_outputs()BNO08xprivate
init_hint_isr()BNO08xprivate
init_spi()BNO08xprivate
init_statusBNO08xprivate
initialize()BNO08x
integrated_gyro_velocity_XBNO08xprivate
integrated_gyro_velocity_YBNO08xprivate
integrated_gyro_velocity_ZBNO08xprivate
kill_all_tasks()BNO08xprivate
largest_sample_period_usBNO08xprivate
launch_tasks()BNO08xprivate
LINEAR_ACCELEROMETER_Q1BNO08xstatic
magf_accuracyBNO08xprivate
MAGNETOMETER_Q1BNO08xstatic
MAX_METADATA_LENGTHBNO08xprivatestatic
mems_raw_accel_XBNO08xprivate
mems_raw_accel_YBNO08xprivate
mems_raw_accel_ZBNO08xprivate
mems_raw_gyro_XBNO08xprivate
mems_raw_gyro_YBNO08xprivate
mems_raw_gyro_ZBNO08xprivate
mems_raw_magf_XBNO08xprivate
mems_raw_magf_YBNO08xprivate
mems_raw_magf_ZBNO08xprivate
meta_dataBNO08xprivate
mode_on()BNO08x
mode_sleep()BNO08x
parse_command_report(bno08x_rx_packet_t *packet)BNO08xprivate
parse_feature_get_response_report(bno08x_rx_packet_t *packet)BNO08xprivate
parse_frs_read_response_report(bno08x_rx_packet_t *packet)BNO08xprivate
parse_gyro_integrated_rotation_vector_report(bno08x_rx_packet_t *packet)BNO08xprivate
parse_input_report(bno08x_rx_packet_t *packet)BNO08xprivate
parse_input_report_data(bno08x_rx_packet_t *packet, uint16_t *data, uint16_t data_length)BNO08xprivate
parse_packet(bno08x_rx_packet_t *packet, bool &notify_users)BNO08xprivate
parse_product_id_report(bno08x_rx_packet_t *packet)BNO08xprivate
print_header(bno08x_rx_packet_t *packet)BNO08xprivate
print_packet(bno08x_rx_packet_t *packet)BNO08xprivate
q_to_float(int16_t fixed_point_value, uint8_t q_point)BNO08x
quat_accuracyBNO08xprivate
queue_calibrate_command(uint8_t _to_calibrate)BNO08xprivate
queue_command(uint8_t command, uint8_t *commands)BNO08xprivate
queue_feature_command(uint8_t report_ID, uint32_t time_between_reports, uint32_t specific_config=0)BNO08xprivate
queue_frs_read_dataBNO08xprivate
queue_packet(uint8_t channel_number, uint8_t data_length, uint8_t *commands)BNO08xprivate
queue_request_product_id_command()BNO08xprivate
queue_reset_reasonBNO08xprivate
queue_rx_dataBNO08xprivate
queue_tare_command(uint8_t command, uint8_t axis=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)BNO08xprivate
queue_tx_dataBNO08xprivate
raw_accel_XBNO08xprivate
raw_accel_YBNO08xprivate
raw_accel_ZBNO08xprivate
raw_bias_XBNO08xprivate
raw_bias_YBNO08xprivate
raw_bias_ZBNO08xprivate
raw_calib_gyro_XBNO08xprivate
raw_calib_gyro_YBNO08xprivate
raw_calib_gyro_ZBNO08xprivate
raw_lin_accel_XBNO08xprivate
raw_lin_accel_YBNO08xprivate
raw_lin_accel_ZBNO08xprivate
raw_magf_XBNO08xprivate
raw_magf_YBNO08xprivate
raw_magf_ZBNO08xprivate
raw_quat_IBNO08xprivate
raw_quat_JBNO08xprivate
raw_quat_KBNO08xprivate
raw_quat_radian_accuracyBNO08xprivate
raw_quat_realBNO08xprivate
raw_uncalib_gyro_XBNO08xprivate
raw_uncalib_gyro_YBNO08xprivate
raw_uncalib_gyro_ZBNO08xprivate
receive_packet()BNO08xprivate
receive_packet_body(bno08x_rx_packet_t *packet)BNO08xprivate
receive_packet_header(bno08x_rx_packet_t *packet)BNO08xprivate
register_cb(std::function< void()> cb_fxn)BNO08x
REPORT_CNTBNO08xprivatestatic
report_ID_to_report_period_tracker_idx(uint8_t report_ID)BNO08xprivatestatic
report_period_trackersBNO08xprivate
request_calibration_status()BNO08x
reset_all_data_to_defaults()BNO08x
ROTATION_VECTOR_ACCURACY_Q1BNO08xstatic
ROTATION_VECTOR_Q1BNO08xstatic
run_full_calibration_routine()BNO08x
RX_DATA_LENGTHBNO08xprivatestatic
save_calibration()BNO08x
save_tare()BNO08x
SCLK_MAX_SPEEDBNO08xprivatestatic
sem_kill_tasksBNO08xprivate
send_packet(bno08x_tx_packet_t *packet)BNO08xprivate
SENSOR_REPORT_ID_ACCELEROMETERBNO08xprivatestatic
SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTORBNO08xprivatestatic
SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTORBNO08xprivatestatic
SENSOR_REPORT_ID_GAME_ROTATION_VECTORBNO08xprivatestatic
SENSOR_REPORT_ID_GEOMAGNETIC_ROTATION_VECTORBNO08xprivatestatic
SENSOR_REPORT_ID_GRAVITYBNO08xprivatestatic
SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTORBNO08xprivatestatic
SENSOR_REPORT_ID_GYROSCOPEBNO08xprivatestatic
SENSOR_REPORT_ID_LINEAR_ACCELERATIONBNO08xprivatestatic
SENSOR_REPORT_ID_MAGNETIC_FIELDBNO08xprivatestatic
SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIERBNO08xprivatestatic
SENSOR_REPORT_ID_RAW_ACCELEROMETERBNO08xprivatestatic
SENSOR_REPORT_ID_RAW_GYROSCOPEBNO08xprivatestatic
SENSOR_REPORT_ID_RAW_MAGNETOMETERBNO08xprivatestatic
SENSOR_REPORT_ID_ROTATION_VECTORBNO08xprivatestatic
SENSOR_REPORT_ID_STABILITY_CLASSIFIERBNO08xprivatestatic
SENSOR_REPORT_ID_STEP_COUNTERBNO08xprivatestatic
SENSOR_REPORT_ID_TAP_DETECTORBNO08xprivatestatic
SENSOR_REPORT_ID_UNCALIBRATED_GYROBNO08xprivatestatic
SHTP_REPORT_BASE_TIMESTAMPBNO08xprivatestatic
SHTP_REPORT_COMMAND_REQUESTBNO08xprivatestatic
SHTP_REPORT_COMMAND_RESPONSEBNO08xprivatestatic
SHTP_REPORT_FRS_READ_REQUESTBNO08xprivatestatic
SHTP_REPORT_FRS_READ_RESPONSEBNO08xprivatestatic
SHTP_REPORT_GET_FEATURE_RESPONSEBNO08xprivatestatic
SHTP_REPORT_PRODUCT_ID_REQUESTBNO08xprivatestatic
SHTP_REPORT_PRODUCT_ID_RESPONSEBNO08xprivatestatic
SHTP_REPORT_SET_FEATURE_COMMANDBNO08xprivatestatic
soft_reset()BNO08x
spi_hdlBNO08xprivate
spi_task()BNO08xprivate
spi_task_hdlBNO08xprivate
spi_task_trampoline(void *arg)BNO08xprivatestatic
spi_transactionBNO08xprivate
stability_classifierBNO08xprivate
step_countBNO08xprivate
TAGBNO08xprivatestatic
tap_detectorBNO08xprivate
TARE_ARVR_STABILIZED_GAME_ROTATION_VECTORBNO08xstatic
TARE_ARVR_STABILIZED_ROTATION_VECTORBNO08xstatic
TARE_AXIS_ALLBNO08xstatic
TARE_AXIS_ZBNO08xstatic
TARE_GAME_ROTATION_VECTORBNO08xstatic
TARE_GEOMAGNETIC_ROTATION_VECTORBNO08xstatic
TARE_GYRO_INTEGRATED_ROTATION_VECTORBNO08xstatic
TARE_NOWBNO08xprivatestatic
tare_now(uint8_t axis_sel=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)BNO08x
TARE_PERSISTBNO08xprivatestatic
TARE_ROTATION_VECTORBNO08xstatic
TARE_SET_REORIENTATIONBNO08xprivatestatic
TASK_CNTBNO08xprivatestatic
time_stampBNO08xprivate
update_accelerometer_data(uint16_t *data, uint8_t status)BNO08xprivate
update_calibrated_gyro_data(uint16_t *data, uint8_t status)BNO08xprivate
update_command_data(bno08x_rx_packet_t *packet)BNO08xprivate
update_gravity_data(uint16_t *data, uint8_t status)BNO08xprivate
update_integrated_gyro_rotation_vector_data(bno08x_rx_packet_t *packet)BNO08xprivate
update_lin_accelerometer_data(uint16_t *data, uint8_t status)BNO08xprivate
update_magf_data(uint16_t *data, uint8_t status)BNO08xprivate
update_personal_activity_classifier_data(bno08x_rx_packet_t *packet)BNO08xprivate
update_raw_accelerometer_data(uint16_t *data)BNO08xprivate
update_raw_gyro_data(uint16_t *data)BNO08xprivate
update_raw_magf_data(uint16_t *data)BNO08xprivate
update_report_period_trackers(uint8_t report_ID, uint32_t new_period)BNO08xprivate
update_rotation_vector_data(uint16_t *data, uint8_t status)BNO08xprivate
update_stability_classifier_data(bno08x_rx_packet_t *packet)BNO08xprivate
update_step_counter_data(uint16_t *data)BNO08xprivate
update_tap_detector_data(bno08x_rx_packet_t *packet)BNO08xprivate
update_uncalibrated_gyro_data(uint16_t *data, uint8_t status)BNO08xprivate
wait_for_data()BNO08xprivate
wait_for_rx_done()BNO08xprivate
wait_for_tx_done()BNO08xprivate
~BNO08x()BNO08x
-
- - - - diff --git a/documentation/html/class_b_n_o08x.html b/documentation/html/class_b_n_o08x.html deleted file mode 100644 index 0963551..0000000 --- a/documentation/html/class_b_n_o08x.html +++ /dev/null @@ -1,17450 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08x Class Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- - -
- -

BNO08x IMU driver class. - More...

- -

#include <BNO08x.hpp>

-
-Collaboration diagram for BNO08x:
-
-
Collaboration graph
- - - - - - - - - -
[legend]
- - - - - - - - - - - - - -

-Classes

struct  bno08x_init_status_t
 Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup). More...
 
struct  bno08x_report_period_tracker_t
 
struct  bno08x_rx_packet_t
 Holds data that is received over spi. More...
 
struct  bno08x_tx_packet_t
 Holds data that is sent over spi. More...
 
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

-Public Member Functions

 BNO08x (bno08x_config_t imu_config=bno08x_config_t())
 BNO08x imu constructor.
 
 ~BNO08x ()
 BNO08x imu deconstructor.
 
bool initialize ()
 Initializes BNO08x sensor.
 
bool hard_reset ()
 Hard resets BNO08x sensor.
 
bool soft_reset ()
 Soft resets BNO08x sensor using executable channel.
 
BNO08xResetReason get_reset_reason ()
 Requests product ID, prints the returned info over serial, and returns the reason for the most resent reset.
 
bool mode_sleep ()
 Puts BNO08x sensor into sleep/low power mode using executable channel.
 
bool mode_on ()
 Turns on/ brings BNO08x sensor out of sleep mode using executable channel.
 
float q_to_float (int16_t fixed_point_value, uint8_t q_point)
 Converts a register value to a float using its associated Q point. (See https://en.wikipedia.org/wiki/Q_(number_format))
 
bool run_full_calibration_routine ()
 Runs full calibration routine.
 
void calibrate_all ()
 Sends command to calibrate accelerometer, gyro, and magnetometer.
 
void calibrate_accelerometer ()
 Sends command to calibrate accelerometer.
 
void calibrate_gyro ()
 Sends command to calibrate gyro.
 
void calibrate_magnetometer ()
 Sends command to calibrate magnetometer.
 
void calibrate_planar_accelerometer ()
 Sends command to calibrate planar accelerometer.
 
void request_calibration_status ()
 Requests ME calibration status from BNO08x (see Ref. Manual 6.4.7.2)
 
bool calibration_complete ()
 Returns true if calibration has completed.
 
void end_calibration ()
 Sends command to end calibration procedure.
 
void save_calibration ()
 Sends command to save internal calibration data (See Ref. Manual 6.4.7).
 
void enable_rotation_vector (uint32_t time_between_reports)
 Sends command to enable rotation vector reports (See Ref. Manual 6.5.18)
 
void enable_game_rotation_vector (uint32_t time_between_reports)
 Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19)
 
void enable_ARVR_stabilized_rotation_vector (uint32_t time_between_reports)
 Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6.5.42)
 
void enable_ARVR_stabilized_game_rotation_vector (uint32_t time_between_reports)
 Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6.5.43)
 
void enable_gyro_integrated_rotation_vector (uint32_t time_between_reports)
 Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6.5.44)
 
void enable_uncalibrated_gyro (uint32_t time_between_reports)
 Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.5.14)
 
void enable_calibrated_gyro (uint32_t time_between_reports)
 Sends command to enable calibrated gyro reports (See Ref. Manual 6.5.13)
 
void enable_accelerometer (uint32_t time_between_reports)
 Sends command to enable accelerometer reports (See Ref. Manual 6.5.9)
 
void enable_linear_accelerometer (uint32_t time_between_reports)
 Sends command to enable linear accelerometer reports (See Ref. Manual 6.5.10)
 
void enable_gravity (uint32_t time_between_reports)
 Sends command to enable gravity reading reports (See Ref. Manual 6.5.11)
 
void enable_magnetometer (uint32_t time_between_reports)
 Sends command to enable magnetometer reports (See Ref. Manual 6.5.16)
 
void enable_tap_detector (uint32_t time_between_reports)
 Sends command to enable tap detector reports (See Ref. Manual 6.5.27)
 
void enable_step_counter (uint32_t time_between_reports)
 Sends command to enable step counter reports (See Ref. Manual 6.5.29)
 
void enable_stability_classifier (uint32_t time_between_reports)
 Sends command to enable activity stability classifier reports (See Ref. Manual 6.5.31)
 
void enable_activity_classifier (uint32_t time_between_reports, BNO08xActivityEnable activities_to_enable, uint8_t(&activity_confidence_vals)[9])
 Sends command to enable activity classifier reports (See Ref. Manual 6.5.36)
 
void enable_raw_mems_gyro (uint32_t time_between_reports)
 Sends command to enable raw MEMs gyro reports (See Ref. Manual 6.5.12)
 
void enable_raw_mems_accelerometer (uint32_t time_between_reports)
 Sends command to enable raw MEMs accelerometer reports (See Ref. Manual 6.5.8)
 
void enable_raw_mems_magnetometer (uint32_t time_between_reports)
 Sends command to enable raw MEMs magnetometer reports (See Ref. Manual 6.5.15)
 
void disable_rotation_vector ()
 Sends command to disable rotation vector reports by setting report interval to 0.
 
void disable_game_rotation_vector ()
 Sends command to disable game rotation vector reports by setting report interval to 0.
 
void disable_ARVR_stabilized_rotation_vector ()
 Sends command to disable ARVR stabilized rotation vector reports by setting report interval to 0.
 
void disable_ARVR_stabilized_game_rotation_vector ()
 Sends command to disable ARVR stabilized game rotation vector reports by setting report interval to 0.
 
void disable_gyro_integrated_rotation_vector ()
 Sends command to disable gyro integrated rotation vector reports by setting report interval to 0.
 
void disable_accelerometer ()
 Sends command to disable accelerometer reports by setting report interval to 0.
 
void disable_linear_accelerometer ()
 Sends command to disable linear accelerometer reports by setting report interval to 0.
 
void disable_gravity ()
 Sends command to disable gravity reports by setting report interval to 0.
 
void disable_calibrated_gyro ()
 Sends command to disable calibrated gyro reports by setting report interval to 0.
 
void disable_uncalibrated_gyro ()
 Sends command to disable uncalibrated gyro reports by setting report interval to 0.
 
void disable_magnetometer ()
 Sends command to disable magnetometer reports by setting report interval to 0.
 
void disable_step_counter ()
 Sends command to disable step counter reports by setting report interval to 0.
 
void disable_stability_classifier ()
 Sends command to disable stability reports by setting report interval to 0.
 
void disable_activity_classifier ()
 Sends command to disable activity classifier reports by setting report interval to 0.
 
void disable_tap_detector ()
 Sends command to disable tap detector reports by setting report interval to 0.
 
void disable_raw_mems_accelerometer ()
 Sends command to disable raw accelerometer reports by setting report interval to 0.
 
void disable_raw_mems_gyro ()
 Sends command to disable raw gyro reports by setting report interval to 0.
 
void disable_raw_mems_magnetometer ()
 Sends command to disable raw magnetometer reports by setting report interval to 0.
 
void tare_now (uint8_t axis_sel=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
 Sends command to tare an axis (See Ref. Manual 6.4.4.1)
 
void save_tare ()
 Sends command to save tare into non-volatile memory of BNO08x (See Ref. Manual 6.4.4.2)
 
void clear_tare ()
 Sends command to clear persistent tare settings in non-volatile memory of BNO08x (See Ref. Manual 6.4.4.3)
 
bool data_available (bool ignore_no_reports_enabled=false)
 Checks if BNO08x has asserted interrupt and sent data.
 
void register_cb (std::function< void()> cb_fxn)
 Registers a callback to execute when new data from a report is received.
 
void reset_all_data_to_defaults ()
 Resets all data returned by public getter APIs to initial values of 0 and low accuracy.
 
uint32_t get_time_stamp ()
 Return timestamp of most recent report.
 
void get_magf (float &x, float &y, float &z, BNO08xAccuracy &accuracy)
 Get the full magnetic field vector.
 
float get_magf_X ()
 Get X component of magnetic field vector.
 
float get_magf_Y ()
 Get Y component of magnetic field vector.
 
float get_magf_Z ()
 Get Z component of magnetic field vector.
 
BNO08xAccuracy get_magf_accuracy ()
 Get accuracy of reported magnetic field vector.
 
void get_gravity (float &x, float &y, float &z, BNO08xAccuracy &accuracy)
 Get full reported gravity vector, units in m/s^2.
 
float get_gravity_X ()
 Get the reported x axis gravity.
 
float get_gravity_Y ()
 Get the reported y axis gravity.
 
float get_gravity_Z ()
 Get the reported z axis gravity.
 
BNO08xAccuracy get_gravity_accuracy ()
 Get the reported gravity accuracy.
 
float get_roll ()
 Get the reported rotation about x axis.
 
float get_pitch ()
 Get the reported rotation about y axis.
 
float get_yaw ()
 Get the reported rotation about z axis.
 
float get_roll_deg ()
 Get the reported rotation about x axis.
 
float get_pitch_deg ()
 Get the reported rotation about y axis.
 
float get_yaw_deg ()
 Get the reported rotation about z axis.
 
void get_quat (float &i, float &j, float &k, float &real, float &rad_accuracy, BNO08xAccuracy &accuracy)
 Get the full quaternion reading.
 
float get_quat_I ()
 Get I component of reported quaternion.
 
float get_quat_J ()
 Get J component of reported quaternion.
 
float get_quat_K ()
 Get K component of reported quaternion.
 
float get_quat_real ()
 Get real component of reported quaternion.
 
float get_quat_radian_accuracy ()
 Get radian accuracy of reported quaternion.
 
BNO08xAccuracy get_quat_accuracy ()
 Get accuracy of reported quaternion.
 
void get_accel (float &x, float &y, float &z, BNO08xAccuracy &accuracy)
 Get full acceleration (total acceleration of device, units in m/s^2).
 
float get_accel_X ()
 Get x axis acceleration (total acceleration of device, units in m/s^2).
 
float get_accel_Y ()
 Get y axis acceleration (total acceleration of device, units in m/s^2).
 
float get_accel_Z ()
 Get z axis acceleration (total acceleration of device, units in m/s^2).
 
BNO08xAccuracy get_accel_accuracy ()
 Get accuracy of linear acceleration.
 
void get_linear_accel (float &x, float &y, float &z, BNO08xAccuracy &accuracy)
 Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2).
 
float get_linear_accel_X ()
 Get x axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
 
float get_linear_accel_Y ()
 Get y axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
 
float get_linear_accel_Z ()
 Get z axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
 
BNO08xAccuracy get_linear_accel_accuracy ()
 Get accuracy of linear acceleration.
 
void get_raw_mems_accel (uint16_t &x, uint16_t &y, uint16_t &z)
 Get full raw acceleration from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8).
 
uint16_t get_raw_mems_accel_X ()
 Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8)
 
uint16_t get_raw_mems_accel_Y ()
 Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8)
 
uint16_t get_raw_mems_accel_Z ()
 Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8)
 
void get_raw_mems_gyro (uint16_t &x, uint16_t &y, uint16_t &z)
 Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)
 
uint16_t get_raw_mems_gyro_X ()
 Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)
 
uint16_t get_raw_mems_gyro_Y ()
 Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)
 
uint16_t get_raw_mems_gyro_Z ()
 Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)
 
void get_raw_mems_magf (uint16_t &x, uint16_t &y, uint16_t &z)
 Get raw magnetometer full reading from physical magnetometer sensor (See Ref. Manual 6.5.15)
 
uint16_t get_raw_mems_magf_X ()
 Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15)
 
uint16_t get_raw_mems_magf_Y ()
 Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15)
 
uint16_t get_raw_mems_magf_Z ()
 Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15)
 
void get_calibrated_gyro_velocity (float &x, float &y, float &z)
 Get full rotational velocity with drift compensation (units in Rad/s).
 
float get_calibrated_gyro_velocity_X ()
 Get calibrated gyro x axis angular velocity measurement.
 
float get_calibrated_gyro_velocity_Y ()
 Get calibrated gyro y axis angular velocity measurement.
 
float get_calibrated_gyro_velocity_Z ()
 Get calibrated gyro z axis angular velocity measurement.
 
void get_uncalibrated_gyro_velocity (float &x, float &y, float &z, float &bx, float &by, float &bz)
 Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is given but not applied.
 
float get_uncalibrated_gyro_velocity_X ()
 Get uncalibrated gyro x axis angular velocity measurement.
 
float get_uncalibrated_gyro_velocity_Y ()
 Get uncalibrated gyro Y axis angular velocity measurement.
 
float get_uncalibrated_gyro_velocity_Z ()
 Get uncalibrated gyro Z axis angular velocity measurement.
 
float get_uncalibrated_gyro_bias_X ()
 Get uncalibrated gyro x axis drift estimate.
 
float get_uncalibrated_gyro_bias_Y ()
 Get uncalibrated gyro Y axis drift estimate.
 
float get_uncalibrated_gyro_bias_Z ()
 Get uncalibrated gyro Z axis drift estimate.
 
void get_integrated_gyro_velocity (float &x, float &y, float &z)
 Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5.44)
 
float get_integrated_gyro_velocity_X ()
 Get x axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44)
 
float get_integrated_gyro_velocity_Y ()
 Get y axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44)
 
float get_integrated_gyro_velocity_Z ()
 Get z axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44)
 
uint8_t get_tap_detector ()
 Get if tap has occured.
 
uint16_t get_step_count ()
 Get the counted amount of steps.
 
BNO08xStability get_stability_classifier ()
 Get the current stability classifier (Seee Ref. Manual 6.5.31)
 
BNO08xActivity get_activity_classifier ()
 Get the current activity classifier (Seee Ref. Manual 6.5.36)
 
int16_t get_Q1 (uint16_t record_ID)
 Gets Q1 point from BNO08x FRS (flash record system).
 
int16_t get_Q2 (uint16_t record_ID)
 Gets Q2 point from BNO08x FRS (flash record system).
 
int16_t get_Q3 (uint16_t record_ID)
 Gets Q3 point from BNO08x FRS (flash record system).
 
float get_resolution (uint16_t record_ID)
 Gets resolution from BNO08x FRS (flash record system).
 
float get_range (uint16_t record_ID)
 Gets range from BNO08x FRS (flash record system).
 
uint32_t FRS_read_word (uint16_t record_ID, uint8_t word_number)
 Reads meta data word from BNO08x FRS (flash record system) given the record ID and word number. (See Ref. Manual 5.1 & 6.3.7)
 
bool FRS_read_request (uint16_t record_ID, uint16_t read_offset, uint16_t block_size)
 Requests meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.1 & 6.3.6)
 
bool FRS_read_data (uint16_t record_ID, uint8_t start_location, uint8_t words_to_read)
 Read meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.1 & 6.3.7)
 
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

-Static Public Attributes

static const constexpr uint16_t FRS_RECORD_ID_ACCELEROMETER
 Accelerometer record ID, to be passed in metadata functions like get_Q1()
 
static const constexpr uint16_t FRS_RECORD_ID_GYROSCOPE_CALIBRATED
 Calirated gyroscope record ID, to be passed in metadata functions like get_Q1()
 
static const constexpr uint16_t FRS_RECORD_ID_MAGNETIC_FIELD_CALIBRATED
 Calibrated magnetometer record ID, to be passed in metadata functions like get_Q1()
 
static const constexpr uint16_t FRS_RECORD_ID_ROTATION_VECTOR
 Rotation vector record ID, to be passed in metadata functions like get_Q1()
 
static const constexpr uint8_t TARE_AXIS_ALL = 0x07U
 Tare all axes (used with tare now command)
 
static const constexpr uint8_t TARE_AXIS_Z = 0x04U
 Tar yaw axis only (used with tare now command)
 
static const constexpr uint8_t TARE_ROTATION_VECTOR = 0U
 Tare rotation vector.
 
static const constexpr uint8_t TARE_GAME_ROTATION_VECTOR = 1U
 Tare game rotation vector.
 
static const constexpr uint8_t TARE_GEOMAGNETIC_ROTATION_VECTOR = 2U
 tare geomagnetic rotation vector
 
static const constexpr uint8_t TARE_GYRO_INTEGRATED_ROTATION_VECTOR = 3U
 Tare gyro integrated rotation vector.
 
static const constexpr uint8_t TARE_ARVR_STABILIZED_ROTATION_VECTOR = 4U
 Tare ARVR stabilized rotation vector.
 
static const constexpr uint8_t TARE_ARVR_STABILIZED_GAME_ROTATION_VECTOR = 5U
 Tare ARVR stabilized game rotation vector.
 
static const constexpr int16_t ROTATION_VECTOR_Q1 = 14
 Rotation vector Q point (See SH-2 Ref. Manual 6.5.18)
 
static const constexpr int16_t ROTATION_VECTOR_ACCURACY_Q1 = 12
 Rotation vector accuracy estimate Q point (See SH-2 Ref. Manual 6.5.18)
 
static const constexpr int16_t ACCELEROMETER_Q1 = 8
 Acceleration Q point (See SH-2 Ref. Manual 6.5.9)
 
static const constexpr int16_t LINEAR_ACCELEROMETER_Q1 = 8
 Linear acceleration Q point (See SH-2 Ref. Manual 6.5.10)
 
static const constexpr int16_t GYRO_Q1 = 9
 Gyro Q point (See SH-2 Ref. Manual 6.5.13)
 
static const constexpr int16_t MAGNETOMETER_Q1 = 4
 Magnetometer Q point (See SH-2 Ref. Manual 6.5.16)
 
static const constexpr int16_t ANGULAR_VELOCITY_Q1 = 10
 Angular velocity Q point (See SH-2 Ref. Manual 6.5.44)
 
static const constexpr int16_t GRAVITY_Q1 = 8
 Gravity Q point (See SH-2 Ref. Manual 6.5.11)
 
- - - - - - - - - - - - - - - -

-Private Types

enum  channels_t {
-  CHANNEL_COMMAND -, CHANNEL_EXECUTABLE -, CHANNEL_CONTROL -, CHANNEL_REPORTS -,
-  CHANNEL_WAKE_REPORTS -, CHANNEL_GYRO -
- }
 SHTP protocol channels. More...
 
typedef struct BNO08x::bno08x_rx_packet_t bno08x_rx_packet_t
 Holds data that is received over spi.
 
typedef struct BNO08x::bno08x_tx_packet_t bno08x_tx_packet_t
 Holds data that is sent over spi.
 
typedef struct BNO08x::bno08x_report_period_tracker_t bno08x_report_period_tracker_t
 
typedef struct BNO08x::bno08x_init_status_t bno08x_init_status_t
 Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup).
 
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

-Private Member Functions

esp_err_t init_config_args ()
 Initializes required esp-idf SPI data structures with values from user passed bno08x_config_t struct.
 
esp_err_t init_gpio ()
 Initializes required gpio.
 
esp_err_t init_gpio_inputs ()
 Initializes required gpio inputs.
 
esp_err_t init_gpio_outputs ()
 Initializes required gpio outputs.
 
esp_err_t init_hint_isr ()
 Initializes host interrupt ISR.
 
esp_err_t init_spi ()
 Initializes SPI.
 
esp_err_t deinit_gpio ()
 Deinitializes GPIO, called from deconstructor.
 
esp_err_t deinit_gpio_inputs ()
 Deinitializes GPIO inputs, called from deconstructor.
 
esp_err_t deinit_gpio_outputs ()
 Deinitializes GPIO outputs, called from deconstructor.
 
esp_err_t deinit_hint_isr ()
 Deinitializes host interrupt ISR, called from deconstructor.
 
esp_err_t deinit_spi ()
 Deinitializes SPI.
 
bool wait_for_rx_done ()
 Waits for data to be received over SPI, or host_int_timeout_ms to elapse.
 
bool wait_for_tx_done ()
 Waits for a queued packet to be sent or host_int_timeout_ms to elapse.
 
bool wait_for_data ()
 Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse.
 
esp_err_t receive_packet ()
 Receives a SHTP packet via SPI and sends it to data_proc_task()
 
esp_err_t receive_packet_header (bno08x_rx_packet_t *packet)
 Receives a SHTP packet header via SPI.
 
esp_err_t receive_packet_body (bno08x_rx_packet_t *packet)
 Receives a SHTP packet body via SPI.
 
void send_packet (bno08x_tx_packet_t *packet)
 Sends a queued SHTP packet via SPI.
 
void flush_rx_packets (uint8_t flush_count)
 
void enable_report (uint8_t report_ID, uint32_t time_between_reports, const EventBits_t report_evt_grp_bit, uint32_t special_config=0)
 Enables a sensor report for a given ID.
 
void disable_report (uint8_t report_ID, const EventBits_t report_evt_grp_bit)
 Disables a sensor report for a given ID by setting its time interval to 0.
 
void queue_packet (uint8_t channel_number, uint8_t data_length, uint8_t *commands)
 Queues an SHTP packet to be sent via SPI.
 
void queue_command (uint8_t command, uint8_t *commands)
 Queues a packet containing a command.
 
void queue_feature_command (uint8_t report_ID, uint32_t time_between_reports, uint32_t specific_config=0)
 Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.5.4)
 
void queue_calibrate_command (uint8_t _to_calibrate)
 Queues a packet containing a command to calibrate the specified sensor.
 
void queue_tare_command (uint8_t command, uint8_t axis=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
 Queues a packet containing a command related to zeroing sensor's axes. (See Ref. Manual 6.4.4.1)
 
void queue_request_product_id_command ()
 Queues a packet containing the request product ID command.
 
uint16_t parse_packet (bno08x_rx_packet_t *packet, bool &notify_users)
 Parses a packet received from bno08x, updating any data according to received reports.
 
uint16_t parse_product_id_report (bno08x_rx_packet_t *packet)
 Parses product id report and prints device info.
 
uint16_t parse_frs_read_response_report (bno08x_rx_packet_t *packet)
 Sends packet to be parsed to meta data function call (FRS_read_data()) through queue.
 
uint16_t parse_feature_get_response_report (bno08x_rx_packet_t *packet)
 Parses get feature request report received from BNO08x.
 
uint16_t parse_input_report (bno08x_rx_packet_t *packet)
 Parses received input report sent by BNO08x.
 
void parse_input_report_data (bno08x_rx_packet_t *packet, uint16_t *data, uint16_t data_length)
 Parses data from received input report.
 
uint16_t parse_gyro_integrated_rotation_vector_report (bno08x_rx_packet_t *packet)
 Parses received gyro integrated rotation vector report sent by BNO08x.
 
uint16_t parse_command_report (bno08x_rx_packet_t *packet)
 Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)
 
void update_accelerometer_data (uint16_t *data, uint8_t status)
 Updates accelerometer data from parsed input report.
 
void update_lin_accelerometer_data (uint16_t *data, uint8_t status)
 Updates linear accelerometer data from parsed input report.
 
void update_calibrated_gyro_data (uint16_t *data, uint8_t status)
 Updates linear gyro data from parsed input report.
 
void update_uncalibrated_gyro_data (uint16_t *data, uint8_t status)
 Updates uncalibrated gyro data from parsed input report.
 
void update_magf_data (uint16_t *data, uint8_t status)
 Updates magnetic field data from parsed input report.
 
void update_gravity_data (uint16_t *data, uint8_t status)
 Updates gravity data from parsed input report.
 
void update_rotation_vector_data (uint16_t *data, uint8_t status)
 Updates roation vector data from parsed input report.
 
void update_step_counter_data (uint16_t *data)
 Updates step counter data from parsed input report.
 
void update_raw_accelerometer_data (uint16_t *data)
 Updates raw accelerometer data from parsed input report.
 
void update_raw_gyro_data (uint16_t *data)
 Updates raw gyro data from parsed input report.
 
void update_raw_magf_data (uint16_t *data)
 Updates raw magnetic field data from parsed input report.
 
void update_tap_detector_data (bno08x_rx_packet_t *packet)
 Updates tap detector data from parsed input report.
 
void update_stability_classifier_data (bno08x_rx_packet_t *packet)
 Updates stability classifier data from parsed input report.
 
void update_personal_activity_classifier_data (bno08x_rx_packet_t *packet)
 Updates activity classifier data from parsed input report.
 
void update_command_data (bno08x_rx_packet_t *packet)
 Updates command data from parsed input report.
 
void update_integrated_gyro_rotation_vector_data (bno08x_rx_packet_t *packet)
 Updates integrated gyro rotation vector data from SHTP channel 5 (CHANNEL_GYRO) special report data.
 
void print_header (bno08x_rx_packet_t *packet)
 Prints the header of the passed SHTP packet to serial console with ESP_LOG statement.
 
void print_packet (bno08x_rx_packet_t *packet)
 Prints the passed SHTP packet to serial console with ESP_LOG statement.
 
void spi_task ()
 Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x.
 
void data_proc_task ()
 Task responsible parsing packets. Executed when SPI task sends a packet to be parsed, notifies wait_for_data() call.
 
esp_err_t launch_tasks ()
 Launches spi_task and data_proc_task on constructor call.
 
esp_err_t kill_all_tasks ()
 Deletes spi_task and data_proc_task safely on deconstructor call.
 
void update_report_period_trackers (uint8_t report_ID, uint32_t new_period)
 Updates period of respective report in report_period_trackers and recalculates host_int_timeout_ms according to next longest report period.
 
- - - - - - - - - - - - - -

-Static Private Member Functions

static void spi_task_trampoline (void *arg)
 Static function used to launch spi task.
 
static void data_proc_task_trampoline (void *arg)
 Static function used to launch data processing task.
 
static uint8_t report_ID_to_report_period_tracker_idx (uint8_t report_ID)
 Converts report id to respective index in report_period_trackers.
 
static void IRAM_ATTR hint_handler (void *arg)
 HINT interrupt service routine, handles falling edge of BNO08x HINT pin.
 
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

-Private Attributes

bool first_boot = true
 true only for first execution of hard_reset(), used to suppress the printing of product ID report.
 
TaskHandle_t spi_task_hdl
 spi_task() handle
 
TaskHandle_t data_proc_task_hdl
 data_proc_task() task handle
 
SemaphoreHandle_t sem_kill_tasks
 semaphore to count amount of killed tasks
 
EventGroupHandle_t evt_grp_spi
 Event group for indicating when bno08x hint pin has triggered and when new data has been processed. Used by calls to sending or receiving functions.
 
EventGroupHandle_t evt_grp_report_en
 Event group for indicating which reports are currently enabled.
 
EventGroupHandle_t evt_grp_task_flow
 Event group for indicating when tasks should complete and self-delete (on deconstructor call)
 
QueueHandle_t queue_rx_data
 Packet queue used to send data received from bno08x from spi_task to data_proc_task.
 
QueueHandle_t queue_tx_data
 Packet queue used to send data to be sent over SPI from sending functions to spi_task.
 
QueueHandle_t queue_frs_read_data
 Queue used to send packet body from data_proc_task to frs read functions.
 
QueueHandle_t queue_reset_reason
 Queue used to send reset reason from product id report to reset_reason() function.
 
std::vector< std::function< void()> > cb_list
 
uint32_t meta_data [9]
 First 9 bytes of meta data returned from FRS read operation (we don't really need the rest) (See Ref. Manual 5.1)
 
bno08x_config_t imu_config {}
 IMU configuration settings.
 
spi_bus_config_t bus_config {}
 SPI bus GPIO configuration settings.
 
spi_device_interface_config_t imu_spi_config {}
 SPI slave device settings.
 
spi_device_handle_t spi_hdl {}
 SPI device handle.
 
spi_transaction_t spi_transaction {}
 SPI transaction handle.
 
bno08x_init_status_t init_status
 Initialization status of various functionality, used by deconstructor during cleanup, set during initialization.
 
uint32_t time_stamp
 Report timestamp (see datasheet 1.3.5.3)
 
uint16_t raw_accel_X
 
uint16_t raw_accel_Y
 
uint16_t raw_accel_Z
 
uint16_t accel_accuracy
 Raw acceleration readings (See SH-2 Ref. Manual 6.5.8)
 
uint16_t raw_lin_accel_X
 
uint16_t raw_lin_accel_Y
 
uint16_t raw_lin_accel_Z
 
uint16_t accel_lin_accuracy
 Raw linear acceleration (See SH-2 Ref. Manual 6.5.10)
 
uint16_t raw_calib_gyro_X
 
uint16_t raw_calib_gyro_Y
 
uint16_t raw_calib_gyro_Z
 Raw gyro reading (See SH-2 Ref. Manual 6.5.13)
 
uint16_t raw_quat_I
 
uint16_t raw_quat_J
 
uint16_t raw_quat_K
 
uint16_t raw_quat_real
 
uint16_t raw_quat_radian_accuracy
 
uint16_t quat_accuracy
 Raw quaternion reading (See SH-2 Ref. Manual 6.5.44)
 
uint16_t integrated_gyro_velocity_X
 
uint16_t integrated_gyro_velocity_Y
 
uint16_t integrated_gyro_velocity_Z
 Raw gyro angular velocity reading from integrated gyro rotation vector (See SH-2 Ref. Manual 6.5.44)
 
uint16_t gravity_X
 
uint16_t gravity_Y
 
uint16_t gravity_Z
 
uint16_t gravity_accuracy
 Gravity reading in m/s^2 (See SH-2 Ref. Manual 6.5.11)
 
uint16_t raw_uncalib_gyro_X
 
uint16_t raw_uncalib_gyro_Y
 
uint16_t raw_uncalib_gyro_Z
 
uint16_t raw_bias_X
 
uint16_t raw_bias_Y
 
uint16_t raw_bias_Z
 Uncalibrated gyro reading (See SH-2 Ref. Manual 6.5.14)
 
uint16_t raw_magf_X
 
uint16_t raw_magf_Y
 
uint16_t raw_magf_Z
 
uint16_t magf_accuracy
 Calibrated magnetic field reading in uTesla (See SH-2 Ref. Manual 6.5.16)
 
uint8_t tap_detector
 Tap detector reading (See SH-2 Ref. Manual 6.5.27)
 
uint16_t step_count
 Step counter reading (See SH-2 Ref. Manual 6.5.29)
 
uint8_t stability_classifier
 BNO08xStability status reading (See SH-2 Ref. Manual 6.5.31)
 
uint8_t activity_classifier
 BNO08xActivity status reading (See SH-2 Ref. Manual 6.5.36)
 
uint8_t * activity_confidences = nullptr
 Confidence of read activities (See SH-2 Ref. Manual 6.5.36)
 
uint8_t calibration_status
 Calibration status of device (See SH-2 Ref. Manual 6.4.7.1 & 6.4.7.2)
 
uint16_t mems_raw_accel_X
 
uint16_t mems_raw_accel_Y
 
uint16_t mems_raw_accel_Z
 Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.5.8)
 
uint16_t mems_raw_gyro_X
 
uint16_t mems_raw_gyro_Y
 
uint16_t mems_raw_gyro_Z
 Raw gyro readings from MEMS sensor (See SH-2 Ref. Manual 6.5.12)
 
uint16_t mems_raw_magf_X
 
uint16_t mems_raw_magf_Y
 
uint16_t mems_raw_magf_Z
 Raw magnetometer (compass) readings from MEMS sensor (See SH-2 Ref. Manual 6.5.15)
 
bno08x_report_period_tracker_t report_period_trackers [REPORT_CNT]
 Current sample period of each report in microseconds linked to report ID (0 if not enabled).
 
uint32_t largest_sample_period_us
 Current largest sample period of any enabled report in microseconds (used to determine timeout for hint ISR).
 
uint8_t current_slowest_report_ID
 ID of the currently enabled report with the largest sample period.
 
TickType_t host_int_timeout_ms
 Max wait between HINT being asserted by BNO08x before transaction is considered failed (in miliseconds), determined by enabled report with longest period.
 
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

-Static Private Attributes

static const constexpr uint8_t TASK_CNT = 2U
 Total amount of tasks utilized by BNO08x driver library.
 
static const constexpr uint16_t RX_DATA_LENGTH = 300U
 length buffer containing data received over spi
 
static const constexpr uint16_t MAX_METADATA_LENGTH = 9U
 max length of metadata used in frs read operations
 
static const constexpr TickType_t HOST_INT_TIMEOUT_DEFAULT_MS
 Max wait between HINT being asserted by BNO08x before transaction is considered failed (in miliseconds), when no reports are enabled (ie during reset)
 
static const constexpr TickType_t HARD_RESET_DELAY_MS
 How long RST pin is held low during hard reset (min 10ns according to datasheet, but should be longer for stable operation)
 
static const constexpr TickType_t CMD_EXECUTION_DELAY_MS
 How long to delay after queueing command to allow it to execute (for ex. after sending command to enable report).
 
static const constexpr uint32_t SCLK_MAX_SPEED = 3000000UL
 Max SPI SCLK speed BNO08x is capable of.
 
static const constexpr EventBits_t EVT_GRP_SPI_RX_DONE_BIT
 When this bit is set it indicates a receive procedure has completed.
 
static const constexpr EventBits_t EVT_GRP_SPI_RX_VALID_PACKET_BIT
 When this bit is set, it indicates a valid packet has been received and processed.
 
static const constexpr EventBits_t EVT_GRP_SPI_RX_INVALID_PACKET_BIT
 When this bit is set, it indicates an invalid packet has been received.
 
static const constexpr EventBits_t EVT_GRP_SPI_TX_DONE_BIT = (1 << 3)
 When this bit is set, it indicates a queued packet has been sent.
 
static const constexpr EventBits_t EVT_GRP_RPT_ROTATION_VECTOR_BIT = (1 << 0)
 When set, rotation vector reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_GAME_ROTATION_VECTOR_BIT = (1 << 1)
 When set, game rotation vector reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BIT
 When set, ARVR stabilized rotation vector reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BIT
 When set, ARVR stabilized game rotation vector reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BIT
 When set, gyro integrator rotation vector reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_ACCELEROMETER_BIT = (1U << 5U)
 When set, accelerometer reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_LINEAR_ACCELEROMETER_BIT = (1U << 6U)
 When set, linear accelerometer reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_GRAVITY_BIT = (1U << 7U)
 When set, gravity reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_GYRO_BIT = (1U << 8U)
 When set, gyro reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_GYRO_UNCALIBRATED_BIT = (1U << 9U)
 When set, uncalibrated gyro reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_MAGNETOMETER_BIT = (1U << 10U)
 When set, magnetometer reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_TAP_DETECTOR_BIT = (1U << 11U)
 When set, tap detector reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_STEP_COUNTER_BIT = (1U << 12U)
 When set, step counter reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_STABILITY_CLASSIFIER_BIT = (1U << 13U)
 When set, stability classifier reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BIT = (1U << 14U)
 When set, activity classifier reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_RAW_ACCELEROMETER_BIT = (1U << 15U)
 When set, raw accelerometer reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_RAW_GYRO_BIT = (1U << 16U)
 When set, raw gyro reports are active.
 
static const constexpr EventBits_t EVT_GRP_RPT_RAW_MAGNETOMETER_BIT = (1U << 17U)
 When set, raw magnetometer reports are active.
 
static const constexpr EventBits_t EVT_GRP_TSK_FLW_RUNNING_BIT
 When set, data_proc_task and spi_task are active, when 0 they are pending deletion or deleted.
 
static const constexpr EventBits_t EVT_GRP_RPT_ALL_BITS
 
static const constexpr uint8_t CALIBRATE_ACCEL = 0U
 Calibrate accelerometer command used by queue_calibrate_command.
 
static const constexpr uint8_t CALIBRATE_GYRO = 1U
 Calibrate gyro command used by queue_calibrate_command.
 
static const constexpr uint8_t CALIBRATE_MAG = 2U
 Calibrate magnetometer command used by queue_calibrate_command.
 
static const constexpr uint8_t CALIBRATE_PLANAR_ACCEL = 3U
 Calibrate planar acceleration command used by queue_calibrate_command.
 
static const constexpr uint8_t CALIBRATE_ACCEL_GYRO_MAG
 Calibrate accelerometer, gyro, & magnetometer command used by queue_calibrate_command.
 
static const constexpr uint8_t CALIBRATE_STOP = 5U
 Stop calibration command used by queue_calibrate_command.
 
static const constexpr uint8_t COMMAND_ERRORS = 1U
 
static const constexpr uint8_t COMMAND_COUNTER = 2U
 
static const constexpr uint8_t COMMAND_TARE = 3U
 Command and response to tare command (See Sh2 Ref. Manual 6.4.4)
 
static const constexpr uint8_t COMMAND_INITIALIZE = 4U
 Reinitialize sensor hub components See (SH2 Ref. Manual 6.4.5)
 
static const constexpr uint8_t COMMAND_DCD = 6U
 Save DCD command (See SH2 Ref. Manual 6.4.7)
 
static const constexpr uint8_t COMMAND_ME_CALIBRATE = 7U
 Command and response to configure ME calibration (See SH2 Ref. Manual 6.4.7)
 
static const constexpr uint8_t COMMAND_DCD_PERIOD_SAVE = 9U
 Configure DCD periodic saving (See SH2 Ref. Manual 6.4)
 
static const constexpr uint8_t COMMAND_OSCILLATOR = 10U
 Retrieve oscillator type command (See SH2 Ref. Manual 6.4)
 
static const constexpr uint8_t COMMAND_CLEAR_DCD = 11U
 Clear DCD & Reset command (See SH2 Ref. Manual 6.4)
 
static const constexpr uint8_t SHTP_REPORT_COMMAND_RESPONSE = 0xF1U
 See SH2 Ref. Manual 6.3.9.
 
static const constexpr uint8_t SHTP_REPORT_COMMAND_REQUEST = 0xF2U
 See SH2 Ref. Manual 6.3.8.
 
static const constexpr uint8_t SHTP_REPORT_FRS_READ_RESPONSE = 0xF3U
 See SH2 Ref. Manual 6.3.7.
 
static const constexpr uint8_t SHTP_REPORT_FRS_READ_REQUEST = 0xF4U
 See SH2 Ref. Manual 6.3.6.
 
static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_RESPONSE = 0xF8U
 See SH2 Ref. Manual 6.3.2.
 
static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_REQUEST = 0xF9U
 See SH2 Ref. Manual 6.3.1.
 
static const constexpr uint8_t SHTP_REPORT_BASE_TIMESTAMP = 0xFBU
 See SH2 Ref. Manual 7.2.1.
 
static const constexpr uint8_t SHTP_REPORT_SET_FEATURE_COMMAND = 0xFDU
 See SH2 Ref. Manual 6.5.4.
 
static const constexpr uint8_t SHTP_REPORT_GET_FEATURE_RESPONSE = 0xFCU
 See SH2 Ref. Manual 6.5.5.
 
static const constexpr uint8_t SENSOR_REPORT_ID_ACCELEROMETER = 0x01U
 See SH2 Ref. Manual 6.5.9.
 
static const constexpr uint8_t SENSOR_REPORT_ID_GYROSCOPE = 0x02U
 See SH2 Ref. Manual 6.5.13.
 
static const constexpr uint8_t SENSOR_REPORT_ID_MAGNETIC_FIELD = 0x03U
 See SH2 Ref. Manual 6.5.16.
 
static const constexpr uint8_t SENSOR_REPORT_ID_LINEAR_ACCELERATION = 0x04U
 See SH2 Ref. Manual 6.5.10.
 
static const constexpr uint8_t SENSOR_REPORT_ID_ROTATION_VECTOR = 0x05U
 See SH2 Ref. Manual 6.5.18.
 
static const constexpr uint8_t SENSOR_REPORT_ID_GRAVITY = 0x06U
 See SH2 Ref. Manual 6.5.11.
 
static const constexpr uint8_t SENSOR_REPORT_ID_UNCALIBRATED_GYRO = 0x07U
 See SH2 Ref. Manual 6.5.14.
 
static const constexpr uint8_t SENSOR_REPORT_ID_GAME_ROTATION_VECTOR = 0x08U
 See SH2 Ref. Manual 6.5.19.
 
static const constexpr uint8_t SENSOR_REPORT_ID_GEOMAGNETIC_ROTATION_VECTOR = 0x09U
 See SH2 Ref. Manual 6.5.20.
 
static const constexpr uint8_t SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR = 0x2AU
 See SH2 Ref. Manual 6.5.44.
 
static const constexpr uint8_t SENSOR_REPORT_ID_TAP_DETECTOR = 0x10U
 See SH2 Ref. Manual 6.5.27.
 
static const constexpr uint8_t SENSOR_REPORT_ID_STEP_COUNTER = 0x11U
 See SH2 Ref. Manual 6.5.29.
 
static const constexpr uint8_t SENSOR_REPORT_ID_STABILITY_CLASSIFIER = 0x13U
 See SH2 Ref. Manual 6.5.31.
 
static const constexpr uint8_t SENSOR_REPORT_ID_RAW_ACCELEROMETER = 0x14U
 See SH2 Ref. Manual 6.5.8.
 
static const constexpr uint8_t SENSOR_REPORT_ID_RAW_GYROSCOPE = 0x15U
 See SH2 Ref. Manual 6.5.12.
 
static const constexpr uint8_t SENSOR_REPORT_ID_RAW_MAGNETOMETER = 0x16U
 See SH2 Ref. Manual 6.5.15.
 
static const constexpr uint8_t SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER = 0x1EU
 See SH2 Ref. Manual 6.5.36.
 
static const constexpr uint8_t SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR = 0x28U
 See SH2 Ref. Manual 6.5.42.
 
static const constexpr uint8_t SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR = 0x29U
 See SH2 Ref. Manual 6.5.43.
 
static const constexpr uint8_t TARE_NOW = 0U
 See SH2 Ref. Manual 6.4.4.1.
 
static const constexpr uint8_t TARE_PERSIST = 1U
 See SH2 Ref. Manual 6.4.4.2.
 
static const constexpr uint8_t TARE_SET_REORIENTATION = 2U
 See SH2 Ref. Manual 6.4.4.3.
 
static const constexpr uint8_t REPORT_CNT = 19
 Total unique reports that can be returned by BNO08x.
 
static const constexpr char * TAG = "BNO08x"
 Class tag used for serial print statements.
 
- - - -

-Friends

class BNO08xTestHelper
 
-

Detailed Description

-

BNO08x IMU driver class.

-

Member Typedef Documentation

- -

◆ bno08x_init_status_t

- -
-
- - - - - -
- - - - -
typedef struct BNO08x::bno08x_init_status_t BNO08x::bno08x_init_status_t
-
-private
-
- -

Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup).

- -
-
- -

◆ bno08x_report_period_tracker_t

- -
-
- - - - - -
- - - - -
typedef struct BNO08x::bno08x_report_period_tracker_t BNO08x::bno08x_report_period_tracker_t
-
-private
-
- -
-
- -

◆ bno08x_rx_packet_t

- -
-
- - - - - -
- - - - -
typedef struct BNO08x::bno08x_rx_packet_t BNO08x::bno08x_rx_packet_t
-
-private
-
- -

Holds data that is received over spi.

- -
-
- -

◆ bno08x_tx_packet_t

- -
-
- - - - - -
- - - - -
typedef struct BNO08x::bno08x_tx_packet_t BNO08x::bno08x_tx_packet_t
-
-private
-
- -

Holds data that is sent over spi.

- -
-
-

Member Enumeration Documentation

- -

◆ channels_t

- -
-
- - - - - -
- - - - -
enum BNO08x::channels_t
-
-private
-
- -

SHTP protocol channels.

- - - - - - - -
Enumerator
CHANNEL_COMMAND 
CHANNEL_EXECUTABLE 
CHANNEL_CONTROL 
CHANNEL_REPORTS 
CHANNEL_WAKE_REPORTS 
CHANNEL_GYRO 
- -
-
-

Constructor & Destructor Documentation

- -

◆ BNO08x()

- -
-
- - - - - - - -
BNO08x::BNO08x (bno08x_config_t imu_config = bno08x_config_t())
-
- -

BNO08x imu constructor.

-

Construct a BNO08x object for managing a BNO08x sensor.

-
Parameters
- - -
imu_configConfiguration settings (optional), default settings can be seen in bno08x_config_t
-
-
-
Returns
void, nothing to return
- -
-
- -

◆ ~BNO08x()

- -
-
- - - - - - - -
BNO08x::~BNO08x ()
-
- -

BNO08x imu deconstructor.

-

Deconstructs a BNO08x object and releases any utilized resources.

-
Returns
void, nothing to return.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
-

Member Function Documentation

- -

◆ calibrate_accelerometer()

- -
-
- - - - - - - -
void BNO08x::calibrate_accelerometer ()
-
- -

Sends command to calibrate accelerometer.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ calibrate_all()

- -
-
- - - - - - - -
void BNO08x::calibrate_all ()
-
- -

Sends command to calibrate accelerometer, gyro, and magnetometer.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ calibrate_gyro()

- -
-
- - - - - - - -
void BNO08x::calibrate_gyro ()
-
- -

Sends command to calibrate gyro.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ calibrate_magnetometer()

- -
-
- - - - - - - -
void BNO08x::calibrate_magnetometer ()
-
- -

Sends command to calibrate magnetometer.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ calibrate_planar_accelerometer()

- -
-
- - - - - - - -
void BNO08x::calibrate_planar_accelerometer ()
-
- -

Sends command to calibrate planar accelerometer.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ calibration_complete()

- -
-
- - - - - - - -
bool BNO08x::calibration_complete ()
-
- -

Returns true if calibration has completed.

-
Returns
True if calibration complete, false if otherwise.
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ clear_tare()

- -
-
- - - - - - - -
void BNO08x::clear_tare ()
-
- -

Sends command to clear persistent tare settings in non-volatile memory of BNO08x (See Ref. Manual 6.4.4.3)

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ data_available()

- -
-
- - - - - - - -
bool BNO08x::data_available (bool ignore_no_reports_enabled = false)
-
- -

Checks if BNO08x has asserted interrupt and sent data.

-
Parameters
- - -
ignore_no_reports_enabledForces a wait for data even if no reports are enabled (default is false), used for unit tests.
-
-
-
Returns
True if new data has been parsed and saved, false if otherwise.
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ data_proc_task()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::data_proc_task ()
-
-private
-
- -

Task responsible parsing packets. Executed when SPI task sends a packet to be parsed, notifies wait_for_data() call.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ data_proc_task_trampoline()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::data_proc_task_trampoline (void * arg)
-
-staticprivate
-
- -

Static function used to launch data processing task.

-

Used such that data_proc_task() can be non-static class member.

-
Parameters
- - -
argvoid pointer to BNO08x imu object
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ deinit_gpio()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::deinit_gpio ()
-
-private
-
- -

Deinitializes GPIO, called from deconstructor.

-
Returns
ESP_OK if deinitialization was success.
-
-Here is the call graph for this function:
-
-
- - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ deinit_gpio_inputs()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::deinit_gpio_inputs ()
-
-private
-
- -

Deinitializes GPIO inputs, called from deconstructor.

-
Returns
ESP_OK if deinitialization was success.
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ deinit_gpio_outputs()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::deinit_gpio_outputs ()
-
-private
-
- -

Deinitializes GPIO outputs, called from deconstructor.

-
Returns
ESP_OK if deinitialization was success.
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ deinit_hint_isr()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::deinit_hint_isr ()
-
-private
-
- -

Deinitializes host interrupt ISR, called from deconstructor.

-
Returns
ESP_OK if deinitialization was success.
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ deinit_spi()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::deinit_spi ()
-
-private
-
- -

Deinitializes SPI.

-
Returns
ESP_OK if deinitialization was success.
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ disable_accelerometer()

- -
-
- - - - - - - -
void BNO08x::disable_accelerometer ()
-
- -

Sends command to disable accelerometer reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - -
- -
-
- -

◆ disable_activity_classifier()

- -
-
- - - - - - - -
void BNO08x::disable_activity_classifier ()
-
- -

Sends command to disable activity classifier reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ disable_ARVR_stabilized_game_rotation_vector()

- -
-
- - - - - - - -
void BNO08x::disable_ARVR_stabilized_game_rotation_vector ()
-
- -

Sends command to disable ARVR stabilized game rotation vector reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ disable_ARVR_stabilized_rotation_vector()

- -
-
- - - - - - - -
void BNO08x::disable_ARVR_stabilized_rotation_vector ()
-
- -

Sends command to disable ARVR stabilized rotation vector reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ disable_calibrated_gyro()

- -
-
- - - - - - - -
void BNO08x::disable_calibrated_gyro ()
-
- -

Sends command to disable calibrated gyro reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ disable_game_rotation_vector()

- -
-
- - - - - - - -
void BNO08x::disable_game_rotation_vector ()
-
- -

Sends command to disable game rotation vector reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ disable_gravity()

- -
-
- - - - - - - -
void BNO08x::disable_gravity ()
-
- -

Sends command to disable gravity reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ disable_gyro_integrated_rotation_vector()

- -
-
- - - - - - - -
void BNO08x::disable_gyro_integrated_rotation_vector ()
-
- -

Sends command to disable gyro integrated rotation vector reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ disable_linear_accelerometer()

- -
-
- - - - - - - -
void BNO08x::disable_linear_accelerometer ()
-
- -

Sends command to disable linear accelerometer reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ disable_magnetometer()

- -
-
- - - - - - - -
void BNO08x::disable_magnetometer ()
-
- -

Sends command to disable magnetometer reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ disable_raw_mems_accelerometer()

- -
-
- - - - - - - -
void BNO08x::disable_raw_mems_accelerometer ()
-
- -

Sends command to disable raw accelerometer reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ disable_raw_mems_gyro()

- -
-
- - - - - - - -
void BNO08x::disable_raw_mems_gyro ()
-
- -

Sends command to disable raw gyro reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ disable_raw_mems_magnetometer()

- -
-
- - - - - - - -
void BNO08x::disable_raw_mems_magnetometer ()
-
- -

Sends command to disable raw magnetometer reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ disable_report()

- -
-
- - - - - -
- - - - - - - - - - - -
void BNO08x::disable_report (uint8_t report_ID,
const EventBits_t report_evt_grp_bit )
-
-private
-
- -

Disables a sensor report for a given ID by setting its time interval to 0.

-
Parameters
- - - -
report_IDThe report ID of the sensor, i.e. SENSOR_REPORT_ID_X
report_evt_grp_bitThe event group bit for the respective report, to indicate to spi_task() it's disabled, i.e. EVT_GRP_RPT_X
-
-
-

If no reports are enabled after disabling, this function will disable interrupts on hint pin.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ disable_rotation_vector()

- -
-
- - - - - - - -
void BNO08x::disable_rotation_vector ()
-
- -

Sends command to disable rotation vector reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - -
- -
-
- -

◆ disable_stability_classifier()

- -
-
- - - - - - - -
void BNO08x::disable_stability_classifier ()
-
- -

Sends command to disable stability reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ disable_step_counter()

- -
-
- - - - - - - -
void BNO08x::disable_step_counter ()
-
- -

Sends command to disable step counter reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ disable_tap_detector()

- -
-
- - - - - - - -
void BNO08x::disable_tap_detector ()
-
- -

Sends command to disable tap detector reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ disable_uncalibrated_gyro()

- -
-
- - - - - - - -
void BNO08x::disable_uncalibrated_gyro ()
-
- -

Sends command to disable uncalibrated gyro reports by setting report interval to 0.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ enable_accelerometer()

- -
-
- - - - - - - -
void BNO08x::enable_accelerometer (uint32_t time_between_reports)
-
- -

Sends command to enable accelerometer reports (See Ref. Manual 6.5.9)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - -
- -
-
- -

◆ enable_activity_classifier()

- -
-
- - - - - - - - - - - - - - - - -
void BNO08x::enable_activity_classifier (uint32_t time_between_reports,
BNO08xActivityEnable activities_to_enable,
uint8_t(&) activity_confidence_vals[9] )
-
- -

Sends command to enable activity classifier reports (See Ref. Manual 6.5.36)

-
Parameters
- - - - -
time_between_reportsDesired time between reports in microseconds.
activities_to_enableDesired activities to enable (0x1F enables all).
activity_confidence_valsReturned activity level confidences.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ enable_ARVR_stabilized_game_rotation_vector()

- -
-
- - - - - - - -
void BNO08x::enable_ARVR_stabilized_game_rotation_vector (uint32_t time_between_reports)
-
- -

Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6.5.43)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ enable_ARVR_stabilized_rotation_vector()

- -
-
- - - - - - - -
void BNO08x::enable_ARVR_stabilized_rotation_vector (uint32_t time_between_reports)
-
- -

Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6.5.42)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ enable_calibrated_gyro()

- -
-
- - - - - - - -
void BNO08x::enable_calibrated_gyro (uint32_t time_between_reports)
-
- -

Sends command to enable calibrated gyro reports (See Ref. Manual 6.5.13)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ enable_game_rotation_vector()

- -
-
- - - - - - - -
void BNO08x::enable_game_rotation_vector (uint32_t time_between_reports)
-
- -

Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ enable_gravity()

- -
-
- - - - - - - -
void BNO08x::enable_gravity (uint32_t time_between_reports)
-
- -

Sends command to enable gravity reading reports (See Ref. Manual 6.5.11)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ enable_gyro_integrated_rotation_vector()

- -
-
- - - - - - - -
void BNO08x::enable_gyro_integrated_rotation_vector (uint32_t time_between_reports)
-
- -

Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6.5.44)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ enable_linear_accelerometer()

- -
-
- - - - - - - -
void BNO08x::enable_linear_accelerometer (uint32_t time_between_reports)
-
- -

Sends command to enable linear accelerometer reports (See Ref. Manual 6.5.10)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ enable_magnetometer()

- -
-
- - - - - - - -
void BNO08x::enable_magnetometer (uint32_t time_between_reports)
-
- -

Sends command to enable magnetometer reports (See Ref. Manual 6.5.16)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - -
- -
-
- -

◆ enable_raw_mems_accelerometer()

- -
-
- - - - - - - -
void BNO08x::enable_raw_mems_accelerometer (uint32_t time_between_reports)
-
- -

Sends command to enable raw MEMs accelerometer reports (See Ref. Manual 6.5.8)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ enable_raw_mems_gyro()

- -
-
- - - - - - - -
void BNO08x::enable_raw_mems_gyro (uint32_t time_between_reports)
-
- -

Sends command to enable raw MEMs gyro reports (See Ref. Manual 6.5.12)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ enable_raw_mems_magnetometer()

- -
-
- - - - - - - -
void BNO08x::enable_raw_mems_magnetometer (uint32_t time_between_reports)
-
- -

Sends command to enable raw MEMs magnetometer reports (See Ref. Manual 6.5.15)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ enable_report()

- -
-
- - - - - -
- - - - - - - - - - - - - - - - - - - - - -
void BNO08x::enable_report (uint8_t report_ID,
uint32_t time_between_reports,
const EventBits_t report_evt_grp_bit,
uint32_t special_config = 0 )
-
-private
-
- -

Enables a sensor report for a given ID.

-
Parameters
- - - - -
report_IDThe report ID of the sensor, i.e. SENSOR_REPORT_ID_X
time_between_reportsThe desired time in microseconds between each report. The BNO08x will send reports according to this interval.
report_evt_grp_bitThe event group bit for the respective report, to indicate to spi_task() it's enabled, i.e. EVT_GRP_RPT_X
-
-
-

If no reports were enabled prior to call, this function will re-enable interrupts on hint pin.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ enable_rotation_vector()

- -
-
- - - - - - - -
void BNO08x::enable_rotation_vector (uint32_t time_between_reports)
-
- -

Sends command to enable rotation vector reports (See Ref. Manual 6.5.18)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - -
- -
-
- -

◆ enable_stability_classifier()

- -
-
- - - - - - - -
void BNO08x::enable_stability_classifier (uint32_t time_between_reports)
-
- -

Sends command to enable activity stability classifier reports (See Ref. Manual 6.5.31)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ enable_step_counter()

- -
-
- - - - - - - -
void BNO08x::enable_step_counter (uint32_t time_between_reports)
-
- -

Sends command to enable step counter reports (See Ref. Manual 6.5.29)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ enable_tap_detector()

- -
-
- - - - - - - -
void BNO08x::enable_tap_detector (uint32_t time_between_reports)
-
- -

Sends command to enable tap detector reports (See Ref. Manual 6.5.27)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ enable_uncalibrated_gyro()

- -
-
- - - - - - - -
void BNO08x::enable_uncalibrated_gyro (uint32_t time_between_reports)
-
- -

Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.5.14)

-
Parameters
- - -
time_between_reportsDesired time between reports in microseconds.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ end_calibration()

- -
-
- - - - - - - -
void BNO08x::end_calibration ()
-
- -

Sends command to end calibration procedure.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ flush_rx_packets()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::flush_rx_packets (uint8_t flush_count)
-
-private
-
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ FRS_read_data()

- -
-
- - - - - - - - - - - - - - - - -
bool BNO08x::FRS_read_data (uint16_t record_ID,
uint8_t start_location,
uint8_t words_to_read )
-
- -

Read meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.1 & 6.3.7)

-

Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional.

-
Parameters
- - - - -
record_IDWhich record ID/ sensor to request meta data from.
start_locationStart byte location.
words_to_readLength of words to read.
-
-
-
Returns
True if meta data read successfully.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ FRS_read_request()

- -
-
- - - - - - - - - - - - - - - - -
bool BNO08x::FRS_read_request (uint16_t record_ID,
uint16_t read_offset,
uint16_t block_size )
-
- -

Requests meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.1 & 6.3.6)

-

Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional.

-
Parameters
- - - - -
record_IDWhich record ID/ sensor to request meta data from.
start_locationStart byte location.
words_to_readLength of words to read.
-
-
-
Returns
True if read request acknowledged (HINT was asserted)
-
-Here is the call graph for this function:
-
-
- - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ FRS_read_word()

- -
-
- - - - - - - - - - - -
uint32_t BNO08x::FRS_read_word (uint16_t record_ID,
uint8_t word_number )
-
- -

Reads meta data word from BNO08x FRS (flash record system) given the record ID and word number. (See Ref. Manual 5.1 & 6.3.7)

-

Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional.

-
Parameters
- - - -
record_IDWhich record ID/ sensor to request meta data from.
word_numberDesired word to read.
-
-
-
Returns
Requested meta data word, 0 if failed.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ get_accel()

- -
-
- - - - - - - - - - - - - - - - - - - - - -
void BNO08x::get_accel (float & x,
float & y,
float & z,
BNO08xAccuracy & accuracy )
-
- -

Get full acceleration (total acceleration of device, units in m/s^2).

-
Parameters
- - - - - -
xReference variable to save X axis acceleration.
yReference variable to save Y axis acceleration.
zReference variable to save Z axis acceleration.
accuracyReference variable to save reported acceleration accuracy.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_accel_accuracy()

- -
-
- - - - - - - -
BNO08xAccuracy BNO08x::get_accel_accuracy ()
-
- -

Get accuracy of linear acceleration.

-
Returns
Accuracy of linear acceleration.
- -
-
- -

◆ get_accel_X()

- -
-
- - - - - - - -
float BNO08x::get_accel_X ()
-
- -

Get x axis acceleration (total acceleration of device, units in m/s^2).

-
Returns
The angular reported x axis acceleration.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_accel_Y()

- -
-
- - - - - - - -
float BNO08x::get_accel_Y ()
-
- -

Get y axis acceleration (total acceleration of device, units in m/s^2).

-
Returns
The angular reported y axis acceleration.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_accel_Z()

- -
-
- - - - - - - -
float BNO08x::get_accel_Z ()
-
- -

Get z axis acceleration (total acceleration of device, units in m/s^2).

-
Returns
The angular reported z axis acceleration.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_activity_classifier()

- -
-
- - - - - - - -
BNO08xActivity BNO08x::get_activity_classifier ()
-
- -

Get the current activity classifier (Seee Ref. Manual 6.5.36)

-
Returns
The current activity: 0 = unknown 1 = in vehicle 2 = on bicycle 3 = on foot 4 = still 5 = tilting 6 = walking 7 = runnning 8 = on stairs
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_calibrated_gyro_velocity()

- -
-
- - - - - - - - - - - - - - - - -
void BNO08x::get_calibrated_gyro_velocity (float & x,
float & y,
float & z )
-
- -

Get full rotational velocity with drift compensation (units in Rad/s).

-
Parameters
- - - - -
xReference variable to save X axis angular velocity
yReference variable to save Y axis angular velocity
zReference variable to save Z axis angular velocity
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_calibrated_gyro_velocity_X()

- -
-
- - - - - - - -
float BNO08x::get_calibrated_gyro_velocity_X ()
-
- -

Get calibrated gyro x axis angular velocity measurement.

-
Returns
The angular reported x axis angular velocity from calibrated gyro (drift compensation applied).
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_calibrated_gyro_velocity_Y()

- -
-
- - - - - - - -
float BNO08x::get_calibrated_gyro_velocity_Y ()
-
- -

Get calibrated gyro y axis angular velocity measurement.

-
Returns
The angular reported y axis angular velocity from calibrated gyro (drift compensation applied).
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_calibrated_gyro_velocity_Z()

- -
-
- - - - - - - -
float BNO08x::get_calibrated_gyro_velocity_Z ()
-
- -

Get calibrated gyro z axis angular velocity measurement.

-
Returns
The angular reported z axis angular velocity from calibrated gyro (drift compensation applied).
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_gravity()

- -
-
- - - - - - - - - - - - - - - - - - - - - -
void BNO08x::get_gravity (float & x,
float & y,
float & z,
BNO08xAccuracy & accuracy )
-
- -

Get full reported gravity vector, units in m/s^2.

-
Parameters
- - - - - -
xReference variable to save X axis gravity.
yReference variable to save Y axis axis gravity.
zReference variable to save Z axis axis gravity.
accuracyReference variable to save reported gravity accuracy.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_gravity_accuracy()

- -
-
- - - - - - - -
BNO08xAccuracy BNO08x::get_gravity_accuracy ()
-
- -

Get the reported gravity accuracy.

-
Returns
Accuracy of reported gravity.
- -
-
- -

◆ get_gravity_X()

- -
-
- - - - - - - -
float BNO08x::get_gravity_X ()
-
- -

Get the reported x axis gravity.

-
Returns
x axis gravity in m/s^2
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_gravity_Y()

- -
-
- - - - - - - -
float BNO08x::get_gravity_Y ()
-
- -

Get the reported y axis gravity.

-
Returns
y axis gravity in m/s^2
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_gravity_Z()

- -
-
- - - - - - - -
float BNO08x::get_gravity_Z ()
-
- -

Get the reported z axis gravity.

-
Returns
z axis gravity in m/s^2
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_integrated_gyro_velocity()

- -
-
- - - - - - - - - - - - - - - - -
void BNO08x::get_integrated_gyro_velocity (float & x,
float & y,
float & z )
-
- -

Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5.44)

-
Parameters
- - - - -
xReference variable to save X axis angular velocity
yReference variable to save Y axis angular velocity
zReference variable to save Z axis angular velocity
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_integrated_gyro_velocity_X()

- -
-
- - - - - - - -
float BNO08x::get_integrated_gyro_velocity_X ()
-
- -

Get x axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44)

-
Returns
The reported x axis angular velocity.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_integrated_gyro_velocity_Y()

- -
-
- - - - - - - -
float BNO08x::get_integrated_gyro_velocity_Y ()
-
- -

Get y axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44)

-
Returns
The reported y axis angular velocity.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_integrated_gyro_velocity_Z()

- -
-
- - - - - - - -
float BNO08x::get_integrated_gyro_velocity_Z ()
-
- -

Get z axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44)

-
Returns
The reported Z axis angular velocity.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_linear_accel()

- -
-
- - - - - - - - - - - - - - - - - - - - - -
void BNO08x::get_linear_accel (float & x,
float & y,
float & z,
BNO08xAccuracy & accuracy )
-
- -

Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2).

-
Parameters
- - - - - -
xReference variable to save X axis acceleration.
yReference variable to save Y axis acceleration.
zReference variable to save Z axis acceleration.
accuracyReference variable to save reported linear acceleration accuracy.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_linear_accel_accuracy()

- -
-
- - - - - - - -
BNO08xAccuracy BNO08x::get_linear_accel_accuracy ()
-
- -

Get accuracy of linear acceleration.

-
Returns
Accuracy of linear acceleration.
- -
-
- -

◆ get_linear_accel_X()

- -
-
- - - - - - - -
float BNO08x::get_linear_accel_X ()
-
- -

Get x axis linear acceleration (acceleration of device minus gravity, units in m/s^2)

-
Returns
The angular reported x axis linear acceleration.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_linear_accel_Y()

- -
-
- - - - - - - -
float BNO08x::get_linear_accel_Y ()
-
- -

Get y axis linear acceleration (acceleration of device minus gravity, units in m/s^2)

-
Returns
The angular reported y axis linear acceleration.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_linear_accel_Z()

- -
-
- - - - - - - -
float BNO08x::get_linear_accel_Z ()
-
- -

Get z axis linear acceleration (acceleration of device minus gravity, units in m/s^2)

-
Returns
The angular reported z axis linear acceleration.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_magf()

- -
-
- - - - - - - - - - - - - - - - - - - - - -
void BNO08x::get_magf (float & x,
float & y,
float & z,
BNO08xAccuracy & accuracy )
-
- -

Get the full magnetic field vector.

-
Parameters
- - - - - -
xReference variable to save reported x magnitude.
yReference variable to save reported y magnitude.
xReference variable to save reported z magnitude.
accuracyReference variable to save reported accuracy.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_magf_accuracy()

- -
-
- - - - - - - -
BNO08xAccuracy BNO08x::get_magf_accuracy ()
-
- -

Get accuracy of reported magnetic field vector.

-
Returns
The accuracy of reported magnetic field vector.
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_magf_X()

- -
-
- - - - - - - -
float BNO08x::get_magf_X ()
-
- -

Get X component of magnetic field vector.

-
Returns
The reported X component of magnetic field vector.
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_magf_Y()

- -
-
- - - - - - - -
float BNO08x::get_magf_Y ()
-
- -

Get Y component of magnetic field vector.

-
Returns
The reported Y component of magnetic field vector.
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_magf_Z()

- -
-
- - - - - - - -
float BNO08x::get_magf_Z ()
-
- -

Get Z component of magnetic field vector.

-
Returns
The reported Z component of magnetic field vector.
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_pitch()

- -
-
- - - - - - - -
float BNO08x::get_pitch ()
-
- -

Get the reported rotation about y axis.

-
Returns
Rotation about the y axis in radians.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_pitch_deg()

- -
-
- - - - - - - -
float BNO08x::get_pitch_deg ()
-
- -

Get the reported rotation about y axis.

-
Returns
Rotation about the y axis in degrees.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_Q1()

- -
-
- - - - - - - -
int16_t BNO08x::get_Q1 (uint16_t record_ID)
-
- -

Gets Q1 point from BNO08x FRS (flash record system).

-

Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional.

-
Parameters
- - -
record_IDWhich record ID/ sensor to get Q1 value for.
-
-
-
Returns
Q1 value for requested sensor.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ get_Q2()

- -
-
- - - - - - - -
int16_t BNO08x::get_Q2 (uint16_t record_ID)
-
- -

Gets Q2 point from BNO08x FRS (flash record system).

-

Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional.

-
Parameters
- - -
record_IDWhich record ID/ sensor to get Q2 value for.
-
-
-
Returns
Q2 value for requested sensor.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ get_Q3()

- -
-
- - - - - - - -
int16_t BNO08x::get_Q3 (uint16_t record_ID)
-
- -

Gets Q3 point from BNO08x FRS (flash record system).

-

Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional.

-
Parameters
- - -
record_IDWhich record ID/ sensor to get Q3 value for.
-
-
-
Returns
Q3 value for requested sensor.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ get_quat()

- -
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
void BNO08x::get_quat (float & i,
float & j,
float & k,
float & real,
float & rad_accuracy,
BNO08xAccuracy & accuracy )
-
- -

Get the full quaternion reading.

-
Parameters
- - - - - - - -
iReference variable to save reported i component of quaternion.
jReference variable to save reported j component of quaternion.
kReference variable to save reported k component of quaternion.
realReference variable to save reported real component of quaternion.
rad_accuracyReference variable to save reported raw quaternion radian accuracy.
accuracyReference variable to save reported quaternion accuracy.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_quat_accuracy()

- -
-
- - - - - - - -
BNO08xAccuracy BNO08x::get_quat_accuracy ()
-
- -

Get accuracy of reported quaternion.

-
Returns
The accuracy of reported quaternion.
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_quat_I()

- -
-
- - - - - - - -
float BNO08x::get_quat_I ()
-
- -

Get I component of reported quaternion.

-
Returns
The I component of reported quaternion.
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_quat_J()

- -
-
- - - - - - - -
float BNO08x::get_quat_J ()
-
- -

Get J component of reported quaternion.

-
Returns
The J component of reported quaternion.
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_quat_K()

- -
-
- - - - - - - -
float BNO08x::get_quat_K ()
-
- -

Get K component of reported quaternion.

-
Returns
The K component of reported quaternion.
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_quat_radian_accuracy()

- -
-
- - - - - - - -
float BNO08x::get_quat_radian_accuracy ()
-
- -

Get radian accuracy of reported quaternion.

-
Returns
The radian accuracy of reported quaternion.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_quat_real()

- -
-
- - - - - - - -
float BNO08x::get_quat_real ()
-
- -

Get real component of reported quaternion.

-
Returns
The real component of reported quaternion.
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_range()

- -
-
- - - - - - - -
float BNO08x::get_range (uint16_t record_ID)
-
- -

Gets range from BNO08x FRS (flash record system).

-
Parameters
- - -
record_IDWhich record ID/ sensor to get range value for.
-
-
-
Returns
The range value for the requested sensor.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_raw_mems_accel()

- -
-
- - - - - - - - - - - - - - - - -
void BNO08x::get_raw_mems_accel (uint16_t & x,
uint16_t & y,
uint16_t & z )
-
- -

Get full raw acceleration from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8).

-
Parameters
- - - - -
xReference variable to save raw X axis acceleration.
yReference variable to save raw Y axis acceleration.
zReference variable to save raw Z axis acceleration.
-
-
-
Returns
void, nothing to return
- -
-
- -

◆ get_raw_mems_accel_X()

- -
-
- - - - - - - -
uint16_t BNO08x::get_raw_mems_accel_X ()
-
- -

Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8)

-
Returns
Reported raw accelerometer x axis reading from physical MEMs sensor.
- -
-
- -

◆ get_raw_mems_accel_Y()

- -
-
- - - - - - - -
uint16_t BNO08x::get_raw_mems_accel_Y ()
-
- -

Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8)

-
Returns
Reported raw accelerometer y axis reading from physical MEMs sensor.
- -
-
- -

◆ get_raw_mems_accel_Z()

- -
-
- - - - - - - -
uint16_t BNO08x::get_raw_mems_accel_Z ()
-
- -

Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8)

-
Returns
Reported raw accelerometer z axis reading from physical MEMs sensor.
- -
-
- -

◆ get_raw_mems_gyro()

- -
-
- - - - - - - - - - - - - - - - -
void BNO08x::get_raw_mems_gyro (uint16_t & x,
uint16_t & y,
uint16_t & z )
-
- -

Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)

-
Parameters
- - - - -
xReference variable to save raw X axis data.
yReference variable to save raw Y axis data.
zReference variable to save raw Z axis data.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_raw_mems_gyro_X()

- -
-
- - - - - - - -
uint16_t BNO08x::get_raw_mems_gyro_X ()
-
- -

Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)

-
Returns
Reported raw gyroscope x axis reading from physical MEMs sensor.
- -
-
- -

◆ get_raw_mems_gyro_Y()

- -
-
- - - - - - - -
uint16_t BNO08x::get_raw_mems_gyro_Y ()
-
- -

Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)

-
Returns
Reported raw gyroscope y axis reading from physical MEMs sensor.
- -
-
- -

◆ get_raw_mems_gyro_Z()

- -
-
- - - - - - - -
uint16_t BNO08x::get_raw_mems_gyro_Z ()
-
- -

Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)

-
Returns
Reported raw gyroscope z axis reading from physical MEMs sensor.
- -
-
- -

◆ get_raw_mems_magf()

- -
-
- - - - - - - - - - - - - - - - -
void BNO08x::get_raw_mems_magf (uint16_t & x,
uint16_t & y,
uint16_t & z )
-
- -

Get raw magnetometer full reading from physical magnetometer sensor (See Ref. Manual 6.5.15)

-
Parameters
- - - - -
xReference variable to save raw X axis data.
yReference variable to save raw Y axis data.
zReference variable to save raw Z axis data.
-
-
-
Returns
void, nothing to return
- -
-
- -

◆ get_raw_mems_magf_X()

- -
-
- - - - - - - -
uint16_t BNO08x::get_raw_mems_magf_X ()
-
- -

Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15)

-
Returns
Reported raw magnetometer x axis reading from physical magnetometer sensor.
- -
-
- -

◆ get_raw_mems_magf_Y()

- -
-
- - - - - - - -
uint16_t BNO08x::get_raw_mems_magf_Y ()
-
- -

Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15)

-
Returns
Reported raw magnetometer y axis reading from physical magnetometer sensor.
- -
-
- -

◆ get_raw_mems_magf_Z()

- -
-
- - - - - - - -
uint16_t BNO08x::get_raw_mems_magf_Z ()
-
- -

Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15)

-
Returns
Reported raw magnetometer z axis reading from physical magnetometer sensor.
- -
-
- -

◆ get_reset_reason()

- -
-
- - - - - - - -
BNO08xResetReason BNO08x::get_reset_reason ()
-
- -

Requests product ID, prints the returned info over serial, and returns the reason for the most resent reset.

-
Returns
The reason for the most recent recent reset ( 1 = POR (power on reset), 2 = internal reset, 3 = watchdog timer, 4 = external reset 5 = other)
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ get_resolution()

- -
-
- - - - - - - -
float BNO08x::get_resolution (uint16_t record_ID)
-
- -

Gets resolution from BNO08x FRS (flash record system).

-
Parameters
- - -
record_IDWhich record ID/ sensor to get resolution value for.
-
-
-
Returns
The resolution value for the requested sensor.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_roll()

- -
-
- - - - - - - -
float BNO08x::get_roll ()
-
- -

Get the reported rotation about x axis.

-
Returns
Rotation about the x axis in radians.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_roll_deg()

- -
-
- - - - - - - -
float BNO08x::get_roll_deg ()
-
- -

Get the reported rotation about x axis.

-
Returns
Rotation about the x axis in degrees.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_stability_classifier()

- -
-
- - - - - - - -
BNO08xStability BNO08x::get_stability_classifier ()
-
- -

Get the current stability classifier (Seee Ref. Manual 6.5.31)

-
Returns
The current stability (0 = unknown, 1 = on table, 2 = stationary)
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_step_count()

- -
-
- - - - - - - -
uint16_t BNO08x::get_step_count ()
-
- -

Get the counted amount of steps.

-
Returns
The current amount of counted steps.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_tap_detector()

- -
-
- - - - - - - -
uint8_t BNO08x::get_tap_detector ()
-
- -

Get if tap has occured.

-
Returns
7 bit tap code indicated which axis taps have occurred. (See Ref. Manual 6.5.27)
- -
-
- -

◆ get_time_stamp()

- -
-
- - - - - - - -
uint32_t BNO08x::get_time_stamp ()
-
- -

Return timestamp of most recent report.

-
Returns
uint32_t containing the timestamp of the most recent report in microseconds.
- -
-
- -

◆ get_uncalibrated_gyro_bias_X()

- -
-
- - - - - - - -
float BNO08x::get_uncalibrated_gyro_bias_X ()
-
- -

Get uncalibrated gyro x axis drift estimate.

-
Returns
The angular reported x axis drift estimate.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_uncalibrated_gyro_bias_Y()

- -
-
- - - - - - - -
float BNO08x::get_uncalibrated_gyro_bias_Y ()
-
- -

Get uncalibrated gyro Y axis drift estimate.

-
Returns
The angular reported Y axis drift estimate.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_uncalibrated_gyro_bias_Z()

- -
-
- - - - - - - -
float BNO08x::get_uncalibrated_gyro_bias_Z ()
-
- -

Get uncalibrated gyro Z axis drift estimate.

-
Returns
The angular reported Z axis drift estimate.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_uncalibrated_gyro_velocity()

- -
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
void BNO08x::get_uncalibrated_gyro_velocity (float & x,
float & y,
float & z,
float & b_x,
float & b_y,
float & b_z )
-
- -

Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is given but not applied.

-
Parameters
- - - - - - - -
xReference variable to save X axis angular velocity
yReference variable to save Y axis angular velocity
zReference variable to save Z axis angular velocity
b_xReference variable to save X axis drift estimate
b_yReference variable to save Y axis drift estimate
b_zReference variable to save Z axis drift estimate
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_uncalibrated_gyro_velocity_X()

- -
-
- - - - - - - -
float BNO08x::get_uncalibrated_gyro_velocity_X ()
-
- -

Get uncalibrated gyro x axis angular velocity measurement.

-
Returns
The angular reported x axis angular velocity from uncalibrated gyro.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_uncalibrated_gyro_velocity_Y()

- -
-
- - - - - - - -
float BNO08x::get_uncalibrated_gyro_velocity_Y ()
-
- -

Get uncalibrated gyro Y axis angular velocity measurement.

-
Returns
The angular reported Y axis angular velocity from uncalibrated gyro.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_uncalibrated_gyro_velocity_Z()

- -
-
- - - - - - - -
float BNO08x::get_uncalibrated_gyro_velocity_Z ()
-
- -

Get uncalibrated gyro Z axis angular velocity measurement.

-
Returns
The angular reported Z axis angular velocity from uncalibrated gyro.
-
-Here is the call graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_yaw()

- -
-
- - - - - - - -
float BNO08x::get_yaw ()
-
- -

Get the reported rotation about z axis.

-
Returns
Rotation about the z axis in radians.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ get_yaw_deg()

- -
-
- - - - - - - -
float BNO08x::get_yaw_deg ()
-
- -

Get the reported rotation about z axis.

-
Returns
Rotation about the z axis in degrees.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ hard_reset()

- -
-
- - - - - - - -
bool BNO08x::hard_reset ()
-
- -

Hard resets BNO08x sensor.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ hint_handler()

- -
-
- - - - - -
- - - - - - - -
void IRAM_ATTR BNO08x::hint_handler (void * arg)
-
-staticprivate
-
- -

HINT interrupt service routine, handles falling edge of BNO08x HINT pin.

-

ISR that launches SPI task to perform transaction upon assertion of BNO08x interrupt pin.

-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ init_config_args()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::init_config_args ()
-
-private
-
- -

Initializes required esp-idf SPI data structures with values from user passed bno08x_config_t struct.

-
Returns
ESP_OK if initialization was success.
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ init_gpio()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::init_gpio ()
-
-private
-
- -

Initializes required gpio.

-
Returns
ESP_OK if initialization was success.
-
-Here is the call graph for this function:
-
-
- - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ init_gpio_inputs()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::init_gpio_inputs ()
-
-private
-
- -

Initializes required gpio inputs.

-
Returns
ESP_OK if initialization was success.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ init_gpio_outputs()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::init_gpio_outputs ()
-
-private
-
- -

Initializes required gpio outputs.

-
Returns
ESP_OK if initialization was success.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ init_hint_isr()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::init_hint_isr ()
-
-private
-
- -

Initializes host interrupt ISR.

-
Returns
ESP_OK if initialization was success.
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ init_spi()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::init_spi ()
-
-private
-
- -

Initializes SPI.

-
Returns
ESP_OK if initialization was success.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ initialize()

- -
-
- - - - - - - -
bool BNO08x::initialize ()
-
- -

Initializes BNO08x sensor.

-

Resets sensor and goes through initialization process. Configures GPIO, required ISRs, and launches two tasks, one to manage SPI transactions, another to process any received data.

-
Returns
True if initialization was success, false if otherwise.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ kill_all_tasks()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::kill_all_tasks ()
-
-private
-
- -

Deletes spi_task and data_proc_task safely on deconstructor call.

-
Returns
ESP_OK if tasks successfully deleted.
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ launch_tasks()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::launch_tasks ()
-
-private
-
- -

Launches spi_task and data_proc_task on constructor call.

-
Returns
ESP_OK if tasks successfully created.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ mode_on()

- -
-
- - - - - - - -
bool BNO08x::mode_on ()
-
- -

Turns on/ brings BNO08x sensor out of sleep mode using executable channel.

-
Returns
True if exiting sleep mode was success.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ mode_sleep()

- -
-
- - - - - - - -
bool BNO08x::mode_sleep ()
-
- -

Puts BNO08x sensor into sleep/low power mode using executable channel.

-
Returns
True if entering sleep mode was success.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ parse_command_report()

- -
-
- - - - - -
- - - - - - - -
uint16_t BNO08x::parse_command_report (bno08x_rx_packet_t * packet)
-
-private
-
- -

Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)

-
Returns
The command report ID, 0 if invalid.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ parse_feature_get_response_report()

- -
-
- - - - - -
- - - - - - - -
uint16_t BNO08x::parse_feature_get_response_report (bno08x_rx_packet_t * packet)
-
-private
-
- -

Parses get feature request report received from BNO08x.

-

Note there is no means in this library currently to request feature reports, this is simply to handle the unsolicited get feature request reports that come with report rate changes (ie when a report is disabled by setting it 0) such that they aren't detected as invalid packets.

-

"6.5.5 of SH-2 Ref manual: "Note that SH-2 protocol version 1.0.1 and higher will send Get Feature Response messages unsolicited if a sensor’s rate changes (e.g. due to change in the rate of a related sensor."

-
Parameters
- - -
packetbno8x_rx_packet_t containing the get feature request report to parse.
-
-
-
Returns
The report ID of the respective sensor, for ex. SENSOR_REPORT_ID_ACCELEROMETER, 0 if invalid.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ parse_frs_read_response_report()

- -
-
- - - - - -
- - - - - - - -
uint16_t BNO08x::parse_frs_read_response_report (bno08x_rx_packet_t * packet)
-
-private
-
- -

Sends packet to be parsed to meta data function call (FRS_read_data()) through queue.

-
Parameters
- - -
packetThe packet containing the frs read report.
-
-
-
Returns
1, always valid, parsing for this happens in frs_read_word()
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ parse_gyro_integrated_rotation_vector_report()

- -
-
- - - - - -
- - - - - - - -
uint16_t BNO08x::parse_gyro_integrated_rotation_vector_report (bno08x_rx_packet_t * packet)
-
-private
-
- -

Parses received gyro integrated rotation vector report sent by BNO08x.

-

Unit responds with packet that contains the following:

-

packet->header[0:3]: First, a 4 byte header packet->body[0:1]: Raw quaternion component I packet->body[2:3]: Raw quaternion component J packet->body[4:5]: Raw quaternion component K packet->body[6:7]: Raw quaternion real component packet->body[8:9]: Raw gyroscope angular velocity in X axis packet->body[10:11]: Raw gyroscope angular velocity in Y axis packet->body[12:13]: Raw gyroscope angular velocity in Z axis

-
Parameters
- - -
packetbno8x_rx_packet_t containing the gyro integrated rotation vector report report to parse
-
-
-
Returns
Integrated rotation vector report ID (always valid)
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ parse_input_report()

- -
-
- - - - - -
- - - - - - - -
uint16_t BNO08x::parse_input_report (bno08x_rx_packet_t * packet)
-
-private
-
- -

Parses received input report sent by BNO08x.

-

Unit responds with packet that contains the following:

-

packet->header[0:3]: First, a 4 byte header packet->body[0:4]: Then a 5 byte timestamp of microsecond ticks since reading was taken packet->body[5 + 0]: Then a feature report ID (0x01 for Accel, 0x05 for Rotation Vector, etc...) packet->body[5 + 1]: Sequence number (See Ref.Manual 6.5.8.2) packet->body[5 + 2]: Status packet->body[3]: Delay packet->body[4:5]: i/accel x/gyro x/etc packet->body[6:7]: j/accel y/gyro y/etc packet->body[8:9]: k/accel z/gyro z/etc packet->body[10:11]: real/gyro temp/etc packet->body[12:13]: Accuracy estimate

-
Parameters
- - -
packetbno8x_rx_packet_t containing the input report to parse
-
-
-
Returns
The report ID of the respective sensor, for ex. SENSOR_REPORT_ID_ACCELEROMETER, 0 if invalid.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ parse_input_report_data()

- -
-
- - - - - -
- - - - - - - - - - - - - - - - -
void BNO08x::parse_input_report_data (bno08x_rx_packet_t * packet,
uint16_t * data,
uint16_t data_length )
-
-private
-
- -

Parses data from received input report.

-
Parameters
- - - - -
packetbno8x_rx_packet_t containing the input report to parse
datauint16_t array to store parsed data in
data_lengthlength of data in bytes parsed from packet header
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ parse_packet()

- -
-
- - - - - -
- - - - - - - - - - - -
uint16_t BNO08x::parse_packet (bno08x_rx_packet_t * packet,
bool & notify_users )
-
-private
-
- -

Parses a packet received from bno08x, updating any data according to received reports.

-
Parameters
- - - -
packetThe packet to be parsed.
notify_usersBool reference that is set to true if users should be notified of new data through callbacks/polling, false if packet is valid but users don't need to be notified.
-
-
-
Returns
0 if invalid packet, non-zero if otherwise.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ parse_product_id_report()

- -
-
- - - - - -
- - - - - - - -
uint16_t BNO08x::parse_product_id_report (bno08x_rx_packet_t * packet)
-
-private
-
- -

Parses product id report and prints device info.

-
Parameters
- - -
packetThe packet containing product id report.
-
-
-
Returns
1, always valid.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ print_header()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::print_header (bno08x_rx_packet_t * packet)
-
-private
-
- -

Prints the header of the passed SHTP packet to serial console with ESP_LOG statement.

-
Parameters
- - -
packetThe packet containing the header to be printed.
-
-
-
Returns
void, nothing to return
- -
-
- -

◆ print_packet()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::print_packet (bno08x_rx_packet_t * packet)
-
-private
-
- -

Prints the passed SHTP packet to serial console with ESP_LOG statement.

-
Parameters
- - -
packetThe packet to be printed.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ q_to_float()

- -
-
- - - - - - - - - - - -
float BNO08x::q_to_float (int16_t fixed_point_value,
uint8_t q_point )
-
- -

Converts a register value to a float using its associated Q point. (See https://en.wikipedia.org/wiki/Q_(number_format))

-
Parameters
- - - -
q_pointQ point value associated with register.
fixed_point_valueThe fixed point value to convert.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ queue_calibrate_command()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::queue_calibrate_command (uint8_t sensor_to_calibrate)
-
-private
-
- -

Queues a packet containing a command to calibrate the specified sensor.

-
Parameters
- - -
sensor_to_calibrateThe sensor to calibrate.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ queue_command()

- -
-
- - - - - -
- - - - - - - - - - - -
void BNO08x::queue_command (uint8_t command,
uint8_t * commands )
-
-private
-
- -

Queues a packet containing a command.

-
Parameters
- - - -
commandThe command to be sent.
commandsCommand data array, pre-packed with exception of first 3 elements (command info)
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ queue_feature_command()

- -
-
- - - - - -
- - - - - - - - - - - - - - - - -
void BNO08x::queue_feature_command (uint8_t report_ID,
uint32_t time_between_reports,
uint32_t specific_config = 0 )
-
-private
-
- -

Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.5.4)

-
Parameters
- - - - -
report_IDID of sensor report to be enabled.
time_between_reportsDesired time between reports in microseconds.
specific_configSpecific config word (used with personal activity classifier)
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ queue_packet()

- -
-
- - - - - -
- - - - - - - - - - - - - - - - -
void BNO08x::queue_packet (uint8_t channel_number,
uint8_t data_length,
uint8_t * commands )
-
-private
-
- -

Queues an SHTP packet to be sent via SPI.

-
Parameters
- - - - -
SHTPchannel number
data_lengthdata length in bytes
commandsarray containing data to be sent
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ queue_request_product_id_command()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::queue_request_product_id_command ()
-
-private
-
- -

Queues a packet containing the request product ID command.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - -
- -
-
- -

◆ queue_tare_command()

- -
-
- - - - - -
- - - - - - - - - - - - - - - - -
void BNO08x::queue_tare_command (uint8_t command,
uint8_t axis = TARE_AXIS_ALL,
uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR )
-
-private
-
- -

Queues a packet containing a command related to zeroing sensor's axes. (See Ref. Manual 6.4.4.1)

-
Parameters
- - - - -
commandTare command to be sent.
axisSpecified axis (can be z or all at once)
rotation_vector_basisWhich rotation vector type to zero axes of, BNO08x saves seperate data for Rotation Vector, Gaming Rotation Vector, etc..)
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - -
- -
-
- -

◆ receive_packet()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::receive_packet ()
-
-private
-
- -

Receives a SHTP packet via SPI and sends it to data_proc_task()

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ receive_packet_body()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::receive_packet_body (bno08x_rx_packet_t * packet)
-
-private
-
- -

Receives a SHTP packet body via SPI.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t to save body to.
-
-
-
Returns
ESP_OK if receive was success.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ receive_packet_header()

- -
-
- - - - - -
- - - - - - - -
esp_err_t BNO08x::receive_packet_header (bno08x_rx_packet_t * packet)
-
-private
-
- -

Receives a SHTP packet header via SPI.

-
Parameters
- - -
packetPointer to bno08x_rx_packet_t to save header to.
-
-
-
Returns
ESP_OK if receive was success.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ register_cb()

- -
-
- - - - - - - -
void BNO08x::register_cb (std::function< void()> cb_fxn)
-
- -

Registers a callback to execute when new data from a report is received.

-
Parameters
- - -
cb_fxnPointer to the call-back function should be of void return type and void input parameters.
-
-
-
Returns
void, nothing to return
- -
-
- -

◆ report_ID_to_report_period_tracker_idx()

- -
-
- - - - - -
- - - - - - - -
uint8_t BNO08x::report_ID_to_report_period_tracker_idx (uint8_t report_ID)
-
-staticprivate
-
- -

Converts report id to respective index in report_period_trackers.

-
Parameters
- - -
report_IDreport ID to return index for.
-
-
-
Returns
Index in report_period_trackers corresponding to passed report ID.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ request_calibration_status()

- -
-
- - - - - - - -
void BNO08x::request_calibration_status ()
-
- -

Requests ME calibration status from BNO08x (see Ref. Manual 6.4.7.2)

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ reset_all_data_to_defaults()

- -
-
- - - - - - - -
void BNO08x::reset_all_data_to_defaults ()
-
- -

Resets all data returned by public getter APIs to initial values of 0 and low accuracy.

-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ run_full_calibration_routine()

- -
-
- - - - - - - -
bool BNO08x::run_full_calibration_routine ()
-
- -

Runs full calibration routine.

-

Enables game rotation vector and magnetometer, starts ME calibration process. Waits for accuracy of returned quaternions and magnetic field vectors to be high, then saves calibration data and returns.

-
Returns
True if calibration succeeded, false if otherwise.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ save_calibration()

- -
-
- - - - - - - -
void BNO08x::save_calibration ()
-
- -

Sends command to save internal calibration data (See Ref. Manual 6.4.7).

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ save_tare()

- -
-
- - - - - - - -
void BNO08x::save_tare ()
-
- -

Sends command to save tare into non-volatile memory of BNO08x (See Ref. Manual 6.4.4.2)

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ send_packet()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::send_packet (bno08x_tx_packet_t * packet)
-
-private
-
- -

Sends a queued SHTP packet via SPI.

-
Parameters
- - -
packetThe packet queued to be sent.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ soft_reset()

- -
-
- - - - - - - -
bool BNO08x::soft_reset ()
-
- -

Soft resets BNO08x sensor using executable channel.

-
Returns
True if reset was success.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ spi_task()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::spi_task ()
-
-private
-
- -

Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ spi_task_trampoline()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::spi_task_trampoline (void * arg)
-
-staticprivate
-
- -

Static function used to launch spi task.

-

Used such that spi_task() can be non-static class member.

-
Parameters
- - -
argvoid pointer to BNO08x imu object
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ tare_now()

- -
-
- - - - - - - - - - - -
void BNO08x::tare_now (uint8_t axis_sel = TARE_AXIS_ALL,
uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR )
-
- -

Sends command to tare an axis (See Ref. Manual 6.4.4.1)

-
Parameters
- - - -
axis_selWhich axes to zero, can be TARE_AXIS_ALL (all axes) or TARE_AXIS_Z (only yaw)
rotation_vector_basisWhich rotation vector type to zero axes can be TARE_ROTATION_VECTOR, TARE_GAME_ROTATION_VECTOR, TARE_GEOMAGNETIC_ROTATION_VECTOR, etc..
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ update_accelerometer_data()

- -
-
- - - - - -
- - - - - - - - - - - -
void BNO08x::update_accelerometer_data (uint16_t * data,
uint8_t status )
-
-private
-
- -

Updates accelerometer data from parsed input report.

-
Parameters
- - - -
datauint16_t array containing parsed input report data.
statusuint8_t containing parsed status bits (represents accuracy)
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_calibrated_gyro_data()

- -
-
- - - - - -
- - - - - - - - - - - -
void BNO08x::update_calibrated_gyro_data (uint16_t * data,
uint8_t status )
-
-private
-
- -

Updates linear gyro data from parsed input report.

-
Parameters
- - - -
datauint16_t array containing parsed input report data.
statusuint8_t containing parsed status bits (represents accuracy)
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_command_data()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::update_command_data (bno08x_rx_packet_t * packet)
-
-private
-
- -

Updates command data from parsed input report.

-
Parameters
- - -
packetbno08x_rx_packet_t containing the packet with command response report.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_gravity_data()

- -
-
- - - - - -
- - - - - - - - - - - -
void BNO08x::update_gravity_data (uint16_t * data,
uint8_t status )
-
-private
-
- -

Updates gravity data from parsed input report.

-
Parameters
- - - -
datauint16_t array containing parsed input report data.
statusuint8_t containing parsed status bits (represents accuracy)
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_integrated_gyro_rotation_vector_data()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::update_integrated_gyro_rotation_vector_data (bno08x_rx_packet_t * packet)
-
-private
-
- -

Updates integrated gyro rotation vector data from SHTP channel 5 (CHANNEL_GYRO) special report data.

-
Parameters
- - -
packetbno08x_rx_packet_t containing the packet with command response report.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_lin_accelerometer_data()

- -
-
- - - - - -
- - - - - - - - - - - -
void BNO08x::update_lin_accelerometer_data (uint16_t * data,
uint8_t status )
-
-private
-
- -

Updates linear accelerometer data from parsed input report.

-
Parameters
- - - -
datauint16_t array containing parsed input report data.
statusuint8_t containing parsed status bits (represents accuracy)
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_magf_data()

- -
-
- - - - - -
- - - - - - - - - - - -
void BNO08x::update_magf_data (uint16_t * data,
uint8_t status )
-
-private
-
- -

Updates magnetic field data from parsed input report.

-
Parameters
- - - -
datauint16_t array containing parsed input report data.
statusuint8_t containing parsed status bits (represents accuracy)
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_personal_activity_classifier_data()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::update_personal_activity_classifier_data (bno08x_rx_packet_t * packet)
-
-private
-
- -

Updates activity classifier data from parsed input report.

-
Parameters
- - -
packetbno08x_rx_packet_t containing the packet with activity classifier report.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_raw_accelerometer_data()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::update_raw_accelerometer_data (uint16_t * data)
-
-private
-
- -

Updates raw accelerometer data from parsed input report.

-
Parameters
- - -
datauint16_t array containing parsed input report data.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_raw_gyro_data()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::update_raw_gyro_data (uint16_t * data)
-
-private
-
- -

Updates raw gyro data from parsed input report.

-
Parameters
- - -
datauint16_t array containing parsed input report data.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_raw_magf_data()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::update_raw_magf_data (uint16_t * data)
-
-private
-
- -

Updates raw magnetic field data from parsed input report.

-
Parameters
- - -
datauint16_t array containing parsed input report data.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_report_period_trackers()

- -
-
- - - - - -
- - - - - - - - - - - -
void BNO08x::update_report_period_trackers (uint8_t report_ID,
uint32_t new_period )
-
-private
-
- -

Updates period of respective report in report_period_trackers and recalculates host_int_timeout_ms according to next longest report period.

-
Parameters
- - -
report_IDreport ID to update period of.
-
-
-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_rotation_vector_data()

- -
-
- - - - - -
- - - - - - - - - - - -
void BNO08x::update_rotation_vector_data (uint16_t * data,
uint8_t status )
-
-private
-
- -

Updates roation vector data from parsed input report.

-
Parameters
- - - -
datauint16_t array containing parsed input report data.
statusuint8_t containing parsed status bits (represents accuracy)
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_stability_classifier_data()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::update_stability_classifier_data (bno08x_rx_packet_t * packet)
-
-private
-
- -

Updates stability classifier data from parsed input report.

-
Parameters
- - -
packetbno08x_rx_packet_t containing the packet with stability classifier report.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_step_counter_data()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::update_step_counter_data (uint16_t * data)
-
-private
-
- -

Updates step counter data from parsed input report.

-
Parameters
- - -
datauint16_t array containing parsed input report data.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_tap_detector_data()

- -
-
- - - - - -
- - - - - - - -
void BNO08x::update_tap_detector_data (bno08x_rx_packet_t * packet)
-
-private
-
- -

Updates tap detector data from parsed input report.

-
Parameters
- - -
packetbno08x_rx_packet_t containing the packet with tap detector report.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ update_uncalibrated_gyro_data()

- -
-
- - - - - -
- - - - - - - - - - - -
void BNO08x::update_uncalibrated_gyro_data (uint16_t * data,
uint8_t status )
-
-private
-
- -

Updates uncalibrated gyro data from parsed input report.

-
Parameters
- - - -
datauint16_t array containing parsed input report data.
statusuint8_t containing parsed status bits (represents accuracy)
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ wait_for_data()

- -
-
- - - - - -
- - - - - - - -
bool BNO08x::wait_for_data ()
-
-private
-
- -

Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse.

-

If no reports are currently enabled the hint pin interrupt will be re-enabled by this function.

-
Returns
True if valid packet has been received within host_int_timeout_ms, false if otherwise.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ wait_for_rx_done()

- -
-
- - - - - -
- - - - - - - -
bool BNO08x::wait_for_rx_done ()
-
-private
-
- -

Waits for data to be received over SPI, or host_int_timeout_ms to elapse.

-

If no reports are currently enabled the hint pin interrupt will be re-enabled by this function. This function is for when the validity of packets is not a concern, it is for flushing packets we do not care about.

-
Returns
True if data has been received over SPI within host_int_timeout_ms.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ wait_for_tx_done()

- -
-
- - - - - -
- - - - - - - -
bool BNO08x::wait_for_tx_done ()
-
-private
-
- -

Waits for a queued packet to be sent or host_int_timeout_ms to elapse.

-

If no reports are currently enabled the hint pin interrupt will be re-enabled by this function.

-
Returns
True if packet was sent within host_int_timeout_ms, false if otherwise.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
-

Friends And Related Symbol Documentation

- -

◆ BNO08xTestHelper

- -
-
- - - - - -
- - - - -
friend class BNO08xTestHelper
-
-friend
-
- -
-
-

Member Data Documentation

- -

◆ accel_accuracy

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::accel_accuracy
-
-private
-
- -

Raw acceleration readings (See SH-2 Ref. Manual 6.5.8)

- -
-
- -

◆ accel_lin_accuracy

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::accel_lin_accuracy
-
-private
-
- -

Raw linear acceleration (See SH-2 Ref. Manual 6.5.10)

- -
-
- -

◆ ACCELEROMETER_Q1

- -
-
- - - - - -
- - - - -
const constexpr int16_t BNO08x::ACCELEROMETER_Q1 = 8
-
-staticconstexpr
-
- -

Acceleration Q point (See SH-2 Ref. Manual 6.5.9)

- -
-
- -

◆ activity_classifier

- -
-
- - - - - -
- - - - -
uint8_t BNO08x::activity_classifier
-
-private
-
- -

BNO08xActivity status reading (See SH-2 Ref. Manual 6.5.36)

- -
-
- -

◆ activity_confidences

- -
-
- - - - - -
- - - - -
uint8_t* BNO08x::activity_confidences = nullptr
-
-private
-
- -

Confidence of read activities (See SH-2 Ref. Manual 6.5.36)

- -
-
- -

◆ ANGULAR_VELOCITY_Q1

- -
-
- - - - - -
- - - - -
const constexpr int16_t BNO08x::ANGULAR_VELOCITY_Q1 = 10
-
-staticconstexpr
-
- -

Angular velocity Q point (See SH-2 Ref. Manual 6.5.44)

- -
-
- -

◆ bus_config

- -
-
- - - - - -
- - - - -
spi_bus_config_t BNO08x::bus_config {}
-
-private
-
- -

SPI bus GPIO configuration settings.

- -
-
- -

◆ CALIBRATE_ACCEL

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::CALIBRATE_ACCEL = 0U
-
-staticconstexprprivate
-
- -

Calibrate accelerometer command used by queue_calibrate_command.

- -
-
- -

◆ CALIBRATE_ACCEL_GYRO_MAG

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::CALIBRATE_ACCEL_GYRO_MAG
-
-staticconstexprprivate
-
-Initial value:
=
-
4U
-
-

Calibrate accelerometer, gyro, & magnetometer command used by queue_calibrate_command.

- -
-
- -

◆ CALIBRATE_GYRO

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::CALIBRATE_GYRO = 1U
-
-staticconstexprprivate
-
- -

Calibrate gyro command used by queue_calibrate_command.

- -
-
- -

◆ CALIBRATE_MAG

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::CALIBRATE_MAG = 2U
-
-staticconstexprprivate
-
- -

Calibrate magnetometer command used by queue_calibrate_command.

- -
-
- -

◆ CALIBRATE_PLANAR_ACCEL

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::CALIBRATE_PLANAR_ACCEL = 3U
-
-staticconstexprprivate
-
- -

Calibrate planar acceleration command used by queue_calibrate_command.

- -
-
- -

◆ CALIBRATE_STOP

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::CALIBRATE_STOP = 5U
-
-staticconstexprprivate
-
- -

Stop calibration command used by queue_calibrate_command.

- -
-
- -

◆ calibration_status

- -
-
- - - - - -
- - - - -
uint8_t BNO08x::calibration_status
-
-private
-
- -

Calibration status of device (See SH-2 Ref. Manual 6.4.7.1 & 6.4.7.2)

- -
-
- -

◆ cb_list

- -
-
- - - - - -
- - - - -
std::vector<std::function<void()> > BNO08x::cb_list
-
-private
-
- -
-
- -

◆ CMD_EXECUTION_DELAY_MS

- -
-
- - - - - -
- - - - -
const constexpr TickType_t BNO08x::CMD_EXECUTION_DELAY_MS
-
-staticconstexprprivate
-
-Initial value:
=
-
10UL /
-
portTICK_PERIOD_MS
-
-

How long to delay after queueing command to allow it to execute (for ex. after sending command to enable report).

- -
-
- -

◆ COMMAND_CLEAR_DCD

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::COMMAND_CLEAR_DCD = 11U
-
-staticconstexprprivate
-
- -

Clear DCD & Reset command (See SH2 Ref. Manual 6.4)

- -
-
- -

◆ COMMAND_COUNTER

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::COMMAND_COUNTER = 2U
-
-staticconstexprprivate
-
- -
-
- -

◆ COMMAND_DCD

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::COMMAND_DCD = 6U
-
-staticconstexprprivate
-
- -

Save DCD command (See SH2 Ref. Manual 6.4.7)

- -
-
- -

◆ COMMAND_DCD_PERIOD_SAVE

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::COMMAND_DCD_PERIOD_SAVE = 9U
-
-staticconstexprprivate
-
- -

Configure DCD periodic saving (See SH2 Ref. Manual 6.4)

- -
-
- -

◆ COMMAND_ERRORS

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::COMMAND_ERRORS = 1U
-
-staticconstexprprivate
-
- -
-
- -

◆ COMMAND_INITIALIZE

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::COMMAND_INITIALIZE = 4U
-
-staticconstexprprivate
-
- -

Reinitialize sensor hub components See (SH2 Ref. Manual 6.4.5)

- -
-
- -

◆ COMMAND_ME_CALIBRATE

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::COMMAND_ME_CALIBRATE = 7U
-
-staticconstexprprivate
-
- -

Command and response to configure ME calibration (See SH2 Ref. Manual 6.4.7)

- -
-
- -

◆ COMMAND_OSCILLATOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::COMMAND_OSCILLATOR = 10U
-
-staticconstexprprivate
-
- -

Retrieve oscillator type command (See SH2 Ref. Manual 6.4)

- -
-
- -

◆ COMMAND_TARE

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::COMMAND_TARE = 3U
-
-staticconstexprprivate
-
- -

Command and response to tare command (See Sh2 Ref. Manual 6.4.4)

- -
-
- -

◆ current_slowest_report_ID

- -
-
- - - - - -
- - - - -
uint8_t BNO08x::current_slowest_report_ID
-
-private
-
- -

ID of the currently enabled report with the largest sample period.

- -
-
- -

◆ data_proc_task_hdl

- -
-
- - - - - -
- - - - -
TaskHandle_t BNO08x::data_proc_task_hdl
-
-private
-
- -

data_proc_task() task handle

- -
-
- -

◆ evt_grp_report_en

- -
-
- - - - - -
- - - - -
EventGroupHandle_t BNO08x::evt_grp_report_en
-
-private
-
- -

Event group for indicating which reports are currently enabled.

- -
-
- -

◆ EVT_GRP_RPT_ACCELEROMETER_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_ACCELEROMETER_BIT = (1U << 5U)
-
-staticconstexprprivate
-
- -

When set, accelerometer reports are active.

- -
-
- -

◆ EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BIT = (1U << 14U)
-
-staticconstexprprivate
-
- -

When set, activity classifier reports are active.

- -
-
- -

◆ EVT_GRP_RPT_ALL_BITS

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_ALL_BITS
-
-staticconstexprprivate
-
-Initial value:
=
- - - - - -
static const constexpr EventBits_t EVT_GRP_RPT_GAME_ROTATION_VECTOR_BIT
When set, game rotation vector reports are active.
Definition BNO08x.hpp:452
-
static const constexpr EventBits_t EVT_GRP_RPT_ACCELEROMETER_BIT
When set, accelerometer reports are active.
Definition BNO08x.hpp:459
-
static const constexpr EventBits_t EVT_GRP_RPT_ROTATION_VECTOR_BIT
When set, rotation vector reports are active.
Definition BNO08x.hpp:451
-
static const constexpr EventBits_t EVT_GRP_RPT_GYRO_BIT
When set, gyro reports are active.
Definition BNO08x.hpp:462
-
static const constexpr EventBits_t EVT_GRP_RPT_RAW_ACCELEROMETER_BIT
When set, raw accelerometer reports are active.
Definition BNO08x.hpp:469
-
static const constexpr EventBits_t EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BIT
When set, gyro integrator rotation vector reports are active.
Definition BNO08x.hpp:457
-
static const constexpr EventBits_t EVT_GRP_RPT_TAP_DETECTOR_BIT
When set, tap detector reports are active.
Definition BNO08x.hpp:465
-
static const constexpr EventBits_t EVT_GRP_RPT_RAW_GYRO_BIT
When set, raw gyro reports are active.
Definition BNO08x.hpp:470
-
static const constexpr EventBits_t EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BIT
When set, ARVR stabilized game rotation vector reports are active.
Definition BNO08x.hpp:455
-
static const constexpr EventBits_t EVT_GRP_RPT_STABILITY_CLASSIFIER_BIT
When set, stability classifier reports are active.
Definition BNO08x.hpp:467
-
static const constexpr EventBits_t EVT_GRP_RPT_MAGNETOMETER_BIT
When set, magnetometer reports are active.
Definition BNO08x.hpp:464
-
static const constexpr EventBits_t EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BIT
When set, activity classifier reports are active.
Definition BNO08x.hpp:468
-
static const constexpr EventBits_t EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BIT
When set, ARVR stabilized rotation vector reports are active.
Definition BNO08x.hpp:453
-
static const constexpr EventBits_t EVT_GRP_RPT_STEP_COUNTER_BIT
When set, step counter reports are active.
Definition BNO08x.hpp:466
-
static const constexpr EventBits_t EVT_GRP_RPT_GRAVITY_BIT
When set, gravity reports are active.
Definition BNO08x.hpp:461
-
static const constexpr EventBits_t EVT_GRP_RPT_RAW_MAGNETOMETER_BIT
When set, raw magnetometer reports are active.
Definition BNO08x.hpp:471
-
static const constexpr EventBits_t EVT_GRP_RPT_LINEAR_ACCELEROMETER_BIT
When set, linear accelerometer reports are active.
Definition BNO08x.hpp:460
-
static const constexpr EventBits_t EVT_GRP_RPT_GYRO_UNCALIBRATED_BIT
When set, uncalibrated gyro reports are active.
Definition BNO08x.hpp:463
-
-
-
- -

◆ EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BIT
-
-staticconstexprprivate
-
-Initial value:
=
-
(1U << 3U)
-
-

When set, ARVR stabilized game rotation vector reports are active.

- -
-
- -

◆ EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BIT
-
-staticconstexprprivate
-
-Initial value:
=
-
(1U << 2U)
-
-

When set, ARVR stabilized rotation vector reports are active.

- -
-
- -

◆ EVT_GRP_RPT_GAME_ROTATION_VECTOR_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_GAME_ROTATION_VECTOR_BIT = (1 << 1)
-
-staticconstexprprivate
-
- -

When set, game rotation vector reports are active.

- -
-
- -

◆ EVT_GRP_RPT_GRAVITY_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_GRAVITY_BIT = (1U << 7U)
-
-staticconstexprprivate
-
- -

When set, gravity reports are active.

- -
-
- -

◆ EVT_GRP_RPT_GYRO_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_GYRO_BIT = (1U << 8U)
-
-staticconstexprprivate
-
- -

When set, gyro reports are active.

- -
-
- -

◆ EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BIT
-
-staticconstexprprivate
-
-Initial value:
=
-
(1U << 4U)
-
-

When set, gyro integrator rotation vector reports are active.

- -
-
- -

◆ EVT_GRP_RPT_GYRO_UNCALIBRATED_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_GYRO_UNCALIBRATED_BIT = (1U << 9U)
-
-staticconstexprprivate
-
- -

When set, uncalibrated gyro reports are active.

- -
-
- -

◆ EVT_GRP_RPT_LINEAR_ACCELEROMETER_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_LINEAR_ACCELEROMETER_BIT = (1U << 6U)
-
-staticconstexprprivate
-
- -

When set, linear accelerometer reports are active.

- -
-
- -

◆ EVT_GRP_RPT_MAGNETOMETER_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_MAGNETOMETER_BIT = (1U << 10U)
-
-staticconstexprprivate
-
- -

When set, magnetometer reports are active.

- -
-
- -

◆ EVT_GRP_RPT_RAW_ACCELEROMETER_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_RAW_ACCELEROMETER_BIT = (1U << 15U)
-
-staticconstexprprivate
-
- -

When set, raw accelerometer reports are active.

- -
-
- -

◆ EVT_GRP_RPT_RAW_GYRO_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_RAW_GYRO_BIT = (1U << 16U)
-
-staticconstexprprivate
-
- -

When set, raw gyro reports are active.

- -
-
- -

◆ EVT_GRP_RPT_RAW_MAGNETOMETER_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_RAW_MAGNETOMETER_BIT = (1U << 17U)
-
-staticconstexprprivate
-
- -

When set, raw magnetometer reports are active.

- -
-
- -

◆ EVT_GRP_RPT_ROTATION_VECTOR_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_ROTATION_VECTOR_BIT = (1 << 0)
-
-staticconstexprprivate
-
- -

When set, rotation vector reports are active.

- -
-
- -

◆ EVT_GRP_RPT_STABILITY_CLASSIFIER_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_STABILITY_CLASSIFIER_BIT = (1U << 13U)
-
-staticconstexprprivate
-
- -

When set, stability classifier reports are active.

- -
-
- -

◆ EVT_GRP_RPT_STEP_COUNTER_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_STEP_COUNTER_BIT = (1U << 12U)
-
-staticconstexprprivate
-
- -

When set, step counter reports are active.

- -
-
- -

◆ EVT_GRP_RPT_TAP_DETECTOR_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_RPT_TAP_DETECTOR_BIT = (1U << 11U)
-
-staticconstexprprivate
-
- -

When set, tap detector reports are active.

- -
-
- -

◆ evt_grp_spi

- -
-
- - - - - -
- - - - -
EventGroupHandle_t BNO08x::evt_grp_spi
-
-private
-
- -

Event group for indicating when bno08x hint pin has triggered and when new data has been processed. Used by calls to sending or receiving functions.

- -
-
- -

◆ EVT_GRP_SPI_RX_DONE_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_SPI_RX_DONE_BIT
-
-staticconstexprprivate
-
-Initial value:
=
-
(1U << 0U)
-
-

When this bit is set it indicates a receive procedure has completed.

- -
-
- -

◆ EVT_GRP_SPI_RX_INVALID_PACKET_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_SPI_RX_INVALID_PACKET_BIT
-
-staticconstexprprivate
-
-Initial value:
=
-
(1U << 2U)
-
-

When this bit is set, it indicates an invalid packet has been received.

- -
-
- -

◆ EVT_GRP_SPI_RX_VALID_PACKET_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_SPI_RX_VALID_PACKET_BIT
-
-staticconstexprprivate
-
-Initial value:
=
-
(1U << 1U)
-
-

When this bit is set, it indicates a valid packet has been received and processed.

- -
-
- -

◆ EVT_GRP_SPI_TX_DONE_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_SPI_TX_DONE_BIT = (1 << 3)
-
-staticconstexprprivate
-
- -

When this bit is set, it indicates a queued packet has been sent.

- -
-
- -

◆ evt_grp_task_flow

- -
-
- - - - - -
- - - - -
EventGroupHandle_t BNO08x::evt_grp_task_flow
-
-private
-
- -

Event group for indicating when tasks should complete and self-delete (on deconstructor call)

- -
-
- -

◆ EVT_GRP_TSK_FLW_RUNNING_BIT

- -
-
- - - - - -
- - - - -
const constexpr EventBits_t BNO08x::EVT_GRP_TSK_FLW_RUNNING_BIT
-
-staticconstexprprivate
-
-Initial value:
=
-
(1U << 0U)
-
-

When set, data_proc_task and spi_task are active, when 0 they are pending deletion or deleted.

- -
-
- -

◆ first_boot

- -
-
- - - - - -
- - - - -
bool BNO08x::first_boot = true
-
-private
-
- -

true only for first execution of hard_reset(), used to suppress the printing of product ID report.

- -
-
- -

◆ FRS_RECORD_ID_ACCELEROMETER

- -
-
- - - - - -
- - - - -
const constexpr uint16_t BNO08x::FRS_RECORD_ID_ACCELEROMETER
-
-staticconstexpr
-
-Initial value:
=
-
0xE302U
-
-

Accelerometer record ID, to be passed in metadata functions like get_Q1()

- -
-
- -

◆ FRS_RECORD_ID_GYROSCOPE_CALIBRATED

- -
-
- - - - - -
- - - - -
const constexpr uint16_t BNO08x::FRS_RECORD_ID_GYROSCOPE_CALIBRATED
-
-staticconstexpr
-
-Initial value:
=
-
0xE306U
-
-

Calirated gyroscope record ID, to be passed in metadata functions like get_Q1()

- -
-
- -

◆ FRS_RECORD_ID_MAGNETIC_FIELD_CALIBRATED

- -
-
- - - - - -
- - - - -
const constexpr uint16_t BNO08x::FRS_RECORD_ID_MAGNETIC_FIELD_CALIBRATED
-
-staticconstexpr
-
-Initial value:
=
-
0xE309U
-
-

Calibrated magnetometer record ID, to be passed in metadata functions like get_Q1()

- -
-
- -

◆ FRS_RECORD_ID_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint16_t BNO08x::FRS_RECORD_ID_ROTATION_VECTOR
-
-staticconstexpr
-
-Initial value:
=
-
0xE30BU
-
-

Rotation vector record ID, to be passed in metadata functions like get_Q1()

- -
-
- -

◆ gravity_accuracy

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::gravity_accuracy
-
-private
-
- -

Gravity reading in m/s^2 (See SH-2 Ref. Manual 6.5.11)

- -
-
- -

◆ GRAVITY_Q1

- -
-
- - - - - -
- - - - -
const constexpr int16_t BNO08x::GRAVITY_Q1 = 8
-
-staticconstexpr
-
- -

Gravity Q point (See SH-2 Ref. Manual 6.5.11)

- -
-
- -

◆ gravity_X

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::gravity_X
-
-private
-
- -
-
- -

◆ gravity_Y

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::gravity_Y
-
-private
-
- -
-
- -

◆ gravity_Z

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::gravity_Z
-
-private
-
- -
-
- -

◆ GYRO_Q1

- -
-
- - - - - -
- - - - -
const constexpr int16_t BNO08x::GYRO_Q1 = 9
-
-staticconstexpr
-
- -

Gyro Q point (See SH-2 Ref. Manual 6.5.13)

- -
-
- -

◆ HARD_RESET_DELAY_MS

- -
-
- - - - - -
- - - - -
const constexpr TickType_t BNO08x::HARD_RESET_DELAY_MS
-
-staticconstexprprivate
-
-Initial value:
=
-
100UL /
-
portTICK_PERIOD_MS
-
-

How long RST pin is held low during hard reset (min 10ns according to datasheet, but should be longer for stable operation)

- -
-
- -

◆ HOST_INT_TIMEOUT_DEFAULT_MS

- -
-
- - - - - -
- - - - -
const constexpr TickType_t BNO08x::HOST_INT_TIMEOUT_DEFAULT_MS
-
-staticconstexprprivate
-
-Initial value:
=
-
3000UL /
-
portTICK_PERIOD_MS
-
-

Max wait between HINT being asserted by BNO08x before transaction is considered failed (in miliseconds), when no reports are enabled (ie during reset)

- -
-
- -

◆ host_int_timeout_ms

- -
-
- - - - - -
- - - - -
TickType_t BNO08x::host_int_timeout_ms
-
-private
-
-Initial value:
=
- -
static const constexpr TickType_t HOST_INT_TIMEOUT_DEFAULT_MS
Max wait between HINT being asserted by BNO08x before transaction is considered failed (in milisecond...
Definition BNO08x.hpp:427
-
-

Max wait between HINT being asserted by BNO08x before transaction is considered failed (in miliseconds), determined by enabled report with longest period.

- -
-
- -

◆ imu_config

- -
-
- - - - - -
- - - - -
bno08x_config_t BNO08x::imu_config {}
-
-private
-
- -

IMU configuration settings.

- -
-
- -

◆ imu_spi_config

- -
-
- - - - - -
- - - - -
spi_device_interface_config_t BNO08x::imu_spi_config {}
-
-private
-
- -

SPI slave device settings.

- -
-
- -

◆ init_status

- -
-
- - - - - -
- - - - -
bno08x_init_status_t BNO08x::init_status
-
-private
-
- -

Initialization status of various functionality, used by deconstructor during cleanup, set during initialization.

- -
-
- -

◆ integrated_gyro_velocity_X

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::integrated_gyro_velocity_X
-
-private
-
- -
-
- -

◆ integrated_gyro_velocity_Y

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::integrated_gyro_velocity_Y
-
-private
-
- -
-
- -

◆ integrated_gyro_velocity_Z

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::integrated_gyro_velocity_Z
-
-private
-
- -

Raw gyro angular velocity reading from integrated gyro rotation vector (See SH-2 Ref. Manual 6.5.44)

- -
-
- -

◆ largest_sample_period_us

- -
-
- - - - - -
- - - - -
uint32_t BNO08x::largest_sample_period_us
-
-private
-
-Initial value:
=
-
0
-
-

Current largest sample period of any enabled report in microseconds (used to determine timeout for hint ISR).

- -
-
- -

◆ LINEAR_ACCELEROMETER_Q1

- -
-
- - - - - -
- - - - -
const constexpr int16_t BNO08x::LINEAR_ACCELEROMETER_Q1 = 8
-
-staticconstexpr
-
- -

Linear acceleration Q point (See SH-2 Ref. Manual 6.5.10)

- -
-
- -

◆ magf_accuracy

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::magf_accuracy
-
-private
-
- -

Calibrated magnetic field reading in uTesla (See SH-2 Ref. Manual 6.5.16)

- -
-
- -

◆ MAGNETOMETER_Q1

- -
-
- - - - - -
- - - - -
const constexpr int16_t BNO08x::MAGNETOMETER_Q1 = 4
-
-staticconstexpr
-
- -

Magnetometer Q point (See SH-2 Ref. Manual 6.5.16)

- -
-
- -

◆ MAX_METADATA_LENGTH

- -
-
- - - - - -
- - - - -
const constexpr uint16_t BNO08x::MAX_METADATA_LENGTH = 9U
-
-staticconstexprprivate
-
- -

max length of metadata used in frs read operations

- -
-
- -

◆ mems_raw_accel_X

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::mems_raw_accel_X
-
-private
-
- -
-
- -

◆ mems_raw_accel_Y

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::mems_raw_accel_Y
-
-private
-
- -
-
- -

◆ mems_raw_accel_Z

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::mems_raw_accel_Z
-
-private
-
- -

Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.5.8)

- -
-
- -

◆ mems_raw_gyro_X

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::mems_raw_gyro_X
-
-private
-
- -
-
- -

◆ mems_raw_gyro_Y

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::mems_raw_gyro_Y
-
-private
-
- -
-
- -

◆ mems_raw_gyro_Z

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::mems_raw_gyro_Z
-
-private
-
- -

Raw gyro readings from MEMS sensor (See SH-2 Ref. Manual 6.5.12)

- -
-
- -

◆ mems_raw_magf_X

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::mems_raw_magf_X
-
-private
-
- -
-
- -

◆ mems_raw_magf_Y

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::mems_raw_magf_Y
-
-private
-
- -
-
- -

◆ mems_raw_magf_Z

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::mems_raw_magf_Z
-
-private
-
- -

Raw magnetometer (compass) readings from MEMS sensor (See SH-2 Ref. Manual 6.5.15)

- -
-
- -

◆ meta_data

- -
-
- - - - - -
- - - - -
uint32_t BNO08x::meta_data[9]
-
-private
-
- -

First 9 bytes of meta data returned from FRS read operation (we don't really need the rest) (See Ref. Manual 5.1)

- -
-
- -

◆ quat_accuracy

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::quat_accuracy
-
-private
-
- -

Raw quaternion reading (See SH-2 Ref. Manual 6.5.44)

- -
-
- -

◆ queue_frs_read_data

- -
-
- - - - - -
- - - - -
QueueHandle_t BNO08x::queue_frs_read_data
-
-private
-
- -

Queue used to send packet body from data_proc_task to frs read functions.

- -
-
- -

◆ queue_reset_reason

- -
-
- - - - - -
- - - - -
QueueHandle_t BNO08x::queue_reset_reason
-
-private
-
- -

Queue used to send reset reason from product id report to reset_reason() function.

- -
-
- -

◆ queue_rx_data

- -
-
- - - - - -
- - - - -
QueueHandle_t BNO08x::queue_rx_data
-
-private
-
- -

Packet queue used to send data received from bno08x from spi_task to data_proc_task.

- -
-
- -

◆ queue_tx_data

- -
-
- - - - - -
- - - - -
QueueHandle_t BNO08x::queue_tx_data
-
-private
-
- -

Packet queue used to send data to be sent over SPI from sending functions to spi_task.

- -
-
- -

◆ raw_accel_X

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_accel_X
-
-private
-
- -
-
- -

◆ raw_accel_Y

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_accel_Y
-
-private
-
- -
-
- -

◆ raw_accel_Z

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_accel_Z
-
-private
-
- -
-
- -

◆ raw_bias_X

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_bias_X
-
-private
-
- -
-
- -

◆ raw_bias_Y

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_bias_Y
-
-private
-
- -
-
- -

◆ raw_bias_Z

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_bias_Z
-
-private
-
- -

Uncalibrated gyro reading (See SH-2 Ref. Manual 6.5.14)

- -
-
- -

◆ raw_calib_gyro_X

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_calib_gyro_X
-
-private
-
- -
-
- -

◆ raw_calib_gyro_Y

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_calib_gyro_Y
-
-private
-
- -
-
- -

◆ raw_calib_gyro_Z

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_calib_gyro_Z
-
-private
-
- -

Raw gyro reading (See SH-2 Ref. Manual 6.5.13)

- -
-
- -

◆ raw_lin_accel_X

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_lin_accel_X
-
-private
-
- -
-
- -

◆ raw_lin_accel_Y

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_lin_accel_Y
-
-private
-
- -
-
- -

◆ raw_lin_accel_Z

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_lin_accel_Z
-
-private
-
- -
-
- -

◆ raw_magf_X

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_magf_X
-
-private
-
- -
-
- -

◆ raw_magf_Y

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_magf_Y
-
-private
-
- -
-
- -

◆ raw_magf_Z

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_magf_Z
-
-private
-
- -
-
- -

◆ raw_quat_I

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_quat_I
-
-private
-
- -
-
- -

◆ raw_quat_J

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_quat_J
-
-private
-
- -
-
- -

◆ raw_quat_K

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_quat_K
-
-private
-
- -
-
- -

◆ raw_quat_radian_accuracy

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_quat_radian_accuracy
-
-private
-
- -
-
- -

◆ raw_quat_real

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_quat_real
-
-private
-
- -
-
- -

◆ raw_uncalib_gyro_X

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_uncalib_gyro_X
-
-private
-
- -
-
- -

◆ raw_uncalib_gyro_Y

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_uncalib_gyro_Y
-
-private
-
- -
-
- -

◆ raw_uncalib_gyro_Z

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::raw_uncalib_gyro_Z
-
-private
-
- -
-
- -

◆ REPORT_CNT

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::REPORT_CNT = 19
-
-staticconstexprprivate
-
- -

Total unique reports that can be returned by BNO08x.

- -
-
- -

◆ report_period_trackers

- -
-
- - - - - -
- - - - -
bno08x_report_period_tracker_t BNO08x::report_period_trackers[REPORT_CNT]
-
-private
-
-Initial value:
- - - - - - - -
0}}
-
static const constexpr uint8_t SENSOR_REPORT_ID_RAW_GYROSCOPE
See SH2 Ref. Manual 6.5.12.
Definition BNO08x.hpp:530
-
static const constexpr uint8_t SENSOR_REPORT_ID_MAGNETIC_FIELD
See SH2 Ref. Manual 6.5.16.
Definition BNO08x.hpp:518
-
static const constexpr uint8_t SENSOR_REPORT_ID_GYROSCOPE
See SH2 Ref. Manual 6.5.13.
Definition BNO08x.hpp:517
-
static const constexpr uint8_t SENSOR_REPORT_ID_STEP_COUNTER
See SH2 Ref. Manual 6.5.29.
Definition BNO08x.hpp:527
-
static const constexpr uint8_t SENSOR_REPORT_ID_ACCELEROMETER
See SH2 Ref. Manual 6.5.9.
Definition BNO08x.hpp:516
-
static const constexpr uint8_t SENSOR_REPORT_ID_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.18.
Definition BNO08x.hpp:520
-
static const constexpr uint8_t SENSOR_REPORT_ID_GRAVITY
See SH2 Ref. Manual 6.5.11.
Definition BNO08x.hpp:521
-
static const constexpr uint8_t SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER
See SH2 Ref. Manual 6.5.36.
Definition BNO08x.hpp:532
-
static const constexpr uint8_t SENSOR_REPORT_ID_RAW_ACCELEROMETER
See SH2 Ref. Manual 6.5.8.
Definition BNO08x.hpp:529
-
static const constexpr uint8_t SENSOR_REPORT_ID_TAP_DETECTOR
See SH2 Ref. Manual 6.5.27.
Definition BNO08x.hpp:526
-
static const constexpr uint8_t SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.42.
Definition BNO08x.hpp:533
-
static const constexpr uint8_t SENSOR_REPORT_ID_RAW_MAGNETOMETER
See SH2 Ref. Manual 6.5.15.
Definition BNO08x.hpp:531
-
static const constexpr uint8_t SENSOR_REPORT_ID_STABILITY_CLASSIFIER
See SH2 Ref. Manual 6.5.31.
Definition BNO08x.hpp:528
-
static const constexpr uint8_t SENSOR_REPORT_ID_GEOMAGNETIC_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.20.
Definition BNO08x.hpp:524
-
static const constexpr uint8_t SENSOR_REPORT_ID_UNCALIBRATED_GYRO
See SH2 Ref. Manual 6.5.14.
Definition BNO08x.hpp:522
-
static const constexpr uint8_t SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.44.
Definition BNO08x.hpp:525
-
static const constexpr uint8_t SENSOR_REPORT_ID_LINEAR_ACCELERATION
See SH2 Ref. Manual 6.5.10.
Definition BNO08x.hpp:519
-
static const constexpr uint8_t SENSOR_REPORT_ID_GAME_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.19.
Definition BNO08x.hpp:523
-
static const constexpr uint8_t SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.43.
Definition BNO08x.hpp:534
-
-

Current sample period of each report in microseconds linked to report ID (0 if not enabled).

- -
-
- -

◆ ROTATION_VECTOR_ACCURACY_Q1

- -
-
- - - - - -
- - - - -
const constexpr int16_t BNO08x::ROTATION_VECTOR_ACCURACY_Q1 = 12
-
-staticconstexpr
-
- -

Rotation vector accuracy estimate Q point (See SH-2 Ref. Manual 6.5.18)

- -
-
- -

◆ ROTATION_VECTOR_Q1

- -
-
- - - - - -
- - - - -
const constexpr int16_t BNO08x::ROTATION_VECTOR_Q1 = 14
-
-staticconstexpr
-
- -

Rotation vector Q point (See SH-2 Ref. Manual 6.5.18)

- -
-
- -

◆ RX_DATA_LENGTH

- -
-
- - - - - -
- - - - -
const constexpr uint16_t BNO08x::RX_DATA_LENGTH = 300U
-
-staticconstexprprivate
-
- -

length buffer containing data received over spi

- -
-
- -

◆ SCLK_MAX_SPEED

- -
-
- - - - - -
- - - - -
const constexpr uint32_t BNO08x::SCLK_MAX_SPEED = 3000000UL
-
-staticconstexprprivate
-
- -

Max SPI SCLK speed BNO08x is capable of.

- -
-
- -

◆ sem_kill_tasks

- -
-
- - - - - -
- - - - -
SemaphoreHandle_t BNO08x::sem_kill_tasks
-
-private
-
- -

semaphore to count amount of killed tasks

- -
-
- -

◆ SENSOR_REPORT_ID_ACCELEROMETER

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_ACCELEROMETER = 0x01U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.9.

- -
-
- -

◆ SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR = 0x29U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.43.

- -
-
- -

◆ SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR = 0x28U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.42.

- -
-
- -

◆ SENSOR_REPORT_ID_GAME_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_GAME_ROTATION_VECTOR = 0x08U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.19.

- -
-
- -

◆ SENSOR_REPORT_ID_GEOMAGNETIC_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_GEOMAGNETIC_ROTATION_VECTOR = 0x09U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.20.

- -
-
- -

◆ SENSOR_REPORT_ID_GRAVITY

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_GRAVITY = 0x06U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.11.

- -
-
- -

◆ SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR = 0x2AU
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.44.

- -
-
- -

◆ SENSOR_REPORT_ID_GYROSCOPE

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_GYROSCOPE = 0x02U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.13.

- -
-
- -

◆ SENSOR_REPORT_ID_LINEAR_ACCELERATION

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_LINEAR_ACCELERATION = 0x04U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.10.

- -
-
- -

◆ SENSOR_REPORT_ID_MAGNETIC_FIELD

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_MAGNETIC_FIELD = 0x03U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.16.

- -
-
- -

◆ SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER = 0x1EU
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.36.

- -
-
- -

◆ SENSOR_REPORT_ID_RAW_ACCELEROMETER

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_RAW_ACCELEROMETER = 0x14U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.8.

- -
-
- -

◆ SENSOR_REPORT_ID_RAW_GYROSCOPE

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_RAW_GYROSCOPE = 0x15U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.12.

- -
-
- -

◆ SENSOR_REPORT_ID_RAW_MAGNETOMETER

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_RAW_MAGNETOMETER = 0x16U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.15.

- -
-
- -

◆ SENSOR_REPORT_ID_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_ROTATION_VECTOR = 0x05U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.18.

- -
-
- -

◆ SENSOR_REPORT_ID_STABILITY_CLASSIFIER

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_STABILITY_CLASSIFIER = 0x13U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.31.

- -
-
- -

◆ SENSOR_REPORT_ID_STEP_COUNTER

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_STEP_COUNTER = 0x11U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.29.

- -
-
- -

◆ SENSOR_REPORT_ID_TAP_DETECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_TAP_DETECTOR = 0x10U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.27.

- -
-
- -

◆ SENSOR_REPORT_ID_UNCALIBRATED_GYRO

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SENSOR_REPORT_ID_UNCALIBRATED_GYRO = 0x07U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.14.

- -
-
- -

◆ SHTP_REPORT_BASE_TIMESTAMP

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SHTP_REPORT_BASE_TIMESTAMP = 0xFBU
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 7.2.1.

- -
-
- -

◆ SHTP_REPORT_COMMAND_REQUEST

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SHTP_REPORT_COMMAND_REQUEST = 0xF2U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.3.8.

- -
-
- -

◆ SHTP_REPORT_COMMAND_RESPONSE

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SHTP_REPORT_COMMAND_RESPONSE = 0xF1U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.3.9.

- -
-
- -

◆ SHTP_REPORT_FRS_READ_REQUEST

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SHTP_REPORT_FRS_READ_REQUEST = 0xF4U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.3.6.

- -
-
- -

◆ SHTP_REPORT_FRS_READ_RESPONSE

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SHTP_REPORT_FRS_READ_RESPONSE = 0xF3U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.3.7.

- -
-
- -

◆ SHTP_REPORT_GET_FEATURE_RESPONSE

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SHTP_REPORT_GET_FEATURE_RESPONSE = 0xFCU
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.5.

- -
-
- -

◆ SHTP_REPORT_PRODUCT_ID_REQUEST

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SHTP_REPORT_PRODUCT_ID_REQUEST = 0xF9U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.3.1.

- -
-
- -

◆ SHTP_REPORT_PRODUCT_ID_RESPONSE

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SHTP_REPORT_PRODUCT_ID_RESPONSE = 0xF8U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.3.2.

- -
-
- -

◆ SHTP_REPORT_SET_FEATURE_COMMAND

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::SHTP_REPORT_SET_FEATURE_COMMAND = 0xFDU
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.5.4.

- -
-
- -

◆ spi_hdl

- -
-
- - - - - -
- - - - -
spi_device_handle_t BNO08x::spi_hdl {}
-
-private
-
- -

SPI device handle.

- -
-
- -

◆ spi_task_hdl

- -
-
- - - - - -
- - - - -
TaskHandle_t BNO08x::spi_task_hdl
-
-private
-
- -

spi_task() handle

- -
-
- -

◆ spi_transaction

- -
-
- - - - - -
- - - - -
spi_transaction_t BNO08x::spi_transaction {}
-
-private
-
- -

SPI transaction handle.

- -
-
- -

◆ stability_classifier

- -
-
- - - - - -
- - - - -
uint8_t BNO08x::stability_classifier
-
-private
-
- -

BNO08xStability status reading (See SH-2 Ref. Manual 6.5.31)

- -
-
- -

◆ step_count

- -
-
- - - - - -
- - - - -
uint16_t BNO08x::step_count
-
-private
-
- -

Step counter reading (See SH-2 Ref. Manual 6.5.29)

- -
-
- -

◆ TAG

- -
-
- - - - - -
- - - - -
const constexpr char* BNO08x::TAG = "BNO08x"
-
-staticconstexprprivate
-
- -

Class tag used for serial print statements.

- -
-
- -

◆ tap_detector

- -
-
- - - - - -
- - - - -
uint8_t BNO08x::tap_detector
-
-private
-
- -

Tap detector reading (See SH-2 Ref. Manual 6.5.27)

- -
-
- -

◆ TARE_ARVR_STABILIZED_GAME_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::TARE_ARVR_STABILIZED_GAME_ROTATION_VECTOR = 5U
-
-staticconstexpr
-
- -

Tare ARVR stabilized game rotation vector.

- -
-
- -

◆ TARE_ARVR_STABILIZED_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::TARE_ARVR_STABILIZED_ROTATION_VECTOR = 4U
-
-staticconstexpr
-
- -

Tare ARVR stabilized rotation vector.

- -
-
- -

◆ TARE_AXIS_ALL

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::TARE_AXIS_ALL = 0x07U
-
-staticconstexpr
-
- -

Tare all axes (used with tare now command)

- -
-
- -

◆ TARE_AXIS_Z

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::TARE_AXIS_Z = 0x04U
-
-staticconstexpr
-
- -

Tar yaw axis only (used with tare now command)

- -
-
- -

◆ TARE_GAME_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::TARE_GAME_ROTATION_VECTOR = 1U
-
-staticconstexpr
-
- -

Tare game rotation vector.

- -
-
- -

◆ TARE_GEOMAGNETIC_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::TARE_GEOMAGNETIC_ROTATION_VECTOR = 2U
-
-staticconstexpr
-
- -

tare geomagnetic rotation vector

- -
-
- -

◆ TARE_GYRO_INTEGRATED_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::TARE_GYRO_INTEGRATED_ROTATION_VECTOR = 3U
-
-staticconstexpr
-
- -

Tare gyro integrated rotation vector.

- -
-
- -

◆ TARE_NOW

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::TARE_NOW = 0U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.4.4.1.

- -
-
- -

◆ TARE_PERSIST

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::TARE_PERSIST = 1U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.4.4.2.

- -
-
- -

◆ TARE_ROTATION_VECTOR

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::TARE_ROTATION_VECTOR = 0U
-
-staticconstexpr
-
- -

Tare rotation vector.

- -
-
- -

◆ TARE_SET_REORIENTATION

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::TARE_SET_REORIENTATION = 2U
-
-staticconstexprprivate
-
- -

See SH2 Ref. Manual 6.4.4.3.

- -
-
- -

◆ TASK_CNT

- -
-
- - - - - -
- - - - -
const constexpr uint8_t BNO08x::TASK_CNT = 2U
-
-staticconstexprprivate
-
- -

Total amount of tasks utilized by BNO08x driver library.

- -
-
- -

◆ time_stamp

- -
-
- - - - - -
- - - - -
uint32_t BNO08x::time_stamp
-
-private
-
- -

Report timestamp (see datasheet 1.3.5.3)

- -
-
-
The documentation for this class was generated from the following files: -
-
- - - - diff --git a/documentation/html/class_b_n_o08x.js b/documentation/html/class_b_n_o08x.js deleted file mode 100644 index e0a6154..0000000 --- a/documentation/html/class_b_n_o08x.js +++ /dev/null @@ -1,388 +0,0 @@ -var class_b_n_o08x = -[ - [ "bno08x_init_status_t", "struct_b_n_o08x_1_1bno08x__init__status__t.html", "struct_b_n_o08x_1_1bno08x__init__status__t" ], - [ "bno08x_report_period_tracker_t", "struct_b_n_o08x_1_1bno08x__report__period__tracker__t.html", "struct_b_n_o08x_1_1bno08x__report__period__tracker__t" ], - [ "bno08x_rx_packet_t", "struct_b_n_o08x_1_1bno08x__rx__packet__t.html", "struct_b_n_o08x_1_1bno08x__rx__packet__t" ], - [ "bno08x_tx_packet_t", "struct_b_n_o08x_1_1bno08x__tx__packet__t.html", "struct_b_n_o08x_1_1bno08x__tx__packet__t" ], - [ "bno08x_init_status_t", "class_b_n_o08x.html#a200dfd32391bcaff73e8498674c7ec87", null ], - [ "bno08x_report_period_tracker_t", "class_b_n_o08x.html#ae87c0e3c6eb34e209855d8e5d48c624b", null ], - [ "bno08x_rx_packet_t", "class_b_n_o08x.html#a407711b4a84223a52cc043a152aea8ba", null ], - [ "bno08x_tx_packet_t", "class_b_n_o08x.html#a3a1a869ac69e6ee850bd2a7f90dd8945", null ], - [ "channels_t", "class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638f", [ - [ "CHANNEL_COMMAND", "class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fad116268ebf7fb5e5cb4795ccc27867ed", null ], - [ "CHANNEL_EXECUTABLE", "class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fab1f28434b161c7ffa7b1a5c5f1a8a95b", null ], - [ "CHANNEL_CONTROL", "class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fa5b5d133bf4a91e14741fdd8e635e897e", null ], - [ "CHANNEL_REPORTS", "class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fabeb0a4983bc57ad2ce9f98360742e03e", null ], - [ "CHANNEL_WAKE_REPORTS", "class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638faefb874de7f2f90fb99b42bedf9623d21", null ], - [ "CHANNEL_GYRO", "class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fadd3caa696e525dd901de7a8e3dbf0731", null ] - ] ], - [ "BNO08x", "class_b_n_o08x.html#ad12fb6cf310ad7a04a4e53809833bd61", null ], - [ "~BNO08x", "class_b_n_o08x.html#a687eee44d68e1bcabce04780d7eb5fb9", null ], - [ "calibrate_accelerometer", "class_b_n_o08x.html#aeffce374f558a167d5b5f19ad627e7cc", null ], - [ "calibrate_all", "class_b_n_o08x.html#afd0ca5f9b9741935543d143a5a43d128", null ], - [ "calibrate_gyro", "class_b_n_o08x.html#a9ada90f8ab6dd33fa2d7c168d9234af1", null ], - [ "calibrate_magnetometer", "class_b_n_o08x.html#ac26350b55095a346d72598ab8aa74b4a", null ], - [ "calibrate_planar_accelerometer", "class_b_n_o08x.html#a1c6c49c97bc098db89db1aaa37e18f26", null ], - [ "calibration_complete", "class_b_n_o08x.html#a71ca35f78b98d93d31eb0c187dc8543b", null ], - [ "clear_tare", "class_b_n_o08x.html#afe39bfdede7b9a2b273983cb29a27d6e", null ], - [ "data_available", "class_b_n_o08x.html#ab56b185d6c9e972a2b28c2621387bb86", null ], - [ "data_proc_task", "class_b_n_o08x.html#ab4373e9b87837ea9fcbc0b536338c7b8", null ], - [ "data_proc_task_trampoline", "class_b_n_o08x.html#a0ae135d7bf7a5f047a1d1aa5cc07e520", null ], - [ "deinit_gpio", "class_b_n_o08x.html#a4f007dd431f10e741414d197bb4926c3", null ], - [ "deinit_gpio_inputs", "class_b_n_o08x.html#a1f0f4cd8dc7d38448e2198ea47d0018c", null ], - [ "deinit_gpio_outputs", "class_b_n_o08x.html#ab132a061bd437fd109225446aa1f6010", null ], - [ "deinit_hint_isr", "class_b_n_o08x.html#a9d96108b0f5b1e1e1ac431bc993ca758", null ], - [ "deinit_spi", "class_b_n_o08x.html#a233920ce97f685fbdabecccacf471d85", null ], - [ "disable_accelerometer", "class_b_n_o08x.html#ad5c991150895b80bee68c933059a4058", null ], - [ "disable_activity_classifier", "class_b_n_o08x.html#a4fdc39294922a9553d84cd96bdae4376", null ], - [ "disable_ARVR_stabilized_game_rotation_vector", "class_b_n_o08x.html#ab187fe50fcfbb04bec9e80eb0fccf61c", null ], - [ "disable_ARVR_stabilized_rotation_vector", "class_b_n_o08x.html#aa59e3d8953c96dc1cc5958a1ac628df4", null ], - [ "disable_calibrated_gyro", "class_b_n_o08x.html#a4d6832a3c0b2b4014e28145e6ffe9c2c", null ], - [ "disable_game_rotation_vector", "class_b_n_o08x.html#a7665cce95e791c89161ec863f49c0392", null ], - [ "disable_gravity", "class_b_n_o08x.html#a5e63a9e68dbe2968b37dcb6dae04de6f", null ], - [ "disable_gyro_integrated_rotation_vector", "class_b_n_o08x.html#aac0a00bed7825d8a2c357a48c3626931", null ], - [ "disable_linear_accelerometer", "class_b_n_o08x.html#afbd2b02d5abe7084ce9de49ee2c9142f", null ], - [ "disable_magnetometer", "class_b_n_o08x.html#a6671b082d20dda8bf5c53cb47db0c338", null ], - [ "disable_raw_mems_accelerometer", "class_b_n_o08x.html#a6cd96063eeac75af5f292bdcd31972ce", null ], - [ "disable_raw_mems_gyro", "class_b_n_o08x.html#a5d3ed8a44a34553cf5239cdd4032e725", null ], - [ "disable_raw_mems_magnetometer", "class_b_n_o08x.html#a62d634fc9bced0197103f2973f27bae2", null ], - [ "disable_report", "class_b_n_o08x.html#a00ec3857cb06ae885e32059ef1cab693", null ], - [ "disable_rotation_vector", "class_b_n_o08x.html#a1ebd456d2a67a22b5ba0911a95915921", null ], - [ "disable_stability_classifier", "class_b_n_o08x.html#ab307ed3352e04c9e998ab4dd066f8932", null ], - [ "disable_step_counter", "class_b_n_o08x.html#a427550a4ba25252912436b899124e157", null ], - [ "disable_tap_detector", "class_b_n_o08x.html#a16f83d1e85576a51abf2c65e5de58cd2", null ], - [ "disable_uncalibrated_gyro", "class_b_n_o08x.html#aaf28212a5f1960c62a73282976142cfc", null ], - [ "enable_accelerometer", "class_b_n_o08x.html#a2795c6579cf03e22f62a5eadc88dee91", null ], - [ "enable_activity_classifier", "class_b_n_o08x.html#a039e8770759e784baa438324ae17883c", null ], - [ "enable_ARVR_stabilized_game_rotation_vector", "class_b_n_o08x.html#a5680148a41cb9cc96d1911150c46d2b8", null ], - [ "enable_ARVR_stabilized_rotation_vector", "class_b_n_o08x.html#a8a5f3b985989e846e831f70f7733d0bc", null ], - [ "enable_calibrated_gyro", "class_b_n_o08x.html#a9e72a094c4469c9eb9fb766744560c53", null ], - [ "enable_game_rotation_vector", "class_b_n_o08x.html#abe04c38b5bd52d331bd8aefae1f51947", null ], - [ "enable_gravity", "class_b_n_o08x.html#a030eae12c3586acf09b48e94630b2544", null ], - [ "enable_gyro_integrated_rotation_vector", "class_b_n_o08x.html#a7388c67de3906ad05b233fd7eff0514d", null ], - [ "enable_linear_accelerometer", "class_b_n_o08x.html#ae1435b83ca83bc51b75f3303afe87f7b", null ], - [ "enable_magnetometer", "class_b_n_o08x.html#a3c32120bcd0987c3ca1bb72910586b59", null ], - [ "enable_raw_mems_accelerometer", "class_b_n_o08x.html#a69f768318a621a7dc6620e5551926c3b", null ], - [ "enable_raw_mems_gyro", "class_b_n_o08x.html#a8be135ed41646199540583b29806d4e5", null ], - [ "enable_raw_mems_magnetometer", "class_b_n_o08x.html#a69b3255550345bcb2d302476d50e38a5", null ], - [ "enable_report", "class_b_n_o08x.html#a789f9b9b8ad0a84a6ca45a85740823ca", null ], - [ "enable_rotation_vector", "class_b_n_o08x.html#ab4c1d5cde156af09b7e88913f3af62c7", null ], - [ "enable_stability_classifier", "class_b_n_o08x.html#ab0a60844b36fb140cad588a65b3a9655", null ], - [ "enable_step_counter", "class_b_n_o08x.html#a5a0b0f5b8e962247a3b8aee8f1dc8e9f", null ], - [ "enable_tap_detector", "class_b_n_o08x.html#ab4c8e37c730ddb168f78c29bd7ae6566", null ], - [ "enable_uncalibrated_gyro", "class_b_n_o08x.html#a7fe5de95b1f51da44247a87317fd0c75", null ], - [ "end_calibration", "class_b_n_o08x.html#ac9d9b6636745e8180807284da67c92a2", null ], - [ "flush_rx_packets", "class_b_n_o08x.html#a48c1d43b66b1a0894cb1fc2179f62cdc", null ], - [ "FRS_read_data", "class_b_n_o08x.html#a40607e557eada666a5e1e416f42cd4a1", null ], - [ "FRS_read_request", "class_b_n_o08x.html#adf789e709ac1667656db757c8d559af9", null ], - [ "FRS_read_word", "class_b_n_o08x.html#a27f5dce5c994be18a587fb622574ad41", null ], - [ "get_accel", "class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885", null ], - [ "get_accel_accuracy", "class_b_n_o08x.html#a6eed9e2d3e639ec7e38dfdf092c14ea1", null ], - [ "get_accel_X", "class_b_n_o08x.html#abce574112a9079d2cbc58cfc352b8a69", null ], - [ "get_accel_Y", "class_b_n_o08x.html#afdf24bb3d54518b23972f21f007817c1", null ], - [ "get_accel_Z", "class_b_n_o08x.html#a0a72477cb7a330fedbcb3e2126b882b1", null ], - [ "get_activity_classifier", "class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed", null ], - [ "get_calibrated_gyro_velocity", "class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f", null ], - [ "get_calibrated_gyro_velocity_X", "class_b_n_o08x.html#a7710e8bee76742e351cecfaf441f0889", null ], - [ "get_calibrated_gyro_velocity_Y", "class_b_n_o08x.html#a492d5bde7377d9f6773eae1d70967f50", null ], - [ "get_calibrated_gyro_velocity_Z", "class_b_n_o08x.html#a1599c0515f05a08c043f237c46d29dea", null ], - [ "get_gravity", "class_b_n_o08x.html#a067678914e928a6691625b17c40237a0", null ], - [ "get_gravity_accuracy", "class_b_n_o08x.html#a77c82cece30dde944efcde81643fd62d", null ], - [ "get_gravity_X", "class_b_n_o08x.html#a88679bccd9339b87ec35fc4fc4e745ae", null ], - [ "get_gravity_Y", "class_b_n_o08x.html#a8a36db7f1c932f33e05e494632059801", null ], - [ "get_gravity_Z", "class_b_n_o08x.html#a5622b4d1754648ea7eb400c1adf9e807", null ], - [ "get_integrated_gyro_velocity", "class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f", null ], - [ "get_integrated_gyro_velocity_X", "class_b_n_o08x.html#a2eb2accfbc70366e6e3eaf391622c1ff", null ], - [ "get_integrated_gyro_velocity_Y", "class_b_n_o08x.html#aff9a7e0190b228f5032474a3f4feb9a1", null ], - [ "get_integrated_gyro_velocity_Z", "class_b_n_o08x.html#aa5b483cb0036e9dd43bf797259634add", null ], - [ "get_linear_accel", "class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46", null ], - [ "get_linear_accel_accuracy", "class_b_n_o08x.html#a6114ba3c8967ac8fde06233c81623c80", null ], - [ "get_linear_accel_X", "class_b_n_o08x.html#a763c3a9699a1081d430fd9b9b7bc49a3", null ], - [ "get_linear_accel_Y", "class_b_n_o08x.html#a1033bdd65b42b6706d1dfc67ece66191", null ], - [ "get_linear_accel_Z", "class_b_n_o08x.html#afdfa7d50362702da689c5d18bf17fd84", null ], - [ "get_magf", "class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb", null ], - [ "get_magf_accuracy", "class_b_n_o08x.html#a2d98b2cba47dffee8745de1955d234a9", null ], - [ "get_magf_X", "class_b_n_o08x.html#a111601243b913751eb51c1f37cba4e7d", null ], - [ "get_magf_Y", "class_b_n_o08x.html#a82ed8d7b9a5c25374839df75a3d220ea", null ], - [ "get_magf_Z", "class_b_n_o08x.html#ab4c48a91d2f8b29430abc17b7f015282", null ], - [ "get_pitch", "class_b_n_o08x.html#a1b91f234d81c45f1f5ca2f27c9f0f6a3", null ], - [ "get_pitch_deg", "class_b_n_o08x.html#af50010400cbd1445e9ddfa259384b412", null ], - [ "get_Q1", "class_b_n_o08x.html#a4421c43323945946ad605f8422958dcf", null ], - [ "get_Q2", "class_b_n_o08x.html#a954dccdcbe8a8c4f1787f13ebb8d932b", null ], - [ "get_Q3", "class_b_n_o08x.html#a1590ba793668f9cb1a32a1f4dd07cb9a", null ], - [ "get_quat", "class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a", null ], - [ "get_quat_accuracy", "class_b_n_o08x.html#a7c7a74367db26ea8bfbdea633ee1d654", null ], - [ "get_quat_I", "class_b_n_o08x.html#a12c12a8e078b28480fb8828d306656f5", null ], - [ "get_quat_J", "class_b_n_o08x.html#a9f6bb642fa0297a7b9bcc94dd7374015", null ], - [ "get_quat_K", "class_b_n_o08x.html#a9f42c70c2337a0d831064a40ecfe2dd8", null ], - [ "get_quat_radian_accuracy", "class_b_n_o08x.html#a61b7d10a98afc6903fea6b2cede27630", null ], - [ "get_quat_real", "class_b_n_o08x.html#a5a556c5ec1baaa7f1156779dbe47a7b7", null ], - [ "get_range", "class_b_n_o08x.html#a0fff04c42c9502615ad73cd1457cb9b0", null ], - [ "get_raw_mems_accel", "class_b_n_o08x.html#aa6bbad8c9123b4dba5007f72a8806303", null ], - [ "get_raw_mems_accel_X", "class_b_n_o08x.html#a868b24d96cb12f614431a410bcc9e434", null ], - [ "get_raw_mems_accel_Y", "class_b_n_o08x.html#aebcbaf9c3aaf37d85a78d22dc22c614a", null ], - [ "get_raw_mems_accel_Z", "class_b_n_o08x.html#a85d1331ebe762f6823bde4bf76a33e21", null ], - [ "get_raw_mems_gyro", "class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27", null ], - [ "get_raw_mems_gyro_X", "class_b_n_o08x.html#a8872241c73bca2ac1698ae867f7d1913", null ], - [ "get_raw_mems_gyro_Y", "class_b_n_o08x.html#a4bcc58423b5cc7c24080c2ef812d3d86", null ], - [ "get_raw_mems_gyro_Z", "class_b_n_o08x.html#ae684dd13ef630dfdbb8de18ee5ea90bb", null ], - [ "get_raw_mems_magf", "class_b_n_o08x.html#a929ad333f73614fb5830c186e3e03a00", null ], - [ "get_raw_mems_magf_X", "class_b_n_o08x.html#a347444f461b2fab5ff37de346ba2a595", null ], - [ "get_raw_mems_magf_Y", "class_b_n_o08x.html#ad8a215314ae96b25b59fdc363c52261c", null ], - [ "get_raw_mems_magf_Z", "class_b_n_o08x.html#a780651af54485edb36d197f30c071615", null ], - [ "get_reset_reason", "class_b_n_o08x.html#a96d47dd0f9aedfbe3f731f8ae76b2e85", null ], - [ "get_resolution", "class_b_n_o08x.html#a1d6ea02d0d4b23ff6a15e9d5c6c92372", null ], - [ "get_roll", "class_b_n_o08x.html#a89618eba08186ee8e679e7313907ddef", null ], - [ "get_roll_deg", "class_b_n_o08x.html#a7077b9a130f1dcf0192454e387968dd6", null ], - [ "get_stability_classifier", "class_b_n_o08x.html#a248544b262582d10d917a687190cb454", null ], - [ "get_step_count", "class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef", null ], - [ "get_tap_detector", "class_b_n_o08x.html#a4797ec731de4c158716da1a7af9d1602", null ], - [ "get_time_stamp", "class_b_n_o08x.html#ad9137777271421a58159f3fe5e05ed20", null ], - [ "get_uncalibrated_gyro_bias_X", "class_b_n_o08x.html#ad228cdf352b7ea95e484da993045a47b", null ], - [ "get_uncalibrated_gyro_bias_Y", "class_b_n_o08x.html#a74725517129dd548c7a3de705d5861bd", null ], - [ "get_uncalibrated_gyro_bias_Z", "class_b_n_o08x.html#a5050359272abd146ab3c7a6101effbd7", null ], - [ "get_uncalibrated_gyro_velocity", "class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104", null ], - [ "get_uncalibrated_gyro_velocity_X", "class_b_n_o08x.html#a71bbcd4b4d63d55d4f7d5f0de6154486", null ], - [ "get_uncalibrated_gyro_velocity_Y", "class_b_n_o08x.html#a2d5a9fa5c960b9efa96d311d25f711de", null ], - [ "get_uncalibrated_gyro_velocity_Z", "class_b_n_o08x.html#ab6dc34d058002e21978f8a7e4cf24592", null ], - [ "get_yaw", "class_b_n_o08x.html#a64d3e41750c6de9413d6982511f78f17", null ], - [ "get_yaw_deg", "class_b_n_o08x.html#af80f7795656e695e036d3b1557aed94c", null ], - [ "hard_reset", "class_b_n_o08x.html#a28cd1c0b3477571d87133234e6358503", null ], - [ "hint_handler", "class_b_n_o08x.html#a804b95c58c30d36933fd251626b85bf7", null ], - [ "init_config_args", "class_b_n_o08x.html#a589eb9780f5bf613bbd447ef5b9ade3d", null ], - [ "init_gpio", "class_b_n_o08x.html#ae0dab25557befcf62bf384fdc241ef10", null ], - [ "init_gpio_inputs", "class_b_n_o08x.html#a8f34d5475474f00ae6a92f73c1fe14e4", null ], - [ "init_gpio_outputs", "class_b_n_o08x.html#ad0b9e8f8d051798bb1da9b19598dbd64", null ], - [ "init_hint_isr", "class_b_n_o08x.html#aa27026da2c52b4aca49b78863f10ec61", null ], - [ "init_spi", "class_b_n_o08x.html#a58f43c8bb1e7fe8560ce442d46240e81", null ], - [ "initialize", "class_b_n_o08x.html#aea8e2c6dd7a2c9899479a7f39fe94798", null ], - [ "kill_all_tasks", "class_b_n_o08x.html#a5adc21b484ff98c42622e2ad9871d5a0", null ], - [ "launch_tasks", "class_b_n_o08x.html#a06f99a6b2182b49a0e61e2107f2be6be", null ], - [ "mode_on", "class_b_n_o08x.html#ac1b3de9b552c611ee9c455d7f19be698", null ], - [ "mode_sleep", "class_b_n_o08x.html#a176ae0112325c05105eacb4566bbfa0b", null ], - [ "parse_command_report", "class_b_n_o08x.html#a4f66045a0528a0c17c52421ea51612e7", null ], - [ "parse_feature_get_response_report", "class_b_n_o08x.html#a206c0e3ddc3b745b56914976d6e69981", null ], - [ "parse_frs_read_response_report", "class_b_n_o08x.html#a51b360d795563b55559f11efb40be36a", null ], - [ "parse_gyro_integrated_rotation_vector_report", "class_b_n_o08x.html#a7be6047fef851a064c7cbc9eba092f6d", null ], - [ "parse_input_report", "class_b_n_o08x.html#a8d9db3e1b6208c2661e1c543deefa53d", null ], - [ "parse_input_report_data", "class_b_n_o08x.html#a002aa97c9af8f6df2d0c83034e4f7b55", null ], - [ "parse_packet", "class_b_n_o08x.html#a1c47d27917ae3b2876efa121b803f924", null ], - [ "parse_product_id_report", "class_b_n_o08x.html#a29cfd7fc2816483ebebe9d55b677a036", null ], - [ "print_header", "class_b_n_o08x.html#a35856c108a47de8b3b38c4395aabb4eb", null ], - [ "print_packet", "class_b_n_o08x.html#a05e4cd5861b55fc0182d7dd13bb85e49", null ], - [ "q_to_float", "class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9", null ], - [ "queue_calibrate_command", "class_b_n_o08x.html#ad097849616c5caab1fd3eb3632ee2b91", null ], - [ "queue_command", "class_b_n_o08x.html#a5cc58139e4d5f0587b90e249ceb476f9", null ], - [ "queue_feature_command", "class_b_n_o08x.html#af7f960dbd26c6f1834661ef5f5bbd4d3", null ], - [ "queue_packet", "class_b_n_o08x.html#a62c570ba96512f4d0d10b2594048de1f", null ], - [ "queue_request_product_id_command", "class_b_n_o08x.html#ab5f200069a2f8cb74cb79c6f162da5a1", null ], - [ "queue_tare_command", "class_b_n_o08x.html#a4c6353e795f734ed28613f9a3d161ea2", null ], - [ "receive_packet", "class_b_n_o08x.html#a8d9f28d8857279a3c4b1f62f6dabb638", null ], - [ "receive_packet_body", "class_b_n_o08x.html#a9ee7e73f695af8965a9ede50136d5a8c", null ], - [ "receive_packet_header", "class_b_n_o08x.html#acb246769719351e02bf2aff06d039475", null ], - [ "register_cb", "class_b_n_o08x.html#a06bb0c70305421b5357e64f31579fdc7", null ], - [ "report_ID_to_report_period_tracker_idx", "class_b_n_o08x.html#a27b5317d11a5b81028b87a73b7024bfa", null ], - [ "request_calibration_status", "class_b_n_o08x.html#affaaa35abbb872da5299ebab6e2c9b11", null ], - [ "reset_all_data_to_defaults", "class_b_n_o08x.html#a453ec8a70646651d4e5b10bf0b2e4d61", null ], - [ "run_full_calibration_routine", "class_b_n_o08x.html#ae6e875a27ae74ebed806ee1a4576845a", null ], - [ "save_calibration", "class_b_n_o08x.html#aa16609de88bfb7b389348859aa0cee54", null ], - [ "save_tare", "class_b_n_o08x.html#afb2ffc4e7ff0498917bc14a83af306e2", null ], - [ "send_packet", "class_b_n_o08x.html#a2c359a44a2c8e83ecb258a340e2d0e1a", null ], - [ "soft_reset", "class_b_n_o08x.html#a973a1b1785f3302ee1b2702c6a27646e", null ], - [ "spi_task", "class_b_n_o08x.html#a2ecd4ed60f82730ae230c61687ec92bf", null ], - [ "spi_task_trampoline", "class_b_n_o08x.html#a0ce6d9db873555f1ebe7e095251eab74", null ], - [ "tare_now", "class_b_n_o08x.html#a4549bbef48208bd9c745fc755b93012f", null ], - [ "update_accelerometer_data", "class_b_n_o08x.html#afe588fbd0055193d3bc08984d7732354", null ], - [ "update_calibrated_gyro_data", "class_b_n_o08x.html#a962b695ef4733d558c6f9684da0931ab", null ], - [ "update_command_data", "class_b_n_o08x.html#af971d82426740e62c1f05adcd2c9ce7c", null ], - [ "update_gravity_data", "class_b_n_o08x.html#ad7de3999d4df19038e27c01f9b02010e", null ], - [ "update_integrated_gyro_rotation_vector_data", "class_b_n_o08x.html#ab02386f13caa446bab5921c1a71f92ab", null ], - [ "update_lin_accelerometer_data", "class_b_n_o08x.html#a7416d844f6188c8d16f181d6d4431708", null ], - [ "update_magf_data", "class_b_n_o08x.html#a3abf4a199bc7a03ac7447c2781673d88", null ], - [ "update_personal_activity_classifier_data", "class_b_n_o08x.html#a04489cf9a125495c7cf07c6ba5e9f6c0", null ], - [ "update_raw_accelerometer_data", "class_b_n_o08x.html#a83fed63c67957ec4338afd43087d6e22", null ], - [ "update_raw_gyro_data", "class_b_n_o08x.html#ad0f0fec4e53029b4ba907414a36ac5ea", null ], - [ "update_raw_magf_data", "class_b_n_o08x.html#a6ddc9600c53a4248d1affcab36f6f245", null ], - [ "update_report_period_trackers", "class_b_n_o08x.html#a0ec9b1a10bbf25a057273605575f0d64", null ], - [ "update_rotation_vector_data", "class_b_n_o08x.html#aa309152750686fbf8ebf7d6de1f1254b", null ], - [ "update_stability_classifier_data", "class_b_n_o08x.html#a358316b883928c50dd381f024e6b0645", null ], - [ "update_step_counter_data", "class_b_n_o08x.html#aa390bf840246e3233e07f6a424efcb6f", null ], - [ "update_tap_detector_data", "class_b_n_o08x.html#ac75b7fb1a1b407d0888ea07d708831b1", null ], - [ "update_uncalibrated_gyro_data", "class_b_n_o08x.html#a8de12c9c47549502147bd85dbb7e364e", null ], - [ "wait_for_data", "class_b_n_o08x.html#a4f12de628073f44b2a3fab2688cf1caf", null ], - [ "wait_for_rx_done", "class_b_n_o08x.html#a2897a178bf2c53cd99df0d4570edf72e", null ], - [ "wait_for_tx_done", "class_b_n_o08x.html#a7cdeb849e728487de961cdfd4030c773", null ], - [ "BNO08xTestHelper", "class_b_n_o08x.html#a190775b71c35d8007faae7dd6a9f1030", null ], - [ "accel_accuracy", "class_b_n_o08x.html#a3365b7ebde01e284274e655c60343df9", null ], - [ "accel_lin_accuracy", "class_b_n_o08x.html#a35e1635ef5edde8fc8640f978c6f2e3c", null ], - [ "ACCELEROMETER_Q1", "class_b_n_o08x.html#a0564aaf5b20dc42b54db4fb3115ac1c7", null ], - [ "activity_classifier", "class_b_n_o08x.html#a75cea49c1c08ca28d9fa7e5ed61c6e7b", null ], - [ "activity_confidences", "class_b_n_o08x.html#af96e8cd070459f945ffbf01b98106e13", null ], - [ "ANGULAR_VELOCITY_Q1", "class_b_n_o08x.html#aafe117561fe9138800073a04a778b4ce", null ], - [ "bus_config", "class_b_n_o08x.html#a982f065df42f00e53fd87c840efdb0f1", null ], - [ "CALIBRATE_ACCEL", "class_b_n_o08x.html#acd5b44d705af1f9aaa271a59a9d2d595", null ], - [ "CALIBRATE_ACCEL_GYRO_MAG", "class_b_n_o08x.html#af53d9e99f163d97ef92fe989b1dd25cc", null ], - [ "CALIBRATE_GYRO", "class_b_n_o08x.html#aeac84719a1cc0f9c8d5a9a749391d4db", null ], - [ "CALIBRATE_MAG", "class_b_n_o08x.html#ac00e8b59ae8d710cf79956eaafa97ddb", null ], - [ "CALIBRATE_PLANAR_ACCEL", "class_b_n_o08x.html#a955dcb60da150490e17367a871b3a3d2", null ], - [ "CALIBRATE_STOP", "class_b_n_o08x.html#a584bfa04a39feb93279ee673c340db54", null ], - [ "calibration_status", "class_b_n_o08x.html#ad212b5028a31e857e76d251ced2724e1", null ], - [ "cb_list", "class_b_n_o08x.html#a6a15e3a64dd71ea61f0448afcce96409", null ], - [ "CMD_EXECUTION_DELAY_MS", "class_b_n_o08x.html#a38e31bdb22afdfe05372ffcd5eabfdd2", null ], - [ "COMMAND_CLEAR_DCD", "class_b_n_o08x.html#a4f580b3cb232a762ea7019ee7b04d419", null ], - [ "COMMAND_COUNTER", "class_b_n_o08x.html#a93dd073c0cc1f3ccfde552649f6ebccc", null ], - [ "COMMAND_DCD", "class_b_n_o08x.html#af124a6c1d8b871f3181b6c85f1099cb2", null ], - [ "COMMAND_DCD_PERIOD_SAVE", "class_b_n_o08x.html#a7a246989c94cd87f68166b20b7ad4c8b", null ], - [ "COMMAND_ERRORS", "class_b_n_o08x.html#a384a1efc9857ad938be3bb44f871539b", null ], - [ "COMMAND_INITIALIZE", "class_b_n_o08x.html#a30eb6d305a187d4d36546841e12176b9", null ], - [ "COMMAND_ME_CALIBRATE", "class_b_n_o08x.html#a8381dfe403ddff522f172cb16780731a", null ], - [ "COMMAND_OSCILLATOR", "class_b_n_o08x.html#a308c8b5307d93a67b5b9066d44494aa5", null ], - [ "COMMAND_TARE", "class_b_n_o08x.html#a0a1756bc16ba3eac45f4229b1e350107", null ], - [ "current_slowest_report_ID", "class_b_n_o08x.html#ae2e8382b5ff8d0ca3375a10b6e273f0c", null ], - [ "data_proc_task_hdl", "class_b_n_o08x.html#af9b6fbf35e7cd55d517d30c6429a21a4", null ], - [ "evt_grp_report_en", "class_b_n_o08x.html#a63eb6c8be6f3bc943a86bb0496871275", null ], - [ "EVT_GRP_RPT_ACCELEROMETER_BIT", "class_b_n_o08x.html#a17b19c32d4dfbc9ae2761a0cdd873314", null ], - [ "EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BIT", "class_b_n_o08x.html#a96eb1b1bfe1266791fd424b3ce402c56", null ], - [ "EVT_GRP_RPT_ALL_BITS", "class_b_n_o08x.html#a89399e8a68a53bc2a269ab73625a2da2", null ], - [ "EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BIT", "class_b_n_o08x.html#a79d3fff1e0f19467cad231b22edafa0f", null ], - [ "EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BIT", "class_b_n_o08x.html#aa9703cee46912a545b5e85e671f08e4b", null ], - [ "EVT_GRP_RPT_GAME_ROTATION_VECTOR_BIT", "class_b_n_o08x.html#a0f3f33d93b72ba6564f9d5fa93c24f98", null ], - [ "EVT_GRP_RPT_GRAVITY_BIT", "class_b_n_o08x.html#ab94a8f69673a3db7556ba67775c5ea93", null ], - [ "EVT_GRP_RPT_GYRO_BIT", "class_b_n_o08x.html#a3a8b12ea9b75f97191785a60d1aa962a", null ], - [ "EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BIT", "class_b_n_o08x.html#a541155dc4544193451cf102e2a992da9", null ], - [ "EVT_GRP_RPT_GYRO_UNCALIBRATED_BIT", "class_b_n_o08x.html#af86821bc0f1e7f5897de20b5e47a85bd", null ], - [ "EVT_GRP_RPT_LINEAR_ACCELEROMETER_BIT", "class_b_n_o08x.html#ad93161968a53ff53a6bb74ab7c34fbff", null ], - [ "EVT_GRP_RPT_MAGNETOMETER_BIT", "class_b_n_o08x.html#a901af6f2d552f197ee830d0a1c06679c", null ], - [ "EVT_GRP_RPT_RAW_ACCELEROMETER_BIT", "class_b_n_o08x.html#a3e56d12435f7be81956d68196f1a46b4", null ], - [ "EVT_GRP_RPT_RAW_GYRO_BIT", "class_b_n_o08x.html#a6be7b240e4447c2c643e706954093aa0", null ], - [ "EVT_GRP_RPT_RAW_MAGNETOMETER_BIT", "class_b_n_o08x.html#ac28553b40b82c7cb409938681afe6cec", null ], - [ "EVT_GRP_RPT_ROTATION_VECTOR_BIT", "class_b_n_o08x.html#a198da2ee3cd9cfa459c3c41c4f8c44b7", null ], - [ "EVT_GRP_RPT_STABILITY_CLASSIFIER_BIT", "class_b_n_o08x.html#a7d6ee23222f55dbe9f70e04b36d9add2", null ], - [ "EVT_GRP_RPT_STEP_COUNTER_BIT", "class_b_n_o08x.html#ab264b65a3aa5a9a74ed11b8977164a73", null ], - [ "EVT_GRP_RPT_TAP_DETECTOR_BIT", "class_b_n_o08x.html#a665464f781fe891b9179478d0174af47", null ], - [ "evt_grp_spi", "class_b_n_o08x.html#aa2b4442b5cc63ebf0c495e6fb537c85e", null ], - [ "EVT_GRP_SPI_RX_DONE_BIT", "class_b_n_o08x.html#a32cffd8f78881925d22d5a7cb55f2bbc", null ], - [ "EVT_GRP_SPI_RX_INVALID_PACKET_BIT", "class_b_n_o08x.html#a15e3f92812f8fe70b30966b73a7cb5b2", null ], - [ "EVT_GRP_SPI_RX_VALID_PACKET_BIT", "class_b_n_o08x.html#a96342b0182f339d5a8d6cac1214ce174", null ], - [ "EVT_GRP_SPI_TX_DONE_BIT", "class_b_n_o08x.html#adf2c292674e428c3b65c846cfab4deb7", null ], - [ "evt_grp_task_flow", "class_b_n_o08x.html#ac4b1fae7a1155c8b93b645b4eb6eb0f1", null ], - [ "EVT_GRP_TSK_FLW_RUNNING_BIT", "class_b_n_o08x.html#a5fc8c8969043c5d08fce80eb1d74a761", null ], - [ "first_boot", "class_b_n_o08x.html#ae4670fed6de963a087ab58f95fda319b", null ], - [ "FRS_RECORD_ID_ACCELEROMETER", "class_b_n_o08x.html#ad7ef7d7068af5f92239c12022dbeb16d", null ], - [ "FRS_RECORD_ID_GYROSCOPE_CALIBRATED", "class_b_n_o08x.html#a35d8f641e73c308f92a5a0a772f90f48", null ], - [ "FRS_RECORD_ID_MAGNETIC_FIELD_CALIBRATED", "class_b_n_o08x.html#a0992d77f9bae0b8e3c8d9331fe84fe24", null ], - [ "FRS_RECORD_ID_ROTATION_VECTOR", "class_b_n_o08x.html#a9f35840b19c8ad11fd1b4622c3269250", null ], - [ "gravity_accuracy", "class_b_n_o08x.html#ae01698d287ea999179a11e2244902022", null ], - [ "GRAVITY_Q1", "class_b_n_o08x.html#ae10722334dfce9635e76519598e165a2", null ], - [ "gravity_X", "class_b_n_o08x.html#af45016be9ea523d80be8467b2907b499", null ], - [ "gravity_Y", "class_b_n_o08x.html#af20dcd487a9fe8fa6243817d51e37be5", null ], - [ "gravity_Z", "class_b_n_o08x.html#afa1cf5c3afbb258d97c55c5fb187f2d6", null ], - [ "GYRO_Q1", "class_b_n_o08x.html#aa3bec8effefa61cec6fa170e9d02c4dd", null ], - [ "HARD_RESET_DELAY_MS", "class_b_n_o08x.html#aa07e329d693eb8d9270a7f9ad6f1d94b", null ], - [ "HOST_INT_TIMEOUT_DEFAULT_MS", "class_b_n_o08x.html#ae51d4e3228a91ee407d5866e604804c4", null ], - [ "host_int_timeout_ms", "class_b_n_o08x.html#ab0c1b4ef4dbcc05a2a6cf37ee039ba0e", null ], - [ "imu_config", "class_b_n_o08x.html#aeda443e9f608fccfec0e6770edc90c82", null ], - [ "imu_spi_config", "class_b_n_o08x.html#a425a1f5a9f3232aadc685caaf4c2f82e", null ], - [ "init_status", "class_b_n_o08x.html#a4520fc3e1dec6389d470945786680013", null ], - [ "integrated_gyro_velocity_X", "class_b_n_o08x.html#a6537ed69245cf71cad6a6a44480dddaa", null ], - [ "integrated_gyro_velocity_Y", "class_b_n_o08x.html#a00b39e22ea9fe306e88aaed490ee0a51", null ], - [ "integrated_gyro_velocity_Z", "class_b_n_o08x.html#ad112beb64badd22a2e1d717e1ee921c8", null ], - [ "largest_sample_period_us", "class_b_n_o08x.html#a7ffc2875b3dff21a827052e4faf273b7", null ], - [ "LINEAR_ACCELEROMETER_Q1", "class_b_n_o08x.html#ad0d37fe07ced24f2c9afc21145a74e7b", null ], - [ "magf_accuracy", "class_b_n_o08x.html#ac5d4e151690774687efa951ca41c16ae", null ], - [ "MAGNETOMETER_Q1", "class_b_n_o08x.html#a9fac9b811b7c2117675a784cb4df204c", null ], - [ "MAX_METADATA_LENGTH", "class_b_n_o08x.html#a2a5b978233eab4c103ab01cfc33a1750", null ], - [ "mems_raw_accel_X", "class_b_n_o08x.html#a937cbdc4edaac72c8cad041d79de5701", null ], - [ "mems_raw_accel_Y", "class_b_n_o08x.html#ad83cecb8a5d2be01db6792755b6057e9", null ], - [ "mems_raw_accel_Z", "class_b_n_o08x.html#a59a4d75f1302ab693b1b26e9ccaa5341", null ], - [ "mems_raw_gyro_X", "class_b_n_o08x.html#a3d6b6257462951ea023af7076c80f6dd", null ], - [ "mems_raw_gyro_Y", "class_b_n_o08x.html#ab6b142416912a096886dd63ad0beb865", null ], - [ "mems_raw_gyro_Z", "class_b_n_o08x.html#ac35d5b12721ab876eaeb1f714a9b3b1d", null ], - [ "mems_raw_magf_X", "class_b_n_o08x.html#ab587cdf991342b69b7fff3b33f537eb5", null ], - [ "mems_raw_magf_Y", "class_b_n_o08x.html#aad926054c81818fff611e10ed913706a", null ], - [ "mems_raw_magf_Z", "class_b_n_o08x.html#a90f0cdf11decc276006f76a494d42ce3", null ], - [ "meta_data", "class_b_n_o08x.html#a7bd032712a975e73e66bd72a3502baba", null ], - [ "quat_accuracy", "class_b_n_o08x.html#a36223f7124751fa71e860b2ef55dd2ac", null ], - [ "queue_frs_read_data", "class_b_n_o08x.html#a9a1c851e8fa5633e11f6abee293d7e9b", null ], - [ "queue_reset_reason", "class_b_n_o08x.html#a84b3639cc159262e0137adb0db5cf9aa", null ], - [ "queue_rx_data", "class_b_n_o08x.html#a7d4661d3aae56013caa8f2bff0f67c08", null ], - [ "queue_tx_data", "class_b_n_o08x.html#a4d5c5eee87a578de9c8318cd294b3a22", null ], - [ "raw_accel_X", "class_b_n_o08x.html#a75fb2f06c5bbe26e3f3c794934ef954c", null ], - [ "raw_accel_Y", "class_b_n_o08x.html#ab56e2ba505fa293d03e955137625c562", null ], - [ "raw_accel_Z", "class_b_n_o08x.html#af254d245b368027df6952b7d7522bd35", null ], - [ "raw_bias_X", "class_b_n_o08x.html#a8a2667f668317cee0a9fc4ef0accc3f5", null ], - [ "raw_bias_Y", "class_b_n_o08x.html#ac38ff5eb93d3c3db0af2504ba02fd93c", null ], - [ "raw_bias_Z", "class_b_n_o08x.html#a0968eaed9b3d979a2caa1aba6e6b417a", null ], - [ "raw_calib_gyro_X", "class_b_n_o08x.html#a87faca2c8c71ff46bf2e6ad4ba271b3a", null ], - [ "raw_calib_gyro_Y", "class_b_n_o08x.html#a66c48af1d4162a9ec25c3a1c95660fe4", null ], - [ "raw_calib_gyro_Z", "class_b_n_o08x.html#af5450d1a9c20c2a5c62c960e3df11c0e", null ], - [ "raw_lin_accel_X", "class_b_n_o08x.html#ae1f71a432cb15e75f522fa18f29f4d50", null ], - [ "raw_lin_accel_Y", "class_b_n_o08x.html#aff3a5590471d1c9fc485a5610433915f", null ], - [ "raw_lin_accel_Z", "class_b_n_o08x.html#abc8add47f1babc66c812a015614143d3", null ], - [ "raw_magf_X", "class_b_n_o08x.html#aa5bdf740161b7c37adcac0154a410118", null ], - [ "raw_magf_Y", "class_b_n_o08x.html#acd365418f24a6da61122c66d82086639", null ], - [ "raw_magf_Z", "class_b_n_o08x.html#ab4862de31d0874b44b6745678e1c905e", null ], - [ "raw_quat_I", "class_b_n_o08x.html#a69dc7e97875060213085ba964b3bd987", null ], - [ "raw_quat_J", "class_b_n_o08x.html#a61ae05dc5572b326541bf8099f0c2a54", null ], - [ "raw_quat_K", "class_b_n_o08x.html#a7720c44ed1c0f1a0663d2adc5e1a1ea1", null ], - [ "raw_quat_radian_accuracy", "class_b_n_o08x.html#a033d6cb1aa137743b69cc3e401df67b7", null ], - [ "raw_quat_real", "class_b_n_o08x.html#a867354267253ae828be4fae15c062db3", null ], - [ "raw_uncalib_gyro_X", "class_b_n_o08x.html#afdc5cdb65bd0b36528b5b671b9d27053", null ], - [ "raw_uncalib_gyro_Y", "class_b_n_o08x.html#acc2c66e2985975266a286385ea855117", null ], - [ "raw_uncalib_gyro_Z", "class_b_n_o08x.html#afac9dd4161f4c0051255293680c9082b", null ], - [ "REPORT_CNT", "class_b_n_o08x.html#a9658c821658ab51fe6831a83d8903a53", null ], - [ "report_period_trackers", "class_b_n_o08x.html#ae3750acb4578ccdd7fcf20abcd8e0904", null ], - [ "ROTATION_VECTOR_ACCURACY_Q1", "class_b_n_o08x.html#a923d65d8568cc31873ad56a3908e1939", null ], - [ "ROTATION_VECTOR_Q1", "class_b_n_o08x.html#a0b19c8f2de2b2bfe033da7f93cdd2608", null ], - [ "RX_DATA_LENGTH", "class_b_n_o08x.html#a1a037bda37493cde56732cc6fdc7884b", null ], - [ "SCLK_MAX_SPEED", "class_b_n_o08x.html#a031976dacd97917d9d72edccb607160c", null ], - [ "sem_kill_tasks", "class_b_n_o08x.html#aa92ff86d82a097a565ed2a2b9000b571", null ], - [ "SENSOR_REPORT_ID_ACCELEROMETER", "class_b_n_o08x.html#a354eaff2218eb382a1851537a75badcc", null ], - [ "SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR", "class_b_n_o08x.html#aeb51ebb6c82158cd7e23bd682c08c4e0", null ], - [ "SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR", "class_b_n_o08x.html#a8d4b91149cfc1a3cd615f60a4ad2275e", null ], - [ "SENSOR_REPORT_ID_GAME_ROTATION_VECTOR", "class_b_n_o08x.html#ada7dbda9f7a0bfb0894a787ce0ff9cef", null ], - [ "SENSOR_REPORT_ID_GEOMAGNETIC_ROTATION_VECTOR", "class_b_n_o08x.html#abb6d0586a5a87b7b34f4c65ae52965a4", null ], - [ "SENSOR_REPORT_ID_GRAVITY", "class_b_n_o08x.html#a6730acb92053d44decb690a7b7234032", null ], - [ "SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR", "class_b_n_o08x.html#acd0fc6ffa70dd2761cba0ac0b88c234f", null ], - [ "SENSOR_REPORT_ID_GYROSCOPE", "class_b_n_o08x.html#a224fb8f833806dd530c5f16e7ab5bc7a", null ], - [ "SENSOR_REPORT_ID_LINEAR_ACCELERATION", "class_b_n_o08x.html#ace7720a02c9f4ef38e319849f6c36a0b", null ], - [ "SENSOR_REPORT_ID_MAGNETIC_FIELD", "class_b_n_o08x.html#a06058a84d6604054aa66ee008ac64aa9", null ], - [ "SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER", "class_b_n_o08x.html#a7274f6d3bda04da0bb304386b4e8d603", null ], - [ "SENSOR_REPORT_ID_RAW_ACCELEROMETER", "class_b_n_o08x.html#a80ea70c4787dea6c3eabb48f583f1916", null ], - [ "SENSOR_REPORT_ID_RAW_GYROSCOPE", "class_b_n_o08x.html#a03b3000424e6d966b80655443ec546bc", null ], - [ "SENSOR_REPORT_ID_RAW_MAGNETOMETER", "class_b_n_o08x.html#a9e9a7578b7584e7eb2ad562b29565fa7", null ], - [ "SENSOR_REPORT_ID_ROTATION_VECTOR", "class_b_n_o08x.html#a37c91f995c385556486df5fbbce8a3d5", null ], - [ "SENSOR_REPORT_ID_STABILITY_CLASSIFIER", "class_b_n_o08x.html#ab5c29f31714b4755c0edbce7156652f7", null ], - [ "SENSOR_REPORT_ID_STEP_COUNTER", "class_b_n_o08x.html#a2a10161bb564067a07f3fcf4021e00bb", null ], - [ "SENSOR_REPORT_ID_TAP_DETECTOR", "class_b_n_o08x.html#a8114460c50e84b0ac750293ab72868c8", null ], - [ "SENSOR_REPORT_ID_UNCALIBRATED_GYRO", "class_b_n_o08x.html#acb8e83fbb0645d4e98a96120ce9f431c", null ], - [ "SHTP_REPORT_BASE_TIMESTAMP", "class_b_n_o08x.html#ae37d6f8431c8c465bfb0c662772b5cb9", null ], - [ "SHTP_REPORT_COMMAND_REQUEST", "class_b_n_o08x.html#ab04695dd189412092254e52bd6e5a75a", null ], - [ "SHTP_REPORT_COMMAND_RESPONSE", "class_b_n_o08x.html#a1e5b64caa514b7e4fe64ab214758b875", null ], - [ "SHTP_REPORT_FRS_READ_REQUEST", "class_b_n_o08x.html#a74af7eacc35cc825940b647c2de0d368", null ], - [ "SHTP_REPORT_FRS_READ_RESPONSE", "class_b_n_o08x.html#aeb760b095dcf808a413ef696f2608e43", null ], - [ "SHTP_REPORT_GET_FEATURE_RESPONSE", "class_b_n_o08x.html#ad09312802cf5b8b5115362c86b53858b", null ], - [ "SHTP_REPORT_PRODUCT_ID_REQUEST", "class_b_n_o08x.html#a542405639c28bd56bc4361b922763c95", null ], - [ "SHTP_REPORT_PRODUCT_ID_RESPONSE", "class_b_n_o08x.html#a0177134162e116501bc9483c6e4b76c3", null ], - [ "SHTP_REPORT_SET_FEATURE_COMMAND", "class_b_n_o08x.html#a1d3bff4e20c2c3d47db322c9e34ef338", null ], - [ "spi_hdl", "class_b_n_o08x.html#acc0ea091465fc9a5736f5e0c6a0ce8ef", null ], - [ "spi_task_hdl", "class_b_n_o08x.html#a615090aae15f1b0410a7e5ecb94957b5", null ], - [ "spi_transaction", "class_b_n_o08x.html#ac16adc5f00b0039c98a4921f13895026", null ], - [ "stability_classifier", "class_b_n_o08x.html#a1b12471e92536a79d0c425d77676f2e1", null ], - [ "step_count", "class_b_n_o08x.html#ad80a77973371b12d722ea39063c648be", null ], - [ "TAG", "class_b_n_o08x.html#a2c98d5f2c406a3efd0b48c5666fa8c46", null ], - [ "tap_detector", "class_b_n_o08x.html#a1171a5738a4e6831ec7fa32a29f15554", null ], - [ "TARE_ARVR_STABILIZED_GAME_ROTATION_VECTOR", "class_b_n_o08x.html#a68aaaab144adbe5af00597408f044d9d", null ], - [ "TARE_ARVR_STABILIZED_ROTATION_VECTOR", "class_b_n_o08x.html#abff9abe904bcdde951cf88c378284b45", null ], - [ "TARE_AXIS_ALL", "class_b_n_o08x.html#a1ef13f6f330810934416ad5fe0ee55b2", null ], - [ "TARE_AXIS_Z", "class_b_n_o08x.html#aecb3e11c1ca5769fd60f42c17a105731", null ], - [ "TARE_GAME_ROTATION_VECTOR", "class_b_n_o08x.html#abaf1ec8bb197db1998a9ed3cec6180d5", null ], - [ "TARE_GEOMAGNETIC_ROTATION_VECTOR", "class_b_n_o08x.html#a225397a04d849e5647992ca80d68febb", null ], - [ "TARE_GYRO_INTEGRATED_ROTATION_VECTOR", "class_b_n_o08x.html#a9ec354d75249f06f13599abf7bedfde0", null ], - [ "TARE_NOW", "class_b_n_o08x.html#a27df630f3e52b35552d2c1f2cf3496b0", null ], - [ "TARE_PERSIST", "class_b_n_o08x.html#a115aef7b38ec0dec2085f6917d832912", null ], - [ "TARE_ROTATION_VECTOR", "class_b_n_o08x.html#a8e2cfc25d0e34ae53a762b88cc3ac3c8", null ], - [ "TARE_SET_REORIENTATION", "class_b_n_o08x.html#a59cde7dd301c94a20b84735c5d49008e", null ], - [ "TASK_CNT", "class_b_n_o08x.html#a5448bffec9a90f5c388b3c22928463ae", null ], - [ "time_stamp", "class_b_n_o08x.html#abc972db20affbd0040b4e6c4892dd57b", null ] -]; \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x__coll__graph.map b/documentation/html/class_b_n_o08x__coll__graph.map deleted file mode 100644 index c0bb2c6..0000000 --- a/documentation/html/class_b_n_o08x__coll__graph.map +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x__coll__graph.md5 b/documentation/html/class_b_n_o08x__coll__graph.md5 deleted file mode 100644 index 5ba20a8..0000000 --- a/documentation/html/class_b_n_o08x__coll__graph.md5 +++ /dev/null @@ -1 +0,0 @@ -bbd564f640bb932b3c4fc107683a6148 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x__coll__graph.png b/documentation/html/class_b_n_o08x__coll__graph.png deleted file mode 100644 index 1913cbd..0000000 Binary files a/documentation/html/class_b_n_o08x__coll__graph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.map b/documentation/html/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.map deleted file mode 100644 index d97570f..0000000 --- a/documentation/html/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.md5 b/documentation/html/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.md5 deleted file mode 100644 index 75bef54..0000000 --- a/documentation/html/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1b8c3de575d3533ebd1e5f64d6762a5b \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.png b/documentation/html/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.png deleted file mode 100644 index a4ff009..0000000 Binary files a/documentation/html/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.map b/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.map deleted file mode 100644 index 4a8e876..0000000 --- a/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.map +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.md5 b/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.md5 deleted file mode 100644 index a3b5668..0000000 --- a/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fc87fe3abc5dac8854446e4333701785 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.png b/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.png deleted file mode 100644 index 8d649be..0000000 Binary files a/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.map b/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.map deleted file mode 100644 index b1d8a2c..0000000 --- a/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.map +++ /dev/null @@ -1,90 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.md5 b/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.md5 deleted file mode 100644 index 9195e35..0000000 --- a/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -44e8d55a10e06b341827c597ad722509 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.png b/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.png deleted file mode 100644 index fe81263..0000000 Binary files a/documentation/html/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.map b/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.map deleted file mode 100644 index b8fce6a..0000000 --- a/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.md5 b/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.md5 deleted file mode 100644 index 49e0f85..0000000 --- a/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fc179de9458a6ec23078e9c59d6b8d55 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.png b/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.png deleted file mode 100644 index 1fd8e71..0000000 Binary files a/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.map b/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.map deleted file mode 100644 index 4bc5ac8..0000000 --- a/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.md5 b/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.md5 deleted file mode 100644 index eb48ca2..0000000 --- a/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f6c24488dde6512ddb287f0dc4bc6827 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.png b/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.png deleted file mode 100644 index 4a89d3a..0000000 Binary files a/documentation/html/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.map b/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.map deleted file mode 100644 index 765232a..0000000 --- a/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.md5 b/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.md5 deleted file mode 100644 index bae50c9..0000000 --- a/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4aab188ff53c6452dc33e9fbf4a43e4c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.png b/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.png deleted file mode 100644 index ea4300f..0000000 Binary files a/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.map b/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.map deleted file mode 100644 index 30e99cc..0000000 --- a/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.md5 b/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.md5 deleted file mode 100644 index e4c3e02..0000000 --- a/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -72ee4ab59f469a5c315dc591209e749b \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.png b/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.png deleted file mode 100644 index 3332899..0000000 Binary files a/documentation/html/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.map b/documentation/html/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.map deleted file mode 100644 index 9a68745..0000000 --- a/documentation/html/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.md5 b/documentation/html/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.md5 deleted file mode 100644 index f5d2276..0000000 --- a/documentation/html/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -86cb41e30e39251e121ef7d9f8511ad4 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.png b/documentation/html/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.png deleted file mode 100644 index 427e73d..0000000 Binary files a/documentation/html/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.map b/documentation/html/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.map deleted file mode 100644 index d433ef7..0000000 --- a/documentation/html/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.map +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.md5 b/documentation/html/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.md5 deleted file mode 100644 index 4408f54..0000000 --- a/documentation/html/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -21970e502d95a672972e9690a937d30c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.png b/documentation/html/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.png deleted file mode 100644 index 158a3f4..0000000 Binary files a/documentation/html/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.map b/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.map deleted file mode 100644 index 6795ab7..0000000 --- a/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.md5 b/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.md5 deleted file mode 100644 index 2b1d449..0000000 --- a/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -975a698ed67f99e6272e45af25535935 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.png b/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.png deleted file mode 100644 index 8954fe5..0000000 Binary files a/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.map b/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.map deleted file mode 100644 index 9809423..0000000 --- a/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.md5 b/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.md5 deleted file mode 100644 index 9a292d4..0000000 --- a/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0255ed5dc1987318e48d5538cd2edaad \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.png b/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.png deleted file mode 100644 index 5ea778f..0000000 Binary files a/documentation/html/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.map b/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.map deleted file mode 100644 index 613c73b..0000000 --- a/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.map +++ /dev/null @@ -1,69 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.md5 b/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.md5 deleted file mode 100644 index 50ff169..0000000 --- a/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -23d0f950ee04784e2133866b6a2a2204 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.png b/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.png deleted file mode 100644 index 1d297ac..0000000 Binary files a/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.map b/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.map deleted file mode 100644 index a572c8f..0000000 --- a/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.md5 b/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.md5 deleted file mode 100644 index 3dc950f..0000000 --- a/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2ec1812b56b9f6c88f5c243515123b87 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.png b/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.png deleted file mode 100644 index 5434208..0000000 Binary files a/documentation/html/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.map b/documentation/html/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.map deleted file mode 100644 index 084bbe2..0000000 --- a/documentation/html/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.md5 b/documentation/html/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.md5 deleted file mode 100644 index 148cf4a..0000000 --- a/documentation/html/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b72a3e9022ba17db5220ddbaccada7b5 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.png b/documentation/html/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.png deleted file mode 100644 index 9f83b85..0000000 Binary files a/documentation/html/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.map b/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.map deleted file mode 100644 index 56201b2..0000000 --- a/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.map +++ /dev/null @@ -1,55 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.md5 b/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.md5 deleted file mode 100644 index 8d2d05d..0000000 --- a/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -23b4195c3fd79164956dab485622ff4a \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.png b/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.png deleted file mode 100644 index 947fdb1..0000000 Binary files a/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.map b/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.map deleted file mode 100644 index f822275..0000000 --- a/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.map +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.md5 b/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.md5 deleted file mode 100644 index 15def7b..0000000 --- a/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -bacf7f699f10be04c8fb4afc1ec47249 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.png b/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.png deleted file mode 100644 index 784ed4e..0000000 Binary files a/documentation/html/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.map b/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.map deleted file mode 100644 index 902d2eb..0000000 --- a/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.map +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.md5 b/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.md5 deleted file mode 100644 index 74de65b..0000000 --- a/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2a9cd674be16e979f440922fd0b1a34d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.png b/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.png deleted file mode 100644 index c5b942e..0000000 Binary files a/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.map b/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.map deleted file mode 100644 index a39fa16..0000000 --- a/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.map +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.md5 b/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.md5 deleted file mode 100644 index eea47da..0000000 --- a/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a618c035e701956960622cfb3c920c0e \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.png b/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.png deleted file mode 100644 index 44ae11d..0000000 Binary files a/documentation/html/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.map b/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.map deleted file mode 100644 index e03cccb..0000000 --- a/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.md5 b/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.md5 deleted file mode 100644 index 1f506f2..0000000 --- a/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2b303a6e79f1ea9bdcff421c967440cb \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.png b/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.png deleted file mode 100644 index f8de69d..0000000 Binary files a/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.map b/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.map deleted file mode 100644 index 7d32b59..0000000 --- a/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.map +++ /dev/null @@ -1,138 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.md5 b/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.md5 deleted file mode 100644 index 3def9c2..0000000 --- a/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -67c65883386e8bcf0dcac5e019176bfb \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.png b/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.png deleted file mode 100644 index 0cd8e41..0000000 Binary files a/documentation/html/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.map b/documentation/html/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.map deleted file mode 100644 index 23ff9b6..0000000 --- a/documentation/html/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.map +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.md5 b/documentation/html/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.md5 deleted file mode 100644 index f13807c..0000000 --- a/documentation/html/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fcbdca423bbc761e14a60e470eb67e0c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.png b/documentation/html/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.png deleted file mode 100644 index e255662..0000000 Binary files a/documentation/html/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.map b/documentation/html/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.map deleted file mode 100644 index f28deb2..0000000 --- a/documentation/html/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.md5 b/documentation/html/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.md5 deleted file mode 100644 index c09918d..0000000 --- a/documentation/html/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d23f2fb44a87ec4a072a34107de2c5d1 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.png b/documentation/html/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.png deleted file mode 100644 index 4b4838e..0000000 Binary files a/documentation/html/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.map b/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.map deleted file mode 100644 index cf5cfab..0000000 --- a/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.md5 b/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.md5 deleted file mode 100644 index 47aee99..0000000 --- a/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2dd13993c84823c558d9969e53c7cf61 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.png b/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.png deleted file mode 100644 index 8b7d9d5..0000000 Binary files a/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.map b/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.map deleted file mode 100644 index d5e24a1..0000000 --- a/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.md5 b/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.md5 deleted file mode 100644 index dcd5f3b..0000000 --- a/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -46c4f89962868349feee15af961a98e4 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.png b/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.png deleted file mode 100644 index bbd320a..0000000 Binary files a/documentation/html/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.map b/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.map deleted file mode 100644 index 48f3639..0000000 --- a/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.md5 b/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.md5 deleted file mode 100644 index 2c4f89e..0000000 --- a/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2494eaecc63182504fb08d6551c92b28 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.png b/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.png deleted file mode 100644 index 1b32196..0000000 Binary files a/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.map b/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.map deleted file mode 100644 index abf47a8..0000000 --- a/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.md5 b/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.md5 deleted file mode 100644 index 16fc944..0000000 --- a/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -acfc7aa3e0ba2e4f69328534d128f355 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.png b/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.png deleted file mode 100644 index 6e47812..0000000 Binary files a/documentation/html/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.map b/documentation/html/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.map deleted file mode 100644 index 9de8489..0000000 --- a/documentation/html/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.md5 b/documentation/html/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.md5 deleted file mode 100644 index 5a4cab7..0000000 --- a/documentation/html/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b13d9d365b94d7a07591b0d3949f80c0 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.png b/documentation/html/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.png deleted file mode 100644 index 452f4d3..0000000 Binary files a/documentation/html/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.map b/documentation/html/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.map deleted file mode 100644 index 750e886..0000000 --- a/documentation/html/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.md5 b/documentation/html/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.md5 deleted file mode 100644 index 5abf395..0000000 --- a/documentation/html/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -cb305694d3eec76fbfb6321360598c45 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.png b/documentation/html/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.png deleted file mode 100644 index 68b6d13..0000000 Binary files a/documentation/html/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.map b/documentation/html/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.map deleted file mode 100644 index 68cbf39..0000000 --- a/documentation/html/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.md5 b/documentation/html/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.md5 deleted file mode 100644 index dd80713..0000000 --- a/documentation/html/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e467656af992cbfeab65ae0210779374 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.png b/documentation/html/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.png deleted file mode 100644 index 58415ba..0000000 Binary files a/documentation/html/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.map b/documentation/html/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.map deleted file mode 100644 index 48f32e2..0000000 --- a/documentation/html/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.md5 b/documentation/html/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.md5 deleted file mode 100644 index efd9312..0000000 --- a/documentation/html/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -343863b4de4e7d4f1e949b61ec05a23d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.png b/documentation/html/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.png deleted file mode 100644 index 3179ce0..0000000 Binary files a/documentation/html/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.map b/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.map deleted file mode 100644 index b1d476a..0000000 --- a/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.map +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.md5 b/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.md5 deleted file mode 100644 index cbea16f..0000000 --- a/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -16d0605eca62e516809118f163adc01c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.png b/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.png deleted file mode 100644 index 701639c..0000000 Binary files a/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.map b/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.map deleted file mode 100644 index 73447d4..0000000 --- a/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.md5 b/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.md5 deleted file mode 100644 index e1c8c29..0000000 --- a/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -327e666ab82655d7ab3119a69b9a334d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.png b/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.png deleted file mode 100644 index 879bacd..0000000 Binary files a/documentation/html/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.map b/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.map deleted file mode 100644 index fa572c1..0000000 --- a/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.map +++ /dev/null @@ -1,49 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.md5 b/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.md5 deleted file mode 100644 index 4d2d719..0000000 --- a/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -26e73417398d8eacde8c501a4ecafc68 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.png b/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.png deleted file mode 100644 index 2165eb3..0000000 Binary files a/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.map b/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.map deleted file mode 100644 index 6861bb8..0000000 --- a/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.map +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.md5 b/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.md5 deleted file mode 100644 index 1bf3bc5..0000000 --- a/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3d47d1c7eb373a5acce77a82c572aa86 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.png b/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.png deleted file mode 100644 index 05d49f4..0000000 Binary files a/documentation/html/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.map b/documentation/html/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.map deleted file mode 100644 index 7089d08..0000000 --- a/documentation/html/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.md5 b/documentation/html/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.md5 deleted file mode 100644 index 3c06809..0000000 --- a/documentation/html/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -dc2080364108de3d8a03959c28dd1edf \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.png b/documentation/html/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.png deleted file mode 100644 index 1552e19..0000000 Binary files a/documentation/html/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.map b/documentation/html/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.map deleted file mode 100644 index 32f9b5c..0000000 --- a/documentation/html/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.map +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.md5 b/documentation/html/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.md5 deleted file mode 100644 index 1c5c0b6..0000000 --- a/documentation/html/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -18ec892c9922db3ef88f45ca9323a786 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.png b/documentation/html/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.png deleted file mode 100644 index 6a69008..0000000 Binary files a/documentation/html/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.map b/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.map deleted file mode 100644 index 2540b54..0000000 --- a/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.md5 b/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.md5 deleted file mode 100644 index 3605bbc..0000000 --- a/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9c0bdcc9fb5c37841aeb90eb42328b07 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.png b/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.png deleted file mode 100644 index b3b97c4..0000000 Binary files a/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.map b/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.map deleted file mode 100644 index f246f9a..0000000 --- a/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.map +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.md5 b/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.md5 deleted file mode 100644 index 069f1af..0000000 --- a/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4c4cbe74e42cd51ac452de39e1325d6e \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.png b/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.png deleted file mode 100644 index c91850b..0000000 Binary files a/documentation/html/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.map b/documentation/html/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.map deleted file mode 100644 index f12e616..0000000 --- a/documentation/html/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.md5 b/documentation/html/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.md5 deleted file mode 100644 index 803d6b7..0000000 --- a/documentation/html/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9ba55232620670811e573686865dbd47 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.png b/documentation/html/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.png deleted file mode 100644 index 4577609..0000000 Binary files a/documentation/html/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.map b/documentation/html/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.map deleted file mode 100644 index fdb4ea0..0000000 --- a/documentation/html/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.map +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.md5 b/documentation/html/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.md5 deleted file mode 100644 index 2c54877..0000000 --- a/documentation/html/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1f86c5d1ebc21c859dd92f8d39c46065 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.png b/documentation/html/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.png deleted file mode 100644 index d0ffc57..0000000 Binary files a/documentation/html/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.map b/documentation/html/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.map deleted file mode 100644 index 3c0d145..0000000 --- a/documentation/html/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.md5 b/documentation/html/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.md5 deleted file mode 100644 index 3257469..0000000 --- a/documentation/html/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -17aea54ff2350028fcdabe40ca8efb9d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.png b/documentation/html/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.png deleted file mode 100644 index e25c35a..0000000 Binary files a/documentation/html/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.map b/documentation/html/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.map deleted file mode 100644 index ed69c82..0000000 --- a/documentation/html/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.md5 b/documentation/html/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.md5 deleted file mode 100644 index 811579f..0000000 --- a/documentation/html/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -295aea5926b2167e314fef66facf36c6 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.png b/documentation/html/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.png deleted file mode 100644 index 5e91f1a..0000000 Binary files a/documentation/html/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.map b/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.map deleted file mode 100644 index 12d92df..0000000 --- a/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.md5 b/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.md5 deleted file mode 100644 index cc36234..0000000 --- a/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f2fe4d73bf04be5e4e87a3c24147d3f2 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.png b/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.png deleted file mode 100644 index 671053a..0000000 Binary files a/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.map b/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.map deleted file mode 100644 index 2fc30e5..0000000 --- a/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.map +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.md5 b/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.md5 deleted file mode 100644 index 0323a9e..0000000 --- a/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -68f3485a6893a25e1762e589ab786531 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.png b/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.png deleted file mode 100644 index e50024c..0000000 Binary files a/documentation/html/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.map b/documentation/html/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.map deleted file mode 100644 index 6ecfb66..0000000 --- a/documentation/html/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.map +++ /dev/null @@ -1,137 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.md5 b/documentation/html/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.md5 deleted file mode 100644 index 319f6a9..0000000 --- a/documentation/html/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5dd48a1a85ffb141d7e1a1f01436318e \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.png b/documentation/html/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.png deleted file mode 100644 index 503f277..0000000 Binary files a/documentation/html/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.map b/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.map deleted file mode 100644 index 6bb4966..0000000 --- a/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.map +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.md5 b/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.md5 deleted file mode 100644 index 6af5332..0000000 --- a/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -54ff33f673ab38cd9a69ec232fcda7e2 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.png b/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.png deleted file mode 100644 index 234e96a..0000000 Binary files a/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.map b/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.map deleted file mode 100644 index 07bd512..0000000 --- a/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.md5 b/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.md5 deleted file mode 100644 index b552aed..0000000 --- a/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -09dead7225c4b69109f5fbb7edb3c654 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.png b/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.png deleted file mode 100644 index 3883773..0000000 Binary files a/documentation/html/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.map b/documentation/html/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.map deleted file mode 100644 index 0f4b820..0000000 --- a/documentation/html/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.map +++ /dev/null @@ -1,123 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.md5 b/documentation/html/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.md5 deleted file mode 100644 index 92f25e0..0000000 --- a/documentation/html/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -adcba0d4887a181165bddef7152efcc0 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.png b/documentation/html/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.png deleted file mode 100644 index a1ba72b..0000000 Binary files a/documentation/html/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.map b/documentation/html/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.map deleted file mode 100644 index 881a4ae..0000000 --- a/documentation/html/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.map +++ /dev/null @@ -1,118 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.md5 b/documentation/html/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.md5 deleted file mode 100644 index e02bff5..0000000 --- a/documentation/html/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -86b12bca8504ee298a7fdde86d1d12be \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.png b/documentation/html/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.png deleted file mode 100644 index f5e1239..0000000 Binary files a/documentation/html/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.map b/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.map deleted file mode 100644 index 9fc1620..0000000 --- a/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.md5 b/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.md5 deleted file mode 100644 index 02fb89a..0000000 --- a/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8d76396ccd7543018bc2eb0907c86dbf \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.png b/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.png deleted file mode 100644 index ec1f940..0000000 Binary files a/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.map b/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.map deleted file mode 100644 index 0a32143..0000000 --- a/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.map +++ /dev/null @@ -1,107 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.md5 b/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.md5 deleted file mode 100644 index 0cbf5e2..0000000 --- a/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -db646bf80d96b0a8d76570dbdd081e8a \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.png b/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.png deleted file mode 100644 index b38f0c8..0000000 Binary files a/documentation/html/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.map b/documentation/html/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.map deleted file mode 100644 index 7dfa9b2..0000000 --- a/documentation/html/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.map +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.md5 b/documentation/html/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.md5 deleted file mode 100644 index 4ac6f92..0000000 --- a/documentation/html/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9ee433661b50829f209d30762f552182 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.png b/documentation/html/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.png deleted file mode 100644 index 7caf6c8..0000000 Binary files a/documentation/html/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.map b/documentation/html/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.map deleted file mode 100644 index 827c3c3..0000000 --- a/documentation/html/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.map +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.md5 b/documentation/html/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.md5 deleted file mode 100644 index 4c40744..0000000 --- a/documentation/html/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a392817f3e52580e43afbd55e313d049 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.png b/documentation/html/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.png deleted file mode 100644 index 897f378..0000000 Binary files a/documentation/html/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.map b/documentation/html/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.map deleted file mode 100644 index e903f6b..0000000 --- a/documentation/html/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.md5 b/documentation/html/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.md5 deleted file mode 100644 index 369853a..0000000 --- a/documentation/html/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9edd3150c2653715602382de9db648d1 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.png b/documentation/html/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.png deleted file mode 100644 index f88344a..0000000 Binary files a/documentation/html/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.map b/documentation/html/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.map deleted file mode 100644 index 77961c4..0000000 --- a/documentation/html/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.md5 b/documentation/html/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.md5 deleted file mode 100644 index 0a5ff71..0000000 --- a/documentation/html/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5c79973012d8aa4e72df3b8d40ddaadc \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.png b/documentation/html/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.png deleted file mode 100644 index baab31c..0000000 Binary files a/documentation/html/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.map b/documentation/html/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.map deleted file mode 100644 index 24adff6..0000000 --- a/documentation/html/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.md5 b/documentation/html/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.md5 deleted file mode 100644 index 32b19f5..0000000 --- a/documentation/html/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -62e271d15a021f03d26cd32cedc0bcf9 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.png b/documentation/html/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.png deleted file mode 100644 index 5dfceae..0000000 Binary files a/documentation/html/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.map b/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.map deleted file mode 100644 index eb014ae..0000000 --- a/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.md5 b/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.md5 deleted file mode 100644 index 8969d96..0000000 --- a/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -80bd67f551f6f3931a667c4890fb3551 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.png b/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.png deleted file mode 100644 index 58afdd0..0000000 Binary files a/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.map b/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.map deleted file mode 100644 index 84125cc..0000000 --- a/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.map +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.md5 b/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.md5 deleted file mode 100644 index 942a00b..0000000 --- a/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -28fe0181bdff21d95c99c7cf507e8efb \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.png b/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.png deleted file mode 100644 index edda0ef..0000000 Binary files a/documentation/html/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.map b/documentation/html/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.map deleted file mode 100644 index a7ea0d3..0000000 --- a/documentation/html/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.md5 b/documentation/html/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.md5 deleted file mode 100644 index f24a1a6..0000000 --- a/documentation/html/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1c0095a9410503af7fb2a6facbf8d5dd \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.png b/documentation/html/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.png deleted file mode 100644 index 2f4c12d..0000000 Binary files a/documentation/html/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.map b/documentation/html/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.map deleted file mode 100644 index 9fda871..0000000 --- a/documentation/html/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.md5 b/documentation/html/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.md5 deleted file mode 100644 index 57250dc..0000000 --- a/documentation/html/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9de40b640a5023811ca8978baab256c3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.png b/documentation/html/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.png deleted file mode 100644 index 90a9e11..0000000 Binary files a/documentation/html/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.map b/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.map deleted file mode 100644 index 14a06a6..0000000 --- a/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.md5 b/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.md5 deleted file mode 100644 index 6120f9b..0000000 --- a/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -641d44e1f71c95c5f5a8a7b3840bd094 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.png b/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.png deleted file mode 100644 index 08d952a..0000000 Binary files a/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.map b/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.map deleted file mode 100644 index a0c63dd..0000000 --- a/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.map +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.md5 b/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.md5 deleted file mode 100644 index 57e2e61..0000000 --- a/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -078f8f94ebf6f3ac2fca219a9b1c15e0 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.png b/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.png deleted file mode 100644 index f8d1d10..0000000 Binary files a/documentation/html/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.map b/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.map deleted file mode 100644 index f7b2de2..0000000 --- a/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.md5 b/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.md5 deleted file mode 100644 index f798149..0000000 --- a/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1f6043d3d78b7a18d1edb4855bf36a67 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.png b/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.png deleted file mode 100644 index 1733a6a..0000000 Binary files a/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.map b/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.map deleted file mode 100644 index 0aa8c0f..0000000 --- a/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.md5 b/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.md5 deleted file mode 100644 index 38fec86..0000000 --- a/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fd77f423e46f53c8734c1b54e597677e \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.png b/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.png deleted file mode 100644 index 6c76584..0000000 Binary files a/documentation/html/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.map b/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.map deleted file mode 100644 index 0b491a7..0000000 --- a/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.md5 b/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.md5 deleted file mode 100644 index 8a804ce..0000000 --- a/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -481ee56661cd2f506e989de0dd31d2c1 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.png b/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.png deleted file mode 100644 index 3fed71a..0000000 Binary files a/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.map b/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.map deleted file mode 100644 index c97912b..0000000 --- a/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.md5 b/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.md5 deleted file mode 100644 index 1499c0e..0000000 --- a/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -02da538b6207fc9f520f1d6139705f03 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.png b/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.png deleted file mode 100644 index 984845b..0000000 Binary files a/documentation/html/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.map b/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.map deleted file mode 100644 index 4fff8e2..0000000 --- a/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.md5 b/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.md5 deleted file mode 100644 index 7d1fe28..0000000 --- a/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5ac936272fd58f3dadfcf11b00eaef2a \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.png b/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.png deleted file mode 100644 index 6a47b0c..0000000 Binary files a/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.map b/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.map deleted file mode 100644 index 16685d4..0000000 --- a/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.md5 b/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.md5 deleted file mode 100644 index e6e0757..0000000 --- a/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5eed703161e37f59fd4783272a498bfb \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.png b/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.png deleted file mode 100644 index 9f3d95c..0000000 Binary files a/documentation/html/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.map b/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.map deleted file mode 100644 index a6b92a2..0000000 --- a/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.md5 b/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.md5 deleted file mode 100644 index 6cf7787..0000000 --- a/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7b6051b32e47412f9ed3588b86a18eef \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.png b/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.png deleted file mode 100644 index 4b8ca8c..0000000 Binary files a/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.map b/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.map deleted file mode 100644 index f8d600c..0000000 --- a/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.md5 b/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.md5 deleted file mode 100644 index 0c44621..0000000 --- a/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -77a02252e21ca5a93b76420d2db0a6b3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.png b/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.png deleted file mode 100644 index a771cbb..0000000 Binary files a/documentation/html/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.map b/documentation/html/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.map deleted file mode 100644 index c539f2c..0000000 --- a/documentation/html/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.map +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.md5 b/documentation/html/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.md5 deleted file mode 100644 index f6156a4..0000000 --- a/documentation/html/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -10fe190888075b8ac69f58529de9477b \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.png b/documentation/html/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.png deleted file mode 100644 index 645df75..0000000 Binary files a/documentation/html/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.map b/documentation/html/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.map deleted file mode 100644 index 7c814d8..0000000 --- a/documentation/html/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.md5 b/documentation/html/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.md5 deleted file mode 100644 index a46c6de..0000000 --- a/documentation/html/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -730753abb507929bbd092c2fc71ffa9d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.png b/documentation/html/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.png deleted file mode 100644 index 8676ecd..0000000 Binary files a/documentation/html/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.map b/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.map deleted file mode 100644 index 402d041..0000000 --- a/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.md5 b/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.md5 deleted file mode 100644 index 7052547..0000000 --- a/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ee2c649c7146b8e008a9fd27a6535b62 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.png b/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.png deleted file mode 100644 index 84ef350..0000000 Binary files a/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.map b/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.map deleted file mode 100644 index fee5978..0000000 --- a/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.map +++ /dev/null @@ -1,101 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.md5 b/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.md5 deleted file mode 100644 index 890e42e..0000000 --- a/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1980bb44d8700e3cad304eb7cd5dfb8e \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.png b/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.png deleted file mode 100644 index b447073..0000000 Binary files a/documentation/html/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.map b/documentation/html/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.map deleted file mode 100644 index 4ac6e83..0000000 --- a/documentation/html/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.md5 b/documentation/html/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.md5 deleted file mode 100644 index 601eea6..0000000 --- a/documentation/html/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -54bd3771ca49f75c36fd0c0baf11462f \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.png b/documentation/html/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.png deleted file mode 100644 index 510409a..0000000 Binary files a/documentation/html/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.map b/documentation/html/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.map deleted file mode 100644 index 8f8f480..0000000 --- a/documentation/html/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.md5 b/documentation/html/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.md5 deleted file mode 100644 index dea03ac..0000000 --- a/documentation/html/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7ebe11ea69cc1cdc361338fe0da19c2a \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.png b/documentation/html/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.png deleted file mode 100644 index 07ba586..0000000 Binary files a/documentation/html/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.map b/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.map deleted file mode 100644 index 22e5f6d..0000000 --- a/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.md5 b/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.md5 deleted file mode 100644 index ab68a11..0000000 --- a/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3cdda5127d51fa15f6523fb9f9a73fac \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.png b/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.png deleted file mode 100644 index 38fa5cf..0000000 Binary files a/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.map b/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.map deleted file mode 100644 index 3822a16..0000000 --- a/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.md5 b/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.md5 deleted file mode 100644 index 9ef7e75..0000000 --- a/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9c6e1fdef7b800f607145fe79015c0a0 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.png b/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.png deleted file mode 100644 index 909cbcf..0000000 Binary files a/documentation/html/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.map b/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.map deleted file mode 100644 index 5169119..0000000 --- a/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.md5 b/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.md5 deleted file mode 100644 index cfc7ad5..0000000 --- a/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0559e325d943e64611be45c34d84828d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.png b/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.png deleted file mode 100644 index e1c5cb3..0000000 Binary files a/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.map b/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.map deleted file mode 100644 index 44cf5dc..0000000 --- a/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.map +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.md5 b/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.md5 deleted file mode 100644 index e6568c8..0000000 --- a/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a640fd7d46c7fcc6dfabf89caf35f2c7 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.png b/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.png deleted file mode 100644 index 5851fca..0000000 Binary files a/documentation/html/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.map b/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.map deleted file mode 100644 index f3e7359..0000000 --- a/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.md5 b/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.md5 deleted file mode 100644 index 541e34f..0000000 --- a/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -02cd2c01b23e37d062ad552c84531e2a \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.png b/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.png deleted file mode 100644 index 078112c..0000000 Binary files a/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.map b/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.map deleted file mode 100644 index ff7a978..0000000 --- a/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.md5 b/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.md5 deleted file mode 100644 index 048bd86..0000000 --- a/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -87f600ae44c770a15959a0569df15935 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.png b/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.png deleted file mode 100644 index 2b53580..0000000 Binary files a/documentation/html/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.map b/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.map deleted file mode 100644 index ad44024..0000000 --- a/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.md5 b/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.md5 deleted file mode 100644 index e8ae398..0000000 --- a/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fbcc2a31557ceb988b3edc2cd1d778c1 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.png b/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.png deleted file mode 100644 index ad7f0da..0000000 Binary files a/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.map b/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.map deleted file mode 100644 index 6cef949..0000000 --- a/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.md5 b/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.md5 deleted file mode 100644 index 641208c..0000000 --- a/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -43634f664fbc36d4f6718a50ae74b57b \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.png b/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.png deleted file mode 100644 index d54c686..0000000 Binary files a/documentation/html/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.map b/documentation/html/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.map deleted file mode 100644 index c179424..0000000 --- a/documentation/html/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.map +++ /dev/null @@ -1,63 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.md5 b/documentation/html/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.md5 deleted file mode 100644 index f5ae373..0000000 --- a/documentation/html/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6d1847d1c843a75aa714dbeb60d104ec \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.png b/documentation/html/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.png deleted file mode 100644 index 4366e4a..0000000 Binary files a/documentation/html/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.map b/documentation/html/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.map deleted file mode 100644 index 66736dd..0000000 --- a/documentation/html/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.map +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.md5 b/documentation/html/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.md5 deleted file mode 100644 index 7fcf103..0000000 --- a/documentation/html/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -bf6a270c74deca423418469a017a5435 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.png b/documentation/html/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.png deleted file mode 100644 index 7696eae..0000000 Binary files a/documentation/html/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.map b/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.map deleted file mode 100644 index 460f7b2..0000000 --- a/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.md5 b/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.md5 deleted file mode 100644 index 1f74d95..0000000 --- a/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -619bedd9e9c1fb635255b95f2676addc \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.png b/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.png deleted file mode 100644 index 85adcc8..0000000 Binary files a/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.map b/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.map deleted file mode 100644 index bb98fce..0000000 --- a/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.md5 b/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.md5 deleted file mode 100644 index 28c4324..0000000 --- a/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -396d0578d3beaaded4a7805d262706d7 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.png b/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.png deleted file mode 100644 index 48f4913..0000000 Binary files a/documentation/html/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.map b/documentation/html/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.map deleted file mode 100644 index 9e60a89..0000000 --- a/documentation/html/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.md5 b/documentation/html/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.md5 deleted file mode 100644 index 54fcc95..0000000 --- a/documentation/html/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -55558466cd936b43adc2cc4113a470f3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.png b/documentation/html/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.png deleted file mode 100644 index b3e6a5f..0000000 Binary files a/documentation/html/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.map b/documentation/html/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.map deleted file mode 100644 index 5ed60c3..0000000 --- a/documentation/html/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.map +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.md5 b/documentation/html/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.md5 deleted file mode 100644 index b279bdb..0000000 --- a/documentation/html/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1877c9fc5ec18c9ab3b29ebfd070aec9 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.png b/documentation/html/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.png deleted file mode 100644 index 3436ab9..0000000 Binary files a/documentation/html/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.map b/documentation/html/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.map deleted file mode 100644 index 883face..0000000 --- a/documentation/html/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.md5 b/documentation/html/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.md5 deleted file mode 100644 index 870e425..0000000 --- a/documentation/html/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b4d0c4ef2d2e92ac9dfec924a431ce30 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.png b/documentation/html/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.png deleted file mode 100644 index 0f0d199..0000000 Binary files a/documentation/html/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.map b/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.map deleted file mode 100644 index aea4788..0000000 --- a/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.md5 b/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.md5 deleted file mode 100644 index c54af10..0000000 --- a/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -63b78db6bb46a7027e090b00ed3b3384 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.png b/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.png deleted file mode 100644 index e46ea00..0000000 Binary files a/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.map b/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.map deleted file mode 100644 index 9b049ab..0000000 --- a/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.md5 b/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.md5 deleted file mode 100644 index f86d037..0000000 --- a/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f6351ed1ee1db960af8eca6fb1230c42 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.png b/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.png deleted file mode 100644 index 3f8cb16..0000000 Binary files a/documentation/html/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.map b/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.map deleted file mode 100644 index 040d864..0000000 --- a/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.md5 b/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.md5 deleted file mode 100644 index 994c046..0000000 --- a/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e42bcd8a6232dcd844500a254811f960 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.png b/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.png deleted file mode 100644 index d886c41..0000000 Binary files a/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.map b/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.map deleted file mode 100644 index d0e0ee5..0000000 --- a/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.md5 b/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.md5 deleted file mode 100644 index 4cefd8c..0000000 --- a/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -cfae9012b399fc24430db9b5b3bca73e \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.png b/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.png deleted file mode 100644 index 78dfea6..0000000 Binary files a/documentation/html/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.map b/documentation/html/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.map deleted file mode 100644 index c368fd6..0000000 --- a/documentation/html/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.md5 b/documentation/html/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.md5 deleted file mode 100644 index ce0944f..0000000 --- a/documentation/html/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6e07aff0aba7901b9b7ea6740dbcea80 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.png b/documentation/html/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.png deleted file mode 100644 index e7666f1..0000000 Binary files a/documentation/html/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.map b/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.map deleted file mode 100644 index dafd73f..0000000 --- a/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.md5 b/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.md5 deleted file mode 100644 index 8835e72..0000000 --- a/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -81f7f735d861a0525f6c0227480620f3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.png b/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.png deleted file mode 100644 index 40fa8ff..0000000 Binary files a/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.map b/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.map deleted file mode 100644 index 45d14f8..0000000 --- a/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.md5 b/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.md5 deleted file mode 100644 index 4e84174..0000000 --- a/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fc67a1991b503144f633bb541f503d34 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.png b/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.png deleted file mode 100644 index e0d0a74..0000000 Binary files a/documentation/html/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.map b/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.map deleted file mode 100644 index bd67fde..0000000 --- a/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.md5 b/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.md5 deleted file mode 100644 index bf931dd..0000000 --- a/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3d6a65f996df84f0187f4a4018c575c3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.png b/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.png deleted file mode 100644 index 63b60a8..0000000 Binary files a/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.map b/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.map deleted file mode 100644 index 87cfdaa..0000000 --- a/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.md5 b/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.md5 deleted file mode 100644 index 6f0e0e0..0000000 --- a/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a86dad16baa67ede78dde3858fc4ff7c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.png b/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.png deleted file mode 100644 index 1bdafa6..0000000 Binary files a/documentation/html/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.map b/documentation/html/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.map deleted file mode 100644 index 325465b..0000000 --- a/documentation/html/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.md5 b/documentation/html/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.md5 deleted file mode 100644 index 1206280..0000000 --- a/documentation/html/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -655f1ff47058039a0f736a42378f6394 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.png b/documentation/html/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.png deleted file mode 100644 index d0fbbff..0000000 Binary files a/documentation/html/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.map b/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.map deleted file mode 100644 index 6868bc7..0000000 --- a/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.md5 b/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.md5 deleted file mode 100644 index ebb7df4..0000000 --- a/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -358de056dd4e0e138c0978eb6eabe341 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.png b/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.png deleted file mode 100644 index 0aa5acc..0000000 Binary files a/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.map b/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.map deleted file mode 100644 index 2237c76..0000000 --- a/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.map +++ /dev/null @@ -1,33 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.md5 b/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.md5 deleted file mode 100644 index 50241bd..0000000 --- a/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e42b9f93e1731be2cca8842c0fbaa408 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.png b/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.png deleted file mode 100644 index 69d2d02..0000000 Binary files a/documentation/html/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.map b/documentation/html/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.map deleted file mode 100644 index 6bb49f2..0000000 --- a/documentation/html/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.md5 b/documentation/html/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.md5 deleted file mode 100644 index f78021d..0000000 --- a/documentation/html/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8dc08021949b66f4430feb5393ec0d08 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.png b/documentation/html/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.png deleted file mode 100644 index ab567d6..0000000 Binary files a/documentation/html/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.map b/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.map deleted file mode 100644 index 8049d38..0000000 --- a/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.md5 b/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.md5 deleted file mode 100644 index 22a9b8e..0000000 --- a/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9144be6f54c5c007e41a29596be8a987 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.png b/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.png deleted file mode 100644 index b8c084a..0000000 Binary files a/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.map b/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.map deleted file mode 100644 index 11876f1..0000000 --- a/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.md5 b/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.md5 deleted file mode 100644 index a448dde..0000000 --- a/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5850e1d3f071714528024f02cb491e0c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.png b/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.png deleted file mode 100644 index 537bde9..0000000 Binary files a/documentation/html/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.map b/documentation/html/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.map deleted file mode 100644 index 1b571fc..0000000 --- a/documentation/html/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.md5 b/documentation/html/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.md5 deleted file mode 100644 index 555b2d4..0000000 --- a/documentation/html/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8b28ad0d2e9f81d877a0cd0a15723a68 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.png b/documentation/html/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.png deleted file mode 100644 index 43999e7..0000000 Binary files a/documentation/html/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.map b/documentation/html/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.map deleted file mode 100644 index 0efcc7a..0000000 --- a/documentation/html/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.map +++ /dev/null @@ -1,103 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.md5 b/documentation/html/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.md5 deleted file mode 100644 index d90d11e..0000000 --- a/documentation/html/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4dc48dee3078f655a569b68f69994b27 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.png b/documentation/html/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.png deleted file mode 100644 index 8691658..0000000 Binary files a/documentation/html/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.map b/documentation/html/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.map deleted file mode 100644 index 8c8017a..0000000 --- a/documentation/html/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.md5 b/documentation/html/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.md5 deleted file mode 100644 index f0d303b..0000000 --- a/documentation/html/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1965eb308db98ce5f1545f19a4b7617c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.png b/documentation/html/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.png deleted file mode 100644 index d79270e..0000000 Binary files a/documentation/html/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.map b/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.map deleted file mode 100644 index 6481bde..0000000 --- a/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.map +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.md5 b/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.md5 deleted file mode 100644 index cf8776b..0000000 --- a/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6c8ffc364d20f35652ce625b7d7a301c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.png b/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.png deleted file mode 100644 index 25cd125..0000000 Binary files a/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.map b/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.map deleted file mode 100644 index ef7b21d..0000000 --- a/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.md5 b/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.md5 deleted file mode 100644 index f8d257d..0000000 --- a/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ac57cdf15a8f98dfd89cc8a08dbf1341 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.png b/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.png deleted file mode 100644 index e93feee..0000000 Binary files a/documentation/html/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.map b/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.map deleted file mode 100644 index 66b63ed..0000000 --- a/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.md5 b/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.md5 deleted file mode 100644 index ab70e56..0000000 --- a/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f1596ceea4331c9e573339e6166710a5 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.png b/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.png deleted file mode 100644 index e1dde28..0000000 Binary files a/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.map b/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.map deleted file mode 100644 index c22faf4..0000000 --- a/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.md5 b/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.md5 deleted file mode 100644 index d8351d2..0000000 --- a/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f074eba7fba7aaaf53cbf234a6a0b3b9 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.png b/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.png deleted file mode 100644 index eebcaa4..0000000 Binary files a/documentation/html/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.map b/documentation/html/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.map deleted file mode 100644 index 670a339..0000000 --- a/documentation/html/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.md5 b/documentation/html/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.md5 deleted file mode 100644 index 7ffefa9..0000000 --- a/documentation/html/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4f8d9c195a9a15404dd3507c9a357b70 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.png b/documentation/html/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.png deleted file mode 100644 index 1ace746..0000000 Binary files a/documentation/html/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.map b/documentation/html/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.map deleted file mode 100644 index 943d4f1..0000000 --- a/documentation/html/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.md5 b/documentation/html/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.md5 deleted file mode 100644 index 0b2cfef..0000000 --- a/documentation/html/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -da21b5c2e32ee3953e41142c853529d5 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.png b/documentation/html/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.png deleted file mode 100644 index 01485e7..0000000 Binary files a/documentation/html/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.map b/documentation/html/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.map deleted file mode 100644 index 20a5116..0000000 --- a/documentation/html/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.md5 b/documentation/html/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.md5 deleted file mode 100644 index 6b750da..0000000 --- a/documentation/html/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2df60ce80829ab85e5b506c7e041ee35 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.png b/documentation/html/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.png deleted file mode 100644 index b916525..0000000 Binary files a/documentation/html/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.map b/documentation/html/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.map deleted file mode 100644 index c865581..0000000 --- a/documentation/html/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.md5 b/documentation/html/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.md5 deleted file mode 100644 index 1e3ae1b..0000000 --- a/documentation/html/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -bb7086f1a7cca0b8b3a31b6119dc47e5 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.png b/documentation/html/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.png deleted file mode 100644 index d987aa6..0000000 Binary files a/documentation/html/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.map b/documentation/html/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.map deleted file mode 100644 index 8314835..0000000 --- a/documentation/html/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.md5 b/documentation/html/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.md5 deleted file mode 100644 index ee0dc4e..0000000 --- a/documentation/html/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f91c9b3b8f41dc96419aac2e9b97b039 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.png b/documentation/html/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.png deleted file mode 100644 index 88af907..0000000 Binary files a/documentation/html/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.map b/documentation/html/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.map deleted file mode 100644 index a21534e..0000000 --- a/documentation/html/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.map +++ /dev/null @@ -1,18 +0,0 @@ - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.md5 b/documentation/html/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.md5 deleted file mode 100644 index df2e144..0000000 --- a/documentation/html/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1ca8c7c9a7a38f68f1ed9fa957fd9af1 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.png b/documentation/html/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.png deleted file mode 100644 index c3bd6a5..0000000 Binary files a/documentation/html/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.map b/documentation/html/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.map deleted file mode 100644 index cd026b0..0000000 --- a/documentation/html/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.md5 b/documentation/html/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.md5 deleted file mode 100644 index 10f4f4b..0000000 --- a/documentation/html/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0a7892d2742f899e8bae800f53a988a4 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.png b/documentation/html/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.png deleted file mode 100644 index 2d924d0..0000000 Binary files a/documentation/html/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.map b/documentation/html/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.map deleted file mode 100644 index 55e69ee..0000000 --- a/documentation/html/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.md5 b/documentation/html/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.md5 deleted file mode 100644 index 084b86f..0000000 --- a/documentation/html/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -786df73a6b017b08dc764c1fae06dadf \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.png b/documentation/html/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.png deleted file mode 100644 index 027e0c3..0000000 Binary files a/documentation/html/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.map b/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.map deleted file mode 100644 index ee77351..0000000 --- a/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.md5 b/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.md5 deleted file mode 100644 index 51cc8ef..0000000 --- a/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2f80270a2babadbe3035b9c7d4691a47 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.png b/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.png deleted file mode 100644 index fabde4c..0000000 Binary files a/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.map b/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.map deleted file mode 100644 index 9e651b3..0000000 --- a/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.md5 b/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.md5 deleted file mode 100644 index a2f0b96..0000000 --- a/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b0418cf0621c26c9f5c304a5b643b9c3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.png b/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.png deleted file mode 100644 index 6bf0678..0000000 Binary files a/documentation/html/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.map b/documentation/html/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.map deleted file mode 100644 index 06516ab..0000000 --- a/documentation/html/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.md5 b/documentation/html/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.md5 deleted file mode 100644 index 2c94a15..0000000 --- a/documentation/html/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8d48d03309bb55406cd33fb56cbb1fd8 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.png b/documentation/html/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.png deleted file mode 100644 index 252456c..0000000 Binary files a/documentation/html/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.map b/documentation/html/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.map deleted file mode 100644 index 0dbd101..0000000 --- a/documentation/html/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.md5 b/documentation/html/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.md5 deleted file mode 100644 index cc79760..0000000 --- a/documentation/html/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -096c5a2960bdeaeaa8af76740ccb7341 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.png b/documentation/html/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.png deleted file mode 100644 index b77801b..0000000 Binary files a/documentation/html/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.map b/documentation/html/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.map deleted file mode 100644 index 9422c83..0000000 --- a/documentation/html/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.md5 b/documentation/html/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.md5 deleted file mode 100644 index c3006e8..0000000 --- a/documentation/html/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b866b5d4768b5401fdb467dbff78c527 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.png b/documentation/html/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.png deleted file mode 100644 index aa43369..0000000 Binary files a/documentation/html/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.map b/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.map deleted file mode 100644 index 09870e9..0000000 --- a/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.md5 b/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.md5 deleted file mode 100644 index ae18e53..0000000 --- a/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -30f8490bed53eef60b35e997461084d3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.png b/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.png deleted file mode 100644 index 7d2046f..0000000 Binary files a/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.map b/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.map deleted file mode 100644 index 8f9d51d..0000000 --- a/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.md5 b/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.md5 deleted file mode 100644 index 0193068..0000000 --- a/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c1dbcfa0a3692ebca1c6747949a0df29 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.png b/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.png deleted file mode 100644 index 62e9cec..0000000 Binary files a/documentation/html/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.map b/documentation/html/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.map deleted file mode 100644 index eddde87..0000000 --- a/documentation/html/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.md5 b/documentation/html/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.md5 deleted file mode 100644 index e9ecdd8..0000000 --- a/documentation/html/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -277d3aa63f7202fb4532bd71a8b989f2 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.png b/documentation/html/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.png deleted file mode 100644 index 3fb15dc..0000000 Binary files a/documentation/html/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.map b/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.map deleted file mode 100644 index d7104f8..0000000 --- a/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.map +++ /dev/null @@ -1,20 +0,0 @@ - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.md5 b/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.md5 deleted file mode 100644 index 9573fc7..0000000 --- a/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9cd1f23125fe870c20940cea0a9ee349 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.png b/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.png deleted file mode 100644 index 00ab6f8..0000000 Binary files a/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.map b/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.map deleted file mode 100644 index 6f38d57..0000000 --- a/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.map +++ /dev/null @@ -1,93 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.md5 b/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.md5 deleted file mode 100644 index 0bb8a8d..0000000 --- a/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -daf8149ebdbb32c7038518928fd1f319 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.png b/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.png deleted file mode 100644 index 03e8861..0000000 Binary files a/documentation/html/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.map b/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.map deleted file mode 100644 index 63056ab..0000000 --- a/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.md5 b/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.md5 deleted file mode 100644 index 67a784b..0000000 --- a/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f0821b81da487b1c7f034019ba541235 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.png b/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.png deleted file mode 100644 index 58b53f1..0000000 Binary files a/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.map b/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.map deleted file mode 100644 index 2ae04bd..0000000 --- a/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.map +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.md5 b/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.md5 deleted file mode 100644 index 9403aaf..0000000 --- a/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -28babd8a794ab8babb2d24d0e8829d73 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.png b/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.png deleted file mode 100644 index efbbc70..0000000 Binary files a/documentation/html/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.map b/documentation/html/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.map deleted file mode 100644 index 87324a2..0000000 --- a/documentation/html/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.md5 b/documentation/html/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.md5 deleted file mode 100644 index a633f39..0000000 --- a/documentation/html/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a118ad39191236f5f34b3ec23d9ab9ce \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.png b/documentation/html/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.png deleted file mode 100644 index ed261b6..0000000 Binary files a/documentation/html/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.map b/documentation/html/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.map deleted file mode 100644 index 03332a6..0000000 --- a/documentation/html/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.map +++ /dev/null @@ -1,105 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.md5 b/documentation/html/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.md5 deleted file mode 100644 index 5c83145..0000000 --- a/documentation/html/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -072a874a280306a1e078572ae566952d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.png b/documentation/html/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.png deleted file mode 100644 index b24a8c4..0000000 Binary files a/documentation/html/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.map b/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.map deleted file mode 100644 index c465c0f..0000000 --- a/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.md5 b/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.md5 deleted file mode 100644 index 03d868d..0000000 --- a/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3533b81cd832c9eddadf8e7c34b19a2c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.png b/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.png deleted file mode 100644 index 20d3d2b..0000000 Binary files a/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.map b/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.map deleted file mode 100644 index 295e920..0000000 --- a/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.md5 b/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.md5 deleted file mode 100644 index 63b3f30..0000000 --- a/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fb3408b32c35928b9577c34c3e787f32 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.png b/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.png deleted file mode 100644 index ed2d1ce..0000000 Binary files a/documentation/html/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.map b/documentation/html/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.map deleted file mode 100644 index 4843177..0000000 --- a/documentation/html/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.map +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.md5 b/documentation/html/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.md5 deleted file mode 100644 index 076c512..0000000 --- a/documentation/html/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -27c1f847be0fc3c289911a5ce23aa500 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.png b/documentation/html/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.png deleted file mode 100644 index d2a9b05..0000000 Binary files a/documentation/html/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.map b/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.map deleted file mode 100644 index 95655ad..0000000 --- a/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.md5 b/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.md5 deleted file mode 100644 index 530fb13..0000000 --- a/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5adb3e3d8f866fabae92db6599baf2b8 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.png b/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.png deleted file mode 100644 index 0f55054..0000000 Binary files a/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.map b/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.map deleted file mode 100644 index 3244823..0000000 --- a/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.md5 b/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.md5 deleted file mode 100644 index 3dd0f89..0000000 --- a/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5c5a1ffdcb6294388d16c87bfecc71ac \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.png b/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.png deleted file mode 100644 index 51239de..0000000 Binary files a/documentation/html/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.map b/documentation/html/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.map deleted file mode 100644 index 18c811b..0000000 --- a/documentation/html/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.md5 b/documentation/html/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.md5 deleted file mode 100644 index 7f2b006..0000000 --- a/documentation/html/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6fb413d894f68800bc7f3da6738d5bb3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.png b/documentation/html/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.png deleted file mode 100644 index e4e43f8..0000000 Binary files a/documentation/html/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.map b/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.map deleted file mode 100644 index d5c2862..0000000 --- a/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.md5 b/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.md5 deleted file mode 100644 index 39cda3b..0000000 --- a/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -441568a428868de075f652fc143b149f \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.png b/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.png deleted file mode 100644 index ba16d32..0000000 Binary files a/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.map b/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.map deleted file mode 100644 index 856059d..0000000 --- a/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.md5 b/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.md5 deleted file mode 100644 index bf94b0e..0000000 --- a/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -033664ca04890df066dd37d8fa5fdbce \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.png b/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.png deleted file mode 100644 index 24651d1..0000000 Binary files a/documentation/html/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.map b/documentation/html/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.map deleted file mode 100644 index 2c76e03..0000000 --- a/documentation/html/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.md5 b/documentation/html/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.md5 deleted file mode 100644 index 370de37..0000000 --- a/documentation/html/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -dbd5e27f2226816ee5cfb001a5fefef7 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.png b/documentation/html/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.png deleted file mode 100644 index 4b74afd..0000000 Binary files a/documentation/html/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.map b/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.map deleted file mode 100644 index 015cbe6..0000000 --- a/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.map +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.md5 b/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.md5 deleted file mode 100644 index 358a5a5..0000000 --- a/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -883cd9e3bfd091a835479e80917868f5 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.png b/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.png deleted file mode 100644 index c3ea50a..0000000 Binary files a/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.map b/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.map deleted file mode 100644 index 4a5e377..0000000 --- a/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.md5 b/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.md5 deleted file mode 100644 index af6b2e7..0000000 --- a/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -571f12b8b03ec459624fa1f1217d50cb \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.png b/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.png deleted file mode 100644 index 1004e7c..0000000 Binary files a/documentation/html/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.map b/documentation/html/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.map deleted file mode 100644 index fc96457..0000000 --- a/documentation/html/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.md5 b/documentation/html/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.md5 deleted file mode 100644 index 38d87da..0000000 --- a/documentation/html/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b013032d91dc8b5c90f802d78c4e5a26 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.png b/documentation/html/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.png deleted file mode 100644 index f3cff32..0000000 Binary files a/documentation/html/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.map b/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.map deleted file mode 100644 index e4304ff..0000000 --- a/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.md5 b/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.md5 deleted file mode 100644 index f7d41cf..0000000 --- a/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -13238573a44c90ee253598d7f492083c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.png b/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.png deleted file mode 100644 index d547fb6..0000000 Binary files a/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.map b/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.map deleted file mode 100644 index ec0d19d..0000000 --- a/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.md5 b/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.md5 deleted file mode 100644 index ddb08ed..0000000 --- a/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2c83bac39eb45b614bc87e14c1afb4cb \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.png b/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.png deleted file mode 100644 index cf2cca0..0000000 Binary files a/documentation/html/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.map b/documentation/html/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.map deleted file mode 100644 index 26b2703..0000000 --- a/documentation/html/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.md5 b/documentation/html/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.md5 deleted file mode 100644 index 0566f34..0000000 --- a/documentation/html/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f838018224a51c4a6ae3ad2bde8f7a8d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.png b/documentation/html/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.png deleted file mode 100644 index 12da4c2..0000000 Binary files a/documentation/html/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.map b/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.map deleted file mode 100644 index 18deb20..0000000 --- a/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.map +++ /dev/null @@ -1,35 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.md5 b/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.md5 deleted file mode 100644 index acded24..0000000 --- a/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8be6de1475beda995ee64a32dffdc20d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.png b/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.png deleted file mode 100644 index 2d5a282..0000000 Binary files a/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.map b/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.map deleted file mode 100644 index 822ea3d..0000000 --- a/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.map +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.md5 b/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.md5 deleted file mode 100644 index a485eb1..0000000 --- a/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a6b67dd54a40fd2c35dbeae3ba36ac6b \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.png b/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.png deleted file mode 100644 index 9476fcd..0000000 Binary files a/documentation/html/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.map b/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.map deleted file mode 100644 index 6138de7..0000000 --- a/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.md5 b/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.md5 deleted file mode 100644 index b6b3a67..0000000 --- a/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a83d2ab6481ac8964472e4f6817e3d28 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.png b/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.png deleted file mode 100644 index 281aee8..0000000 Binary files a/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.map b/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.map deleted file mode 100644 index 1513b4d..0000000 --- a/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.map +++ /dev/null @@ -1,23 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.md5 b/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.md5 deleted file mode 100644 index 4262e25..0000000 --- a/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -21cb7a1ac813a14a5c9d46479d40c21d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.png b/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.png deleted file mode 100644 index 8338070..0000000 Binary files a/documentation/html/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.map b/documentation/html/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.map deleted file mode 100644 index 07bd706..0000000 --- a/documentation/html/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.md5 b/documentation/html/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.md5 deleted file mode 100644 index 28c5dc2..0000000 --- a/documentation/html/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6fbdd9704120f56a7b8066ebfe29111b \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.png b/documentation/html/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.png deleted file mode 100644 index 8fbd80c..0000000 Binary files a/documentation/html/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.map b/documentation/html/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.map deleted file mode 100644 index cda1e76..0000000 --- a/documentation/html/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.map +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.md5 b/documentation/html/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.md5 deleted file mode 100644 index 44e464e..0000000 --- a/documentation/html/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -090f0e862b1c368ea8f6816d57f8da31 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.png b/documentation/html/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.png deleted file mode 100644 index 7cd511d..0000000 Binary files a/documentation/html/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.map b/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.map deleted file mode 100644 index 516a960..0000000 --- a/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.md5 b/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.md5 deleted file mode 100644 index e71f77a..0000000 --- a/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b3bb9f37c3754d7f889a690b783e0590 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.png b/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.png deleted file mode 100644 index 5a7c980..0000000 Binary files a/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.map b/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.map deleted file mode 100644 index 08b383a..0000000 --- a/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.md5 b/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.md5 deleted file mode 100644 index 8b809ee..0000000 --- a/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -590a17d1690d9a67b91ed424b8b7b737 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.png b/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.png deleted file mode 100644 index 26d697a..0000000 Binary files a/documentation/html/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.map b/documentation/html/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.map deleted file mode 100644 index f1a95be..0000000 --- a/documentation/html/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.md5 b/documentation/html/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.md5 deleted file mode 100644 index d35f7e9..0000000 --- a/documentation/html/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -04ec1aab6be3f00b15583a4a81eeaab2 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.png b/documentation/html/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.png deleted file mode 100644 index 5acd5ed..0000000 Binary files a/documentation/html/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.map b/documentation/html/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.map deleted file mode 100644 index 2b5fda6..0000000 --- a/documentation/html/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.md5 b/documentation/html/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.md5 deleted file mode 100644 index 22e195f..0000000 --- a/documentation/html/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7ba3df902e2cd184b67e4b912271401f \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.png b/documentation/html/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.png deleted file mode 100644 index d82e91a..0000000 Binary files a/documentation/html/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.map b/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.map deleted file mode 100644 index 6d95755..0000000 --- a/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.md5 b/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.md5 deleted file mode 100644 index 2c3f53b..0000000 --- a/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -32c4153e148c225d0d3eda2b3f3b17e1 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.png b/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.png deleted file mode 100644 index 2810f7e..0000000 Binary files a/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.map b/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.map deleted file mode 100644 index cba60e6..0000000 --- a/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.md5 b/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.md5 deleted file mode 100644 index c2827a5..0000000 --- a/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3f192d2614226f0e42ef0051694ad28e \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.png b/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.png deleted file mode 100644 index 3939433..0000000 Binary files a/documentation/html/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.map b/documentation/html/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.map deleted file mode 100644 index 6364d88..0000000 --- a/documentation/html/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.md5 b/documentation/html/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.md5 deleted file mode 100644 index 724048a..0000000 --- a/documentation/html/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c8e1ffdf9c1961c017261464243dea45 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.png b/documentation/html/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.png deleted file mode 100644 index 2495142..0000000 Binary files a/documentation/html/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.map b/documentation/html/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.map deleted file mode 100644 index 1f3310e..0000000 --- a/documentation/html/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.md5 b/documentation/html/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.md5 deleted file mode 100644 index a01fecd..0000000 --- a/documentation/html/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5f5055a4feb9e79264a47e18ea48d648 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.png b/documentation/html/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.png deleted file mode 100644 index 6235409..0000000 Binary files a/documentation/html/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.map b/documentation/html/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.map deleted file mode 100644 index fb841d3..0000000 --- a/documentation/html/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.md5 b/documentation/html/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.md5 deleted file mode 100644 index fed9cd2..0000000 --- a/documentation/html/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7ed3a10ce0ceda386f4e93c90eb5b9ad \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.png b/documentation/html/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.png deleted file mode 100644 index 25aa26f..0000000 Binary files a/documentation/html/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.map b/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.map deleted file mode 100644 index 69e0224..0000000 --- a/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.md5 b/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.md5 deleted file mode 100644 index de54c2e..0000000 --- a/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -68227168a9556eccd0cb4230c78ed85f \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.png b/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.png deleted file mode 100644 index 8813250..0000000 Binary files a/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.map b/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.map deleted file mode 100644 index 3c50ada..0000000 --- a/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.md5 b/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.md5 deleted file mode 100644 index 7a4b6cf..0000000 --- a/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7232bd071e5111b7f10be34498ca4e12 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.png b/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.png deleted file mode 100644 index e9c29aa..0000000 Binary files a/documentation/html/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.map b/documentation/html/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.map deleted file mode 100644 index ed20b13..0000000 --- a/documentation/html/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.map +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.md5 b/documentation/html/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.md5 deleted file mode 100644 index 5af9d9d..0000000 --- a/documentation/html/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a39cda1a133b738201b79f3e61392a30 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.png b/documentation/html/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.png deleted file mode 100644 index cc0c945..0000000 Binary files a/documentation/html/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.map b/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.map deleted file mode 100644 index 9e20f1c..0000000 --- a/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.md5 b/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.md5 deleted file mode 100644 index 838ed89..0000000 --- a/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f49539a95ec2027122721c1ece06ce77 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.png b/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.png deleted file mode 100644 index b62a457..0000000 Binary files a/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.map b/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.map deleted file mode 100644 index e24de19..0000000 --- a/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.md5 b/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.md5 deleted file mode 100644 index 7432b6b..0000000 --- a/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e5b994fd5a29b45fb7ec02627d4291e1 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.png b/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.png deleted file mode 100644 index 9e2494b..0000000 Binary files a/documentation/html/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.map b/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.map deleted file mode 100644 index b09cd0f..0000000 --- a/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.md5 b/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.md5 deleted file mode 100644 index 345f7bf..0000000 --- a/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -85321fe73e73e086dc0deb7f2383a81b \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.png b/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.png deleted file mode 100644 index 1de1ec5..0000000 Binary files a/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.map b/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.map deleted file mode 100644 index fd64cef..0000000 --- a/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.md5 b/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.md5 deleted file mode 100644 index 6369532..0000000 --- a/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -cbce8f390af35f07cc4e03dcc42066d7 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.png b/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.png deleted file mode 100644 index 2d161b8..0000000 Binary files a/documentation/html/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.map b/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.map deleted file mode 100644 index 5ca51b1..0000000 --- a/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.map +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.md5 b/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.md5 deleted file mode 100644 index f7c2df0..0000000 --- a/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b7566f68906139250d64ac33ab1bbba7 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.png b/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.png deleted file mode 100644 index 7187dd8..0000000 Binary files a/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.map b/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.map deleted file mode 100644 index efe5291..0000000 --- a/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.md5 b/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.md5 deleted file mode 100644 index 768f8d0..0000000 --- a/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8474a7f07ce70b1f43fb580a8a29d1ef \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.png b/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.png deleted file mode 100644 index e8c0cba..0000000 Binary files a/documentation/html/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.map b/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.map deleted file mode 100644 index 625700c..0000000 --- a/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.md5 b/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.md5 deleted file mode 100644 index c11ad9e..0000000 --- a/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d62ba8f4acb8c057a1baa70f6fa82bcb \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.png b/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.png deleted file mode 100644 index ca6460c..0000000 Binary files a/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.map b/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.map deleted file mode 100644 index 43fd016..0000000 --- a/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.md5 b/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.md5 deleted file mode 100644 index b8aeb06..0000000 --- a/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -dee59612e7c7229270a82722900a9641 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.png b/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.png deleted file mode 100644 index 460f34b..0000000 Binary files a/documentation/html/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.map b/documentation/html/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.map deleted file mode 100644 index a33f1f9..0000000 --- a/documentation/html/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.md5 b/documentation/html/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.md5 deleted file mode 100644 index afa5c65..0000000 --- a/documentation/html/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a7460556e97771669cfbb7a24eceb421 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.png b/documentation/html/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.png deleted file mode 100644 index 712c8fd..0000000 Binary files a/documentation/html/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.map b/documentation/html/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.map deleted file mode 100644 index 8c05bd8..0000000 --- a/documentation/html/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.md5 b/documentation/html/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.md5 deleted file mode 100644 index 0a19368..0000000 --- a/documentation/html/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -53d2a1ccf018f348a2e012ee1d8e1e47 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.png b/documentation/html/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.png deleted file mode 100644 index 707e450..0000000 Binary files a/documentation/html/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.map b/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.map deleted file mode 100644 index 4569cd5..0000000 --- a/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.md5 b/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.md5 deleted file mode 100644 index c437701..0000000 --- a/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -26e23ee7c1624c8be8750da3f228ade4 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.png b/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.png deleted file mode 100644 index 0bce1b9..0000000 Binary files a/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.map b/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.map deleted file mode 100644 index 33ea8f3..0000000 --- a/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.md5 b/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.md5 deleted file mode 100644 index d17f001..0000000 --- a/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3c5769cd6e6c27c5897f5f839edf7c78 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.png b/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.png deleted file mode 100644 index f126ff8..0000000 Binary files a/documentation/html/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.map b/documentation/html/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.map deleted file mode 100644 index 66c5fb0..0000000 --- a/documentation/html/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.md5 b/documentation/html/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.md5 deleted file mode 100644 index 3200354..0000000 --- a/documentation/html/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -86a768ed6a06b483a1aba63916df23b2 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.png b/documentation/html/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.png deleted file mode 100644 index 6bbc772..0000000 Binary files a/documentation/html/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.map b/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.map deleted file mode 100644 index bf0903e..0000000 --- a/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.md5 b/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.md5 deleted file mode 100644 index c4c3f64..0000000 --- a/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -dd5549132c0f1443d2e87a5e79c9e9a4 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.png b/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.png deleted file mode 100644 index fb7d109..0000000 Binary files a/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.map b/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.map deleted file mode 100644 index 787e315..0000000 --- a/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.md5 b/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.md5 deleted file mode 100644 index 04fe7d5..0000000 --- a/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f7f9a0ece3bf42ec464d9ede86e327a0 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.png b/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.png deleted file mode 100644 index 3ddc694..0000000 Binary files a/documentation/html/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.map b/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.map deleted file mode 100644 index 4f35b03..0000000 --- a/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.md5 b/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.md5 deleted file mode 100644 index 1d7e64d..0000000 --- a/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1767df82c55e87856d02a95e7ade8756 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.png b/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.png deleted file mode 100644 index b5d7a20..0000000 Binary files a/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.map b/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.map deleted file mode 100644 index de5f5d1..0000000 --- a/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.md5 b/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.md5 deleted file mode 100644 index e084a47..0000000 --- a/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8620fb31e7e96b180de30e461b232aa5 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.png b/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.png deleted file mode 100644 index 93e5354..0000000 Binary files a/documentation/html/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.map b/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.map deleted file mode 100644 index 65d0a6a..0000000 --- a/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.md5 b/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.md5 deleted file mode 100644 index b3fadc1..0000000 --- a/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -676894d52acdef98a30cdf577a553c13 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.png b/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.png deleted file mode 100644 index 645f096..0000000 Binary files a/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.map b/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.map deleted file mode 100644 index 95e63cc..0000000 --- a/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.md5 b/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.md5 deleted file mode 100644 index f6bc58e..0000000 --- a/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9a7124d89af5774e1f2e0f93275f8023 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.png b/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.png deleted file mode 100644 index 001d485..0000000 Binary files a/documentation/html/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.map b/documentation/html/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.map deleted file mode 100644 index 13e5ef8..0000000 --- a/documentation/html/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.md5 b/documentation/html/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.md5 deleted file mode 100644 index 3bb490d..0000000 --- a/documentation/html/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9e12c092d6a3d264e9c1db82134e44e3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.png b/documentation/html/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.png deleted file mode 100644 index d1a327e..0000000 Binary files a/documentation/html/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.map b/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.map deleted file mode 100644 index 6530167..0000000 --- a/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.md5 b/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.md5 deleted file mode 100644 index 5947596..0000000 --- a/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5daae66a4bb009eb9e7a1e2804b3e132 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.png b/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.png deleted file mode 100644 index cb68ace..0000000 Binary files a/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.map b/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.map deleted file mode 100644 index d5616a4..0000000 --- a/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.md5 b/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.md5 deleted file mode 100644 index 23a463d..0000000 --- a/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -07f73491fe6396d4ee5de40e00e869aa \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.png b/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.png deleted file mode 100644 index b055a59..0000000 Binary files a/documentation/html/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.map b/documentation/html/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.map deleted file mode 100644 index c16ce6f..0000000 --- a/documentation/html/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.md5 b/documentation/html/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.md5 deleted file mode 100644 index 3914ed6..0000000 --- a/documentation/html/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -68ff3a246abb94b253ccc4c1093a42a3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.png b/documentation/html/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.png deleted file mode 100644 index 47554ca..0000000 Binary files a/documentation/html/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.map b/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.map deleted file mode 100644 index d1dbdb1..0000000 --- a/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.md5 b/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.md5 deleted file mode 100644 index a17673a..0000000 --- a/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7dc91d11877a8784d81e5e6214a3e69e \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.png b/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.png deleted file mode 100644 index dabf909..0000000 Binary files a/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.map b/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.map deleted file mode 100644 index cb6143e..0000000 --- a/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.md5 b/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.md5 deleted file mode 100644 index 0f7bb20..0000000 --- a/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d6d6ffa36866f9adcffb5fc87246e08f \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.png b/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.png deleted file mode 100644 index c524d36..0000000 Binary files a/documentation/html/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.map b/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.map deleted file mode 100644 index 4b9bc77..0000000 --- a/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.md5 b/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.md5 deleted file mode 100644 index 3675eae..0000000 --- a/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f10ac5ddecb10ec6f863555e40834cfb \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.png b/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.png deleted file mode 100644 index ec876a7..0000000 Binary files a/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.map b/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.map deleted file mode 100644 index 7da230b..0000000 --- a/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.md5 b/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.md5 deleted file mode 100644 index d454350..0000000 --- a/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -86c4dd1f9c3f2e17d578a2911d89720c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.png b/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.png deleted file mode 100644 index 830fb63..0000000 Binary files a/documentation/html/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.map b/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.map deleted file mode 100644 index 1148fc7..0000000 --- a/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.map +++ /dev/null @@ -1,53 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.md5 b/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.md5 deleted file mode 100644 index 24c724d..0000000 --- a/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -29ccf12bb97640c9baadb71a1a548273 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.png b/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.png deleted file mode 100644 index e5cc2cf..0000000 Binary files a/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.map b/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.map deleted file mode 100644 index 76be206..0000000 --- a/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.map +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.md5 b/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.md5 deleted file mode 100644 index 2b8de53..0000000 --- a/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -cccdd5dffc3a1fb6533fd659170296da \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.png b/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.png deleted file mode 100644 index b33f814..0000000 Binary files a/documentation/html/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.map b/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.map deleted file mode 100644 index 452426c..0000000 --- a/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.md5 b/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.md5 deleted file mode 100644 index 70e10b3..0000000 --- a/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -676399900389aac49a2a46eb8b24aa75 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.png b/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.png deleted file mode 100644 index c95c925..0000000 Binary files a/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.map b/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.map deleted file mode 100644 index 5aa6f3f..0000000 --- a/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.map +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.md5 b/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.md5 deleted file mode 100644 index 08a5a18..0000000 --- a/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f7a36add6905e50244631798bf8079a1 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.png b/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.png deleted file mode 100644 index 38b7ceb..0000000 Binary files a/documentation/html/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.map b/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.map deleted file mode 100644 index 40ba194..0000000 --- a/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.md5 b/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.md5 deleted file mode 100644 index 0b2c9e2..0000000 --- a/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fbb906caa76c5dafba3381e3ff4253b6 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.png b/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.png deleted file mode 100644 index c1a2e93..0000000 Binary files a/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.map b/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.map deleted file mode 100644 index 48f3a50..0000000 --- a/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.md5 b/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.md5 deleted file mode 100644 index a48c162..0000000 --- a/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b52109aa4c3f9764711532991b197778 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.png b/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.png deleted file mode 100644 index 41d707d..0000000 Binary files a/documentation/html/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.map b/documentation/html/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.map deleted file mode 100644 index 31db838..0000000 --- a/documentation/html/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.md5 b/documentation/html/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.md5 deleted file mode 100644 index 1bd90a7..0000000 --- a/documentation/html/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6288c7c1a484d734b06fa9bfb54cff0e \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.png b/documentation/html/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.png deleted file mode 100644 index 7d8f3e9..0000000 Binary files a/documentation/html/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.map b/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.map deleted file mode 100644 index 7fa256a..0000000 --- a/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.md5 b/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.md5 deleted file mode 100644 index e2616b7..0000000 --- a/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -19dd6fe21f9746923ee58645f464e87b \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.png b/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.png deleted file mode 100644 index 23b840f..0000000 Binary files a/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.map b/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.map deleted file mode 100644 index 879201d..0000000 --- a/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.map +++ /dev/null @@ -1,47 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.md5 b/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.md5 deleted file mode 100644 index aea5eb4..0000000 --- a/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9c979ebe492d185dd06a0839dc39ac0f \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.png b/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.png deleted file mode 100644 index 0c4362e..0000000 Binary files a/documentation/html/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.map b/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.map deleted file mode 100644 index e40e809..0000000 --- a/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.md5 b/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.md5 deleted file mode 100644 index 3a82999..0000000 --- a/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -826b9bcf50e5ced6bcf5863697cee4d4 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.png b/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.png deleted file mode 100644 index 39a51ce..0000000 Binary files a/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.map b/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.map deleted file mode 100644 index 2fd599f..0000000 --- a/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.md5 b/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.md5 deleted file mode 100644 index d3ae20c..0000000 --- a/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -35f8838cbf3d0ca53276d18462eddc38 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.png b/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.png deleted file mode 100644 index 427855b..0000000 Binary files a/documentation/html/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.map b/documentation/html/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.map deleted file mode 100644 index 60a53fa..0000000 --- a/documentation/html/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.md5 b/documentation/html/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.md5 deleted file mode 100644 index 3ccf111..0000000 --- a/documentation/html/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c50f32c8cf4ce25442c908088717f5c3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.png b/documentation/html/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.png deleted file mode 100644 index 7d4d031..0000000 Binary files a/documentation/html/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.map b/documentation/html/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.map deleted file mode 100644 index 6b23cd8..0000000 --- a/documentation/html/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.md5 b/documentation/html/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.md5 deleted file mode 100644 index 4786150..0000000 --- a/documentation/html/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -09003273e842e4de4ff3620df3e59015 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.png b/documentation/html/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.png deleted file mode 100644 index d44c0a0..0000000 Binary files a/documentation/html/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.map b/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.map deleted file mode 100644 index 4926ed1..0000000 --- a/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.md5 b/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.md5 deleted file mode 100644 index 879ec66..0000000 --- a/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -092538e31f4ae9259de9a2e3f094bba1 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.png b/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.png deleted file mode 100644 index d973919..0000000 Binary files a/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.map b/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.map deleted file mode 100644 index d8e08a2..0000000 --- a/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.md5 b/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.md5 deleted file mode 100644 index 198f090..0000000 --- a/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3d0960047610c87cbd7aa164eacbfd15 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.png b/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.png deleted file mode 100644 index bfcb51b..0000000 Binary files a/documentation/html/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.map b/documentation/html/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.map deleted file mode 100644 index d5a80b1..0000000 --- a/documentation/html/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.md5 b/documentation/html/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.md5 deleted file mode 100644 index 5d9c8a5..0000000 --- a/documentation/html/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -996d45399debd84dfd48d5b3f0986b23 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.png b/documentation/html/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.png deleted file mode 100644 index 629bc80..0000000 Binary files a/documentation/html/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.map b/documentation/html/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.map deleted file mode 100644 index 1e0eb89..0000000 --- a/documentation/html/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.md5 b/documentation/html/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.md5 deleted file mode 100644 index d44a188..0000000 --- a/documentation/html/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5a14296291029d30993f9cf2171208cb \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.png b/documentation/html/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.png deleted file mode 100644 index d30453a..0000000 Binary files a/documentation/html/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.map b/documentation/html/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.map deleted file mode 100644 index c856aa5..0000000 --- a/documentation/html/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.md5 b/documentation/html/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.md5 deleted file mode 100644 index b1b0ecb..0000000 --- a/documentation/html/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -162b27c114128430b7d63dc836b81883 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.png b/documentation/html/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.png deleted file mode 100644 index c43cb3b..0000000 Binary files a/documentation/html/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.map b/documentation/html/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.map deleted file mode 100644 index 8d9c8c6..0000000 --- a/documentation/html/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.md5 b/documentation/html/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.md5 deleted file mode 100644 index 04e7c71..0000000 --- a/documentation/html/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5eff414eff1a274e313d2c2e0ae56c17 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.png b/documentation/html/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.png deleted file mode 100644 index 1489db7..0000000 Binary files a/documentation/html/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.map b/documentation/html/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.map deleted file mode 100644 index 1dbf158..0000000 --- a/documentation/html/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.md5 b/documentation/html/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.md5 deleted file mode 100644 index d53519b..0000000 --- a/documentation/html/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a4e52aff6aa5f49a174d573553f351cb \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.png b/documentation/html/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.png deleted file mode 100644 index e1a7ab6..0000000 Binary files a/documentation/html/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.map b/documentation/html/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.map deleted file mode 100644 index 564bd2f..0000000 --- a/documentation/html/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.map +++ /dev/null @@ -1,25 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.md5 b/documentation/html/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.md5 deleted file mode 100644 index 47c8ba4..0000000 --- a/documentation/html/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -49b2e488cf54885f64cac6707e5dd5be \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.png b/documentation/html/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.png deleted file mode 100644 index bb33ae3..0000000 Binary files a/documentation/html/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.map b/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.map deleted file mode 100644 index eebb97f..0000000 --- a/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.md5 b/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.md5 deleted file mode 100644 index cbc6744..0000000 --- a/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -98d4938530c76a01060d14f7069085cc \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.png b/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.png deleted file mode 100644 index f83172d..0000000 Binary files a/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.map b/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.map deleted file mode 100644 index 0574f11..0000000 --- a/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.md5 b/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.md5 deleted file mode 100644 index 5ebcdd0..0000000 --- a/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1ff6613ddbe60e2ca566f665d468d5f0 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.png b/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.png deleted file mode 100644 index cfae6c0..0000000 Binary files a/documentation/html/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.map b/documentation/html/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.map deleted file mode 100644 index c7a2ab5..0000000 --- a/documentation/html/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.map +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.md5 b/documentation/html/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.md5 deleted file mode 100644 index 9aedec0..0000000 --- a/documentation/html/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b4fa191835936bdd5f82195811249178 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.png b/documentation/html/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.png deleted file mode 100644 index a5e3570..0000000 Binary files a/documentation/html/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.map b/documentation/html/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.map deleted file mode 100644 index f608ddd..0000000 --- a/documentation/html/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.md5 b/documentation/html/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.md5 deleted file mode 100644 index 923815e..0000000 --- a/documentation/html/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -76bc8192ea2a3b05a42a3511356aa185 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.png b/documentation/html/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.png deleted file mode 100644 index 62cd68d..0000000 Binary files a/documentation/html/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.map b/documentation/html/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.map deleted file mode 100644 index c6f28eb..0000000 --- a/documentation/html/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.md5 b/documentation/html/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.md5 deleted file mode 100644 index a36bc05..0000000 --- a/documentation/html/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -16fb1592e3540e38e18dbc7876160b59 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.png b/documentation/html/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.png deleted file mode 100644 index 8d85253..0000000 Binary files a/documentation/html/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.map b/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.map deleted file mode 100644 index 354dcd8..0000000 --- a/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.md5 b/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.md5 deleted file mode 100644 index e1ab66e..0000000 --- a/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e37d5ad820b489ef654636aea0a164ce \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.png b/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.png deleted file mode 100644 index 284abb6..0000000 Binary files a/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.map b/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.map deleted file mode 100644 index 2041b2d..0000000 --- a/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.map +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.md5 b/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.md5 deleted file mode 100644 index 7aa9ebc..0000000 --- a/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -02f3f24a258eb8b0ec359b0b702306e6 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.png b/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.png deleted file mode 100644 index 5771093..0000000 Binary files a/documentation/html/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.map b/documentation/html/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.map deleted file mode 100644 index 3b2dbbb..0000000 --- a/documentation/html/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.md5 b/documentation/html/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.md5 deleted file mode 100644 index fd2977b..0000000 --- a/documentation/html/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -cfa7d7f8b33077a310bff347608b1154 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.png b/documentation/html/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.png deleted file mode 100644 index c9bc292..0000000 Binary files a/documentation/html/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.map b/documentation/html/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.map deleted file mode 100644 index d25b929..0000000 --- a/documentation/html/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.md5 b/documentation/html/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.md5 deleted file mode 100644 index 1eacb99..0000000 --- a/documentation/html/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -44cdbc2f4baf0bacb288fffbc30e2191 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.png b/documentation/html/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.png deleted file mode 100644 index 2d60400..0000000 Binary files a/documentation/html/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.map b/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.map deleted file mode 100644 index af181c1..0000000 --- a/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.md5 b/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.md5 deleted file mode 100644 index a8179bb..0000000 --- a/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -232aaa145c18f5dd6db2b90331f57be6 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.png b/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.png deleted file mode 100644 index 2d8527e..0000000 Binary files a/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.map b/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.map deleted file mode 100644 index 0a2232c..0000000 --- a/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.map +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.md5 b/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.md5 deleted file mode 100644 index 18bdb07..0000000 --- a/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8df29acbb42104e04b7513c6614346f4 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.png b/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.png deleted file mode 100644 index 5b75449..0000000 Binary files a/documentation/html/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.map b/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.map deleted file mode 100644 index a5cda36..0000000 --- a/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.md5 b/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.md5 deleted file mode 100644 index 6423707..0000000 --- a/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -180c8761feecc30b334177a18c64f76d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.png b/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.png deleted file mode 100644 index 1d03f7c..0000000 Binary files a/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.map b/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.map deleted file mode 100644 index a09e14e..0000000 --- a/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.map +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.md5 b/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.md5 deleted file mode 100644 index 4a0d50c..0000000 --- a/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -87adf0d7cbecdad863836ae5380c4015 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.png b/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.png deleted file mode 100644 index 17322b3..0000000 Binary files a/documentation/html/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.map b/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.map deleted file mode 100644 index 9cb68f8..0000000 --- a/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.map +++ /dev/null @@ -1,22 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.md5 b/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.md5 deleted file mode 100644 index f8b3dcf..0000000 --- a/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e6a13a1c96139ff5263475611a4699e3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.png b/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.png deleted file mode 100644 index 975bd9b..0000000 Binary files a/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.map b/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.map deleted file mode 100644 index 684e839..0000000 --- a/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.md5 b/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.md5 deleted file mode 100644 index ccf02fb..0000000 --- a/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -95c4e9032b07642dd20579d711a2c644 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.png b/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.png deleted file mode 100644 index 70924bf..0000000 Binary files a/documentation/html/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.map b/documentation/html/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.map deleted file mode 100644 index de0ab36..0000000 --- a/documentation/html/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.map +++ /dev/null @@ -1,75 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.md5 b/documentation/html/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.md5 deleted file mode 100644 index b592c86..0000000 --- a/documentation/html/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -30a0853b931043ea9c04527f2fbfc617 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.png b/documentation/html/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.png deleted file mode 100644 index a457271..0000000 Binary files a/documentation/html/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.map b/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.map deleted file mode 100644 index 98b80b6..0000000 --- a/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.md5 b/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.md5 deleted file mode 100644 index 120898f..0000000 --- a/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0220442faaf119e49fa2ef8558406931 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.png b/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.png deleted file mode 100644 index 58e9de2..0000000 Binary files a/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.map b/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.map deleted file mode 100644 index 86b34b6..0000000 --- a/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.md5 b/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.md5 deleted file mode 100644 index 32af7bb..0000000 --- a/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -df34a8595cfc49b37a2cf2bcd4b0850d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.png b/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.png deleted file mode 100644 index 74ede0f..0000000 Binary files a/documentation/html/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.map b/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.map deleted file mode 100644 index 70dc604..0000000 --- a/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.map +++ /dev/null @@ -1,101 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.md5 b/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.md5 deleted file mode 100644 index 82f8050..0000000 --- a/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2f6e7c9a9cd1d50401f7835cd2b1fd9d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.png b/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.png deleted file mode 100644 index 7f51466..0000000 Binary files a/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.map b/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.map deleted file mode 100644 index 80d2f1c..0000000 --- a/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.md5 b/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.md5 deleted file mode 100644 index cc2890b..0000000 --- a/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -50b52a3afe7c8eca9b52be6d261cf9d2 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.png b/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.png deleted file mode 100644 index 9074d8b..0000000 Binary files a/documentation/html/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.map b/documentation/html/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.map deleted file mode 100644 index 1b994c1..0000000 --- a/documentation/html/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.md5 b/documentation/html/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.md5 deleted file mode 100644 index 76c80d2..0000000 --- a/documentation/html/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1d48b4529a2b4aef3808d20a7706cf1e \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.png b/documentation/html/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.png deleted file mode 100644 index 7f619e7..0000000 Binary files a/documentation/html/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.map b/documentation/html/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.map deleted file mode 100644 index ffbbb79..0000000 --- a/documentation/html/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.map +++ /dev/null @@ -1,18 +0,0 @@ - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.md5 b/documentation/html/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.md5 deleted file mode 100644 index f6feecc..0000000 --- a/documentation/html/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c59694186d382392e8ce9661a946b471 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.png b/documentation/html/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.png deleted file mode 100644 index ec13a31..0000000 Binary files a/documentation/html/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.map b/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.map deleted file mode 100644 index 8e7f856..0000000 --- a/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.md5 b/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.md5 deleted file mode 100644 index 7123ade..0000000 --- a/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5cb96b8b96188d62ed0cfa8ffc70a514 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.png b/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.png deleted file mode 100644 index 136073f..0000000 Binary files a/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.map b/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.map deleted file mode 100644 index 500bab1..0000000 --- a/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.map +++ /dev/null @@ -1,51 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.md5 b/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.md5 deleted file mode 100644 index d64f97c..0000000 --- a/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4807f09f4e931d7c6be41d0b1d60ea7d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.png b/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.png deleted file mode 100644 index 351d55f..0000000 Binary files a/documentation/html/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.map b/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.map deleted file mode 100644 index 3e29655..0000000 --- a/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.md5 b/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.md5 deleted file mode 100644 index 1d9ed64..0000000 --- a/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -98b4f934344b0c66dfbee0365cc3915b \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.png b/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.png deleted file mode 100644 index 3e1cfdc..0000000 Binary files a/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.map b/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.map deleted file mode 100644 index 5f53906..0000000 --- a/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.map +++ /dev/null @@ -1,138 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.md5 b/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.md5 deleted file mode 100644 index 26675db..0000000 --- a/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a91bfe91aeb0edb593c02d6ecf7cc64d \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.png b/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.png deleted file mode 100644 index 7be0526..0000000 Binary files a/documentation/html/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.map b/documentation/html/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.map deleted file mode 100644 index 583df88..0000000 --- a/documentation/html/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.map +++ /dev/null @@ -1,18 +0,0 @@ - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.md5 b/documentation/html/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.md5 deleted file mode 100644 index 6405783..0000000 --- a/documentation/html/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2a7d0e6e36d27ddd81c698cfba81e442 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.png b/documentation/html/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.png deleted file mode 100644 index b2c1415..0000000 Binary files a/documentation/html/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.map b/documentation/html/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.map deleted file mode 100644 index 1441b26..0000000 --- a/documentation/html/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.md5 b/documentation/html/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.md5 deleted file mode 100644 index 729f9d3..0000000 --- a/documentation/html/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -95a3893da0af00691eec9a70605d9455 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.png b/documentation/html/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.png deleted file mode 100644 index 87ed6c0..0000000 Binary files a/documentation/html/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.map b/documentation/html/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.map deleted file mode 100644 index d6929ed..0000000 --- a/documentation/html/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.md5 b/documentation/html/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.md5 deleted file mode 100644 index 70b9d1c..0000000 --- a/documentation/html/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d92e913a4ba85d8457a05ccf30d649d3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.png b/documentation/html/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.png deleted file mode 100644 index a1f5173..0000000 Binary files a/documentation/html/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.map b/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.map deleted file mode 100644 index c5f48ed..0000000 --- a/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.md5 b/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.md5 deleted file mode 100644 index d749e7c..0000000 --- a/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0e24b75d0bb498e768b805528a0320a0 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.png b/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.png deleted file mode 100644 index b168173..0000000 Binary files a/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.map b/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.map deleted file mode 100644 index af2307c..0000000 --- a/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.md5 b/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.md5 deleted file mode 100644 index f1b06db..0000000 --- a/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -463d97e50bc3c6195f250019b89af1b4 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.png b/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.png deleted file mode 100644 index 68fbeab..0000000 Binary files a/documentation/html/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.map b/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.map deleted file mode 100644 index e516c16..0000000 --- a/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.md5 b/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.md5 deleted file mode 100644 index 16e7c52..0000000 --- a/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -697b8105ee362811c4c94b754b33de33 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.png b/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.png deleted file mode 100644 index 6703637..0000000 Binary files a/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.map b/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.map deleted file mode 100644 index 3827ec4..0000000 --- a/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.md5 b/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.md5 deleted file mode 100644 index 399842b..0000000 --- a/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -85e8dc86a5c700fabd3068d3e4ff780b \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.png b/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.png deleted file mode 100644 index cc56604..0000000 Binary files a/documentation/html/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.map b/documentation/html/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.map deleted file mode 100644 index 45802c5..0000000 --- a/documentation/html/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.md5 b/documentation/html/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.md5 deleted file mode 100644 index 1a5b10e..0000000 --- a/documentation/html/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d0016b9db48f73cbee2779b484324b9c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.png b/documentation/html/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.png deleted file mode 100644 index 7523691..0000000 Binary files a/documentation/html/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.map b/documentation/html/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.map deleted file mode 100644 index 1386906..0000000 --- a/documentation/html/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.md5 b/documentation/html/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.md5 deleted file mode 100644 index d802b09..0000000 --- a/documentation/html/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -cf04315479b99d3fa53d551fd2955b89 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.png b/documentation/html/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.png deleted file mode 100644 index 044b598..0000000 Binary files a/documentation/html/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.map b/documentation/html/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.map deleted file mode 100644 index 706eace..0000000 --- a/documentation/html/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.md5 b/documentation/html/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.md5 deleted file mode 100644 index 67626fb..0000000 --- a/documentation/html/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5edca377a1d9f8058a795007d0e8a6d1 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.png b/documentation/html/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.png deleted file mode 100644 index b119dc1..0000000 Binary files a/documentation/html/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.map b/documentation/html/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.map deleted file mode 100644 index 70f8eb7..0000000 --- a/documentation/html/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.map +++ /dev/null @@ -1,27 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.md5 b/documentation/html/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.md5 deleted file mode 100644 index cd3aff9..0000000 --- a/documentation/html/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2fc1261a6bfbe062d91b171d24584b69 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.png b/documentation/html/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.png deleted file mode 100644 index 533d9e3..0000000 Binary files a/documentation/html/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.map b/documentation/html/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.map deleted file mode 100644 index 482be98..0000000 --- a/documentation/html/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.md5 b/documentation/html/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.md5 deleted file mode 100644 index 927d09a..0000000 --- a/documentation/html/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e67fd560ecd057846ad8b6b000fe8015 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.png b/documentation/html/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.png deleted file mode 100644 index 9343d7f..0000000 Binary files a/documentation/html/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.map b/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.map deleted file mode 100644 index 573660a..0000000 --- a/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.map +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.md5 b/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.md5 deleted file mode 100644 index e98099b..0000000 --- a/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5e59dacc5d66b9ffa9d6803817c0ae34 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.png b/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.png deleted file mode 100644 index cfbf89d..0000000 Binary files a/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.map b/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.map deleted file mode 100644 index 69f2492..0000000 --- a/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.md5 b/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.md5 deleted file mode 100644 index 2baf14c..0000000 --- a/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e5a4f1b745d2a88623feb300f0bd8234 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.png b/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.png deleted file mode 100644 index adfc8c1..0000000 Binary files a/documentation/html/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper-members.html b/documentation/html/class_b_n_o08x_test_helper-members.html deleted file mode 100644 index a6b2cd6..0000000 --- a/documentation/html/class_b_n_o08x_test_helper-members.html +++ /dev/null @@ -1,142 +0,0 @@ - - - - - - - -esp32_BNO08x: Member List - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
BNO08xTestHelper Member List
-
-
- -

This is the complete list of members for BNO08xTestHelper, including all inherited members.

- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
accelerometer_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)BNO08xTestHelperinlinestatic
activity_classifier_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)BNO08xTestHelperinlinestatic
BNO08xAccuracy_to_str(BNO08xAccuracy accuracy)BNO08xTestHelperinlinestatic
BNO08xActivity_to_str(BNO08xActivity activity)BNO08xTestHelperinlinestatic
BNO08xStability_to_str(BNO08xStability stability)BNO08xTestHelperinlinestatic
calibrated_gyro_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)BNO08xTestHelperinlinestatic
call_init_config_args()BNO08xTestHelperinlinestatic
call_init_gpio()BNO08xTestHelperinlinestatic
call_init_hint_isr()BNO08xTestHelperinlinestatic
call_init_spi()BNO08xTestHelperinlinestatic
call_launch_tasks()BNO08xTestHelperinlinestatic
create_test_imu()BNO08xTestHelperinlinestatic
destroy_test_imu()BNO08xTestHelperinlinestatic
get_test_imu()BNO08xTestHelperinlinestatic
gravity_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)BNO08xTestHelperinlinestatic
gyro_integrated_rotation_vector_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)BNO08xTestHelperinlinestatic
imu_cfgBNO08xTestHelperinlineprivatestatic
imu_report_data_t typedefBNO08xTestHelper
linear_accelerometer_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)BNO08xTestHelperinlinestatic
magnetometer_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)BNO08xTestHelperinlinestatic
print_test_end_banner(const char *TEST_TAG)BNO08xTestHelperinlinestatic
print_test_msg(const char *TEST_TAG, const char *msg)BNO08xTestHelperinlinestatic
print_test_start_banner(const char *TEST_TAG)BNO08xTestHelperinlinestatic
reset_all_imu_data_to_test_defaults()BNO08xTestHelperinlinestatic
rotation_vector_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)BNO08xTestHelperinlinestatic
set_test_imu_cfg(bno08x_config_t cfg)BNO08xTestHelperinlinestatic
stability_classifier_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)BNO08xTestHelperinlinestatic
step_counter_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)BNO08xTestHelperinlinestatic
TAGBNO08xTestHelperprivatestatic
test_imuBNO08xTestHelperinlineprivatestatic
uncalibrated_gyro_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)BNO08xTestHelperinlinestatic
update_report_data(imu_report_data_t *report_data)BNO08xTestHelperinlinestatic
-
- - - - diff --git a/documentation/html/class_b_n_o08x_test_helper.html b/documentation/html/class_b_n_o08x_test_helper.html deleted file mode 100644 index 3437f2c..0000000 --- a/documentation/html/class_b_n_o08x_test_helper.html +++ /dev/null @@ -1,2124 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08xTestHelper Class Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- - -
- -

BNO08x unit test helper class. - More...

- -

#include <BNO08xTestHelper.hpp>

-
-Collaboration diagram for BNO08xTestHelper:
-
-
Collaboration graph
- - - - - - - - - - - - -
[legend]
- - - - - -

-Classes

struct  imu_report_data_t
 IMU configuration settings passed into constructor. More...
 
- - - - -

-Public Types

typedef struct BNO08xTestHelper::imu_report_data_t imu_report_data_t
 IMU configuration settings passed into constructor.
 
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

-Static Public Member Functions

static void print_test_start_banner (const char *TEST_TAG)
 Prints test begin banner.
 
static void print_test_end_banner (const char *TEST_TAG)
 Prints end begin banner.
 
static void print_test_msg (const char *TEST_TAG, const char *msg)
 Prints a message during a test.
 
static void set_test_imu_cfg (bno08x_config_t cfg)
 Set test imu configuration used with create_test_imu()
 
static void create_test_imu ()
 Calls BNO08x constructor and creates new test IMU on heap.
 
static void destroy_test_imu ()
 Deletes test IMU calling deconstructor and releases heap allocated memory.
 
static BNO08xget_test_imu ()
 Deletes test IMU calling deconstructor and releases heap allocated memory.
 
static esp_err_t call_init_config_args ()
 Used to call private BNO08x::init_config_args() member for tests.
 
static esp_err_t call_init_gpio ()
 Used to call private BNO08x::init_gpio() member for tests.
 
static esp_err_t call_init_hint_isr ()
 Used to call private BNO08x::init_hint_isr() member for tests.
 
static esp_err_t call_init_spi ()
 Used to call private BNO08x::init_spi() member for tests.
 
static esp_err_t call_launch_tasks ()
 Used to call private BNO08x::launch_tasks() member for tests.
 
static bool rotation_vector_data_is_new (imu_report_data_t *report_data, imu_report_data_t *default_report_data)
 Checks if report_data matches the default states stored within prev_report_data data for respective report.
 
static bool gyro_integrated_rotation_vector_data_is_new (imu_report_data_t *report_data, imu_report_data_t *default_report_data)
 Checks if report_data matches the default states stored within prev_report_data data for respective report.
 
static bool uncalibrated_gyro_data_is_new (imu_report_data_t *report_data, imu_report_data_t *default_report_data)
 Checks if report_data matches the default states stored within prev_report_data data for respective report.
 
static bool calibrated_gyro_data_is_new (imu_report_data_t *report_data, imu_report_data_t *default_report_data)
 Checks if report_data matches the default states stored within prev_report_data data for respective report.
 
static bool accelerometer_data_is_new (imu_report_data_t *report_data, imu_report_data_t *default_report_data)
 Checks if report_data matches the default states stored within prev_report_data data for respective report.
 
static bool linear_accelerometer_data_is_new (imu_report_data_t *report_data, imu_report_data_t *default_report_data)
 Checks if report_data matches the default states stored within prev_report_data data for respective report.
 
static bool gravity_data_is_new (imu_report_data_t *report_data, imu_report_data_t *default_report_data)
 Checks if report_data matches the default states stored within prev_report_data data for respective report.
 
static bool magnetometer_data_is_new (imu_report_data_t *report_data, imu_report_data_t *default_report_data)
 Checks if report_data matches the default states stored within prev_report_data data for respective report.
 
static bool step_counter_data_is_new (imu_report_data_t *report_data, imu_report_data_t *default_report_data)
 Checks if report_data matches the default states stored within prev_report_data data for respective report.
 
static bool stability_classifier_data_is_new (imu_report_data_t *report_data, imu_report_data_t *default_report_data)
 Checks if report_data matches the default states stored within prev_report_data data for respective report.
 
static bool activity_classifier_data_is_new (imu_report_data_t *report_data, imu_report_data_t *default_report_data)
 Checks if report_data matches the default states stored within prev_report_data data for respective report.
 
static void update_report_data (imu_report_data_t *report_data)
 Updates report data with calls relevant test_imu methods.
 
static void reset_all_imu_data_to_test_defaults ()
 Resets internal test imu data with test defaults.
 
static const char * BNO08xAccuracy_to_str (BNO08xAccuracy accuracy)
 Converts BNO08xAccuracy enum class object to string.
 
static const char * BNO08xStability_to_str (BNO08xStability stability)
 Converts BNO08xStability enum class object to string.
 
static const char * BNO08xActivity_to_str (BNO08xActivity activity)
 Converts BNO08xActivity enum class object to string.
 
- - - - - - - -

-Static Private Attributes

static BNO08xtest_imu = nullptr
 
static bno08x_config_t imu_cfg
 
static const constexpr char * TAG = "BNO08xTestHelper"
 
-

Detailed Description

-

BNO08x unit test helper class.

-

Member Typedef Documentation

- -

◆ imu_report_data_t

- -
-
- - - - -
typedef struct BNO08xTestHelper::imu_report_data_t BNO08xTestHelper::imu_report_data_t
-
- -

IMU configuration settings passed into constructor.

- -
-
-

Member Function Documentation

- -

◆ accelerometer_data_is_new()

- -
-
- - - - - -
- - - - - - - - - - - -
static bool BNO08xTestHelper::accelerometer_data_is_new (imu_report_data_t * report_data,
imu_report_data_t * default_report_data )
-
-inlinestatic
-
- -

Checks if report_data matches the default states stored within prev_report_data data for respective report.

-
Parameters
- - - -
report_dataCurrent report data.
default_report_dataDefault report data to compare (should always contain default values)
-
-
-
Returns
True if new data was received for respective report.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ activity_classifier_data_is_new()

- -
-
- - - - - -
- - - - - - - - - - - -
static bool BNO08xTestHelper::activity_classifier_data_is_new (imu_report_data_t * report_data,
imu_report_data_t * default_report_data )
-
-inlinestatic
-
- -

Checks if report_data matches the default states stored within prev_report_data data for respective report.

-
Parameters
- - - -
report_dataCurrent report data.
default_report_dataDefault report data to compare (should always contain default values)
-
-
-
Returns
True if new data was received for respective report.
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ BNO08xAccuracy_to_str()

- -
-
- - - - - -
- - - - - - - -
static const char * BNO08xTestHelper::BNO08xAccuracy_to_str (BNO08xAccuracy accuracy)
-
-inlinestatic
-
- -

Converts BNO08xAccuracy enum class object to string.

-
Parameters
- - -
report_dataBNO08xAccuracy object to convert to string.
-
-
-
Returns
The resulting string conversion.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ BNO08xActivity_to_str()

- -
-
- - - - - -
- - - - - - - -
static const char * BNO08xTestHelper::BNO08xActivity_to_str (BNO08xActivity activity)
-
-inlinestatic
-
- -

Converts BNO08xActivity enum class object to string.

-
Parameters
- - -
activityBNO08xActivity object to convert to string.
-
-
-
Returns
The resulting string conversion.
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ BNO08xStability_to_str()

- -
-
- - - - - -
- - - - - - - -
static const char * BNO08xTestHelper::BNO08xStability_to_str (BNO08xStability stability)
-
-inlinestatic
-
- -

Converts BNO08xStability enum class object to string.

-
Parameters
- - -
stabilityBNO08xStability object to convert to string.
-
-
-
Returns
The resulting string conversion.
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ calibrated_gyro_data_is_new()

- -
-
- - - - - -
- - - - - - - - - - - -
static bool BNO08xTestHelper::calibrated_gyro_data_is_new (imu_report_data_t * report_data,
imu_report_data_t * default_report_data )
-
-inlinestatic
-
- -

Checks if report_data matches the default states stored within prev_report_data data for respective report.

-
Parameters
- - - -
report_dataCurrent report data.
default_report_dataDefault report data to compare (should always contain default values)
-
-
-
Returns
True if new data was received for respective report.
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ call_init_config_args()

- -
-
- - - - - -
- - - - - - - -
static esp_err_t BNO08xTestHelper::call_init_config_args ()
-
-inlinestatic
-
- -

Used to call private BNO08x::init_config_args() member for tests.

-
Returns
ESP_OK if init succeeded.
-
-Here is the call graph for this function:
-
-
- - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ call_init_gpio()

- -
-
- - - - - -
- - - - - - - -
static esp_err_t BNO08xTestHelper::call_init_gpio ()
-
-inlinestatic
-
- -

Used to call private BNO08x::init_gpio() member for tests.

-
Returns
ESP_OK if init succeeded.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ call_init_hint_isr()

- -
-
- - - - - -
- - - - - - - -
static esp_err_t BNO08xTestHelper::call_init_hint_isr ()
-
-inlinestatic
-
- -

Used to call private BNO08x::init_hint_isr() member for tests.

-
Returns
ESP_OK if init succeeded.
-
-Here is the call graph for this function:
-
-
- - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ call_init_spi()

- -
-
- - - - - -
- - - - - - - -
static esp_err_t BNO08xTestHelper::call_init_spi ()
-
-inlinestatic
-
- -

Used to call private BNO08x::init_spi() member for tests.

-
Returns
ESP_OK if init succeeded.
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ call_launch_tasks()

- -
-
- - - - - -
- - - - - - - -
static esp_err_t BNO08xTestHelper::call_launch_tasks ()
-
-inlinestatic
-
- -

Used to call private BNO08x::launch_tasks() member for tests.

-
Returns
ESP_OK if init succeeded.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ create_test_imu()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestHelper::create_test_imu ()
-
-inlinestatic
-
- -

Calls BNO08x constructor and creates new test IMU on heap.

-
Returns
void, nothing to return
-
-Here is the call graph for this function:
-
-
- - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - -
- -
-
- -

◆ destroy_test_imu()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestHelper::destroy_test_imu ()
-
-inlinestatic
-
- -

Deletes test IMU calling deconstructor and releases heap allocated memory.

-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ get_test_imu()

- -
-
- - - - - -
- - - - - - - -
static BNO08x * BNO08xTestHelper::get_test_imu ()
-
-inlinestatic
-
- -

Deletes test IMU calling deconstructor and releases heap allocated memory.

-
Returns
Pointer to BNO08x IMU object to test.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ gravity_data_is_new()

- -
-
- - - - - -
- - - - - - - - - - - -
static bool BNO08xTestHelper::gravity_data_is_new (imu_report_data_t * report_data,
imu_report_data_t * default_report_data )
-
-inlinestatic
-
- -

Checks if report_data matches the default states stored within prev_report_data data for respective report.

-
Parameters
- - - -
report_dataCurrent report data.
default_report_dataDefault report data to compare (should always contain default values)
-
-
-
Returns
True if new data was received for respective report.
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ gyro_integrated_rotation_vector_data_is_new()

- -
-
- - - - - -
- - - - - - - - - - - -
static bool BNO08xTestHelper::gyro_integrated_rotation_vector_data_is_new (imu_report_data_t * report_data,
imu_report_data_t * default_report_data )
-
-inlinestatic
-
- -

Checks if report_data matches the default states stored within prev_report_data data for respective report.

-
Parameters
- - - -
report_dataCurrent report data.
default_report_dataDefault report data to compare (should always contain default values)
-
-
-
Returns
True if new data was received for respective report.
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ linear_accelerometer_data_is_new()

- -
-
- - - - - -
- - - - - - - - - - - -
static bool BNO08xTestHelper::linear_accelerometer_data_is_new (imu_report_data_t * report_data,
imu_report_data_t * default_report_data )
-
-inlinestatic
-
- -

Checks if report_data matches the default states stored within prev_report_data data for respective report.

-
Parameters
- - - -
report_dataCurrent report data.
default_report_dataDefault report data to compare (should always contain default values)
-
-
-
Returns
True if new data was received for respective report.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ magnetometer_data_is_new()

- -
-
- - - - - -
- - - - - - - - - - - -
static bool BNO08xTestHelper::magnetometer_data_is_new (imu_report_data_t * report_data,
imu_report_data_t * default_report_data )
-
-inlinestatic
-
- -

Checks if report_data matches the default states stored within prev_report_data data for respective report.

-
Parameters
- - - -
report_dataCurrent report data.
default_report_dataDefault report data to compare (should always contain default values)
-
-
-
Returns
True if new data was received for respective report.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - -
- -
-
- -

◆ print_test_end_banner()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestHelper::print_test_end_banner (const char * TEST_TAG)
-
-inlinestatic
-
- -

Prints end begin banner.

-
Parameters
- - -
TEST_TAGString containing test name.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ print_test_msg()

- -
-
- - - - - -
- - - - - - - - - - - -
BNO08xTestHelper::print_test_msg (const char * TEST_TAG,
const char * msg )
-
-inlinestatic
-
- -

Prints a message during a test.

-
Parameters
- - - -
TEST_TAGString containing test name.
msgString containing message to print.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ print_test_start_banner()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestHelper::print_test_start_banner (const char * TEST_TAG)
-
-inlinestatic
-
- -

Prints test begin banner.

-
Parameters
- - -
TEST_TAGString containing test name.
-
-
-
Returns
void, nothing to return
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ reset_all_imu_data_to_test_defaults()

- -
-
- - - - - -
- - - - - - - -
BNO08xTestHelper::reset_all_imu_data_to_test_defaults ()
-
-inlinestatic
-
- -

Resets internal test imu data with test defaults.

-
Returns
void, nothing to return.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ rotation_vector_data_is_new()

- -
-
- - - - - -
- - - - - - - - - - - -
static bool BNO08xTestHelper::rotation_vector_data_is_new (imu_report_data_t * report_data,
imu_report_data_t * default_report_data )
-
-inlinestatic
-
- -

Checks if report_data matches the default states stored within prev_report_data data for respective report.

-
Parameters
- - - -
report_dataCurrent report data.
default_report_dataDefault report data to compare (should always contain default values)
-
-
-
Returns
True if new data was received for respective report.
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - -
- -
-
- -

◆ set_test_imu_cfg()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestHelper::set_test_imu_cfg (bno08x_config_t cfg)
-
-inlinestatic
-
- -

Set test imu configuration used with create_test_imu()

-
Parameters
- - -
cfgString containing test name.
-
-
-
Returns
void, nothing to return
- -
-
- -

◆ stability_classifier_data_is_new()

- -
-
- - - - - -
- - - - - - - - - - - -
static bool BNO08xTestHelper::stability_classifier_data_is_new (imu_report_data_t * report_data,
imu_report_data_t * default_report_data )
-
-inlinestatic
-
- -

Checks if report_data matches the default states stored within prev_report_data data for respective report.

-
Parameters
- - - -
report_dataCurrent report data.
default_report_dataDefault report data to compare (should always contain default values)
-
-
-
Returns
True if new data was received for respective report.
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ step_counter_data_is_new()

- -
-
- - - - - -
- - - - - - - - - - - -
static bool BNO08xTestHelper::step_counter_data_is_new (imu_report_data_t * report_data,
imu_report_data_t * default_report_data )
-
-inlinestatic
-
- -

Checks if report_data matches the default states stored within prev_report_data data for respective report.

-
Parameters
- - - -
report_dataCurrent report data.
default_report_dataDefault report data to compare (should always contain default values)
-
-
-
Returns
True if new data was received for respective report.
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ uncalibrated_gyro_data_is_new()

- -
-
- - - - - -
- - - - - - - - - - - -
static bool BNO08xTestHelper::uncalibrated_gyro_data_is_new (imu_report_data_t * report_data,
imu_report_data_t * default_report_data )
-
-inlinestatic
-
- -

Checks if report_data matches the default states stored within prev_report_data data for respective report.

-
Parameters
- - - -
report_dataCurrent report data.
default_report_dataDefault report data to compare (should always contain default values)
-
-
-
Returns
True if new data was received for respective report.
-
-Here is the caller graph for this function:
-
-
- - - - - - - -
- -
-
- -

◆ update_report_data()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestHelper::update_report_data (imu_report_data_t * report_data)
-
-inlinestatic
-
- -

Updates report data with calls relevant test_imu methods.

-
Parameters
- - -
report_dataPointer to imu_report_data_t struct to save report data.
-
-
-
Returns
void, noting to return.
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
- -
-
-

Member Data Documentation

- -

◆ imu_cfg

- -
-
- - - - - -
- - - - -
bno08x_config_t BNO08xTestHelper::imu_cfg
-
-inlinestaticprivate
-
- -
-
- -

◆ TAG

- -
-
- - - - - -
- - - - -
const constexpr char* BNO08xTestHelper::TAG = "BNO08xTestHelper"
-
-staticconstexprprivate
-
- -
-
- -

◆ test_imu

- -
-
- - - - - -
- - - - -
BNO08x* BNO08xTestHelper::test_imu = nullptr
-
-inlinestaticprivate
-
- -
-
-
The documentation for this class was generated from the following files: -
-
- - - - diff --git a/documentation/html/class_b_n_o08x_test_helper.js b/documentation/html/class_b_n_o08x_test_helper.js deleted file mode 100644 index ffe6c11..0000000 --- a/documentation/html/class_b_n_o08x_test_helper.js +++ /dev/null @@ -1,36 +0,0 @@ -var class_b_n_o08x_test_helper = -[ - [ "imu_report_data_t", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html", "struct_b_n_o08x_test_helper_1_1imu__report__data__t" ], - [ "imu_report_data_t", "class_b_n_o08x_test_helper.html#a0b3d9379e670b0c532ba76801cfb7580", null ], - [ "accelerometer_data_is_new", "class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea", null ], - [ "activity_classifier_data_is_new", "class_b_n_o08x_test_helper.html#afc6cc734ad843aca30a7cb76ad6dedb9", null ], - [ "BNO08xAccuracy_to_str", "class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3", null ], - [ "BNO08xActivity_to_str", "class_b_n_o08x_test_helper.html#ac95ba2892d54e6219123ad3ca0104750", null ], - [ "BNO08xStability_to_str", "class_b_n_o08x_test_helper.html#ae922f36719ab085550ef270d5a149059", null ], - [ "calibrated_gyro_data_is_new", "class_b_n_o08x_test_helper.html#a084e65ff5c0e2f429b39ebb53b0e03c9", null ], - [ "call_init_config_args", "class_b_n_o08x_test_helper.html#a71d9fd7d459a98a7e9089a8587a21f8d", null ], - [ "call_init_gpio", "class_b_n_o08x_test_helper.html#a504749533ccd91890d73440809d38161", null ], - [ "call_init_hint_isr", "class_b_n_o08x_test_helper.html#a836c928981ac85d34668c9b97af17a15", null ], - [ "call_init_spi", "class_b_n_o08x_test_helper.html#a7d2d784da1e850dab41154b35d7cdab5", null ], - [ "call_launch_tasks", "class_b_n_o08x_test_helper.html#adf2488d1f7e3dec21a0d0c99417c181a", null ], - [ "create_test_imu", "class_b_n_o08x_test_helper.html#a6bd040c7d670a9713f2ab8a8a3913518", null ], - [ "destroy_test_imu", "class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40", null ], - [ "get_test_imu", "class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b", null ], - [ "gravity_data_is_new", "class_b_n_o08x_test_helper.html#a3c2514f3bad3f091de4646c5798f487a", null ], - [ "gyro_integrated_rotation_vector_data_is_new", "class_b_n_o08x_test_helper.html#ac5b0ac4c70bbfcba9f2e8f353b35f9f6", null ], - [ "linear_accelerometer_data_is_new", "class_b_n_o08x_test_helper.html#ad398739ce46400c1ac35e1cf7603d590", null ], - [ "magnetometer_data_is_new", "class_b_n_o08x_test_helper.html#a157342da2def8b659d27ae4d24063cb5", null ], - [ "print_test_end_banner", "class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919", null ], - [ "print_test_msg", "class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002", null ], - [ "print_test_start_banner", "class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885", null ], - [ "reset_all_imu_data_to_test_defaults", "class_b_n_o08x_test_helper.html#ade6be1fd8ef3a99e0edae4cbf25eb528", null ], - [ "rotation_vector_data_is_new", "class_b_n_o08x_test_helper.html#aeb8cd985faf8e403f62b60fced9cb2fd", null ], - [ "set_test_imu_cfg", "class_b_n_o08x_test_helper.html#a9e2f9bf13f28f1a6ba87e86bc5947cf1", null ], - [ "stability_classifier_data_is_new", "class_b_n_o08x_test_helper.html#a95ed21657224358877a66d010eeefad3", null ], - [ "step_counter_data_is_new", "class_b_n_o08x_test_helper.html#aa7eb152d4192c3949bb3443ef6221782", null ], - [ "uncalibrated_gyro_data_is_new", "class_b_n_o08x_test_helper.html#adb5952b2b96b553024b6a841e30adad2", null ], - [ "update_report_data", "class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2", null ], - [ "imu_cfg", "class_b_n_o08x_test_helper.html#a008b268f705b9d2925230cb8193c9f28", null ], - [ "TAG", "class_b_n_o08x_test_helper.html#aa09d388a5da3a925ac25125b9c5c3a90", null ], - [ "test_imu", "class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243", null ] -]; \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper__coll__graph.map b/documentation/html/class_b_n_o08x_test_helper__coll__graph.map deleted file mode 100644 index f40afaf..0000000 --- a/documentation/html/class_b_n_o08x_test_helper__coll__graph.map +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper__coll__graph.md5 b/documentation/html/class_b_n_o08x_test_helper__coll__graph.md5 deleted file mode 100644 index da75ef9..0000000 --- a/documentation/html/class_b_n_o08x_test_helper__coll__graph.md5 +++ /dev/null @@ -1 +0,0 @@ -ea36b22d41692eb60413ee8b2c2c3d15 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper__coll__graph.png b/documentation/html/class_b_n_o08x_test_helper__coll__graph.png deleted file mode 100644 index bb64f72..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper__coll__graph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.map deleted file mode 100644 index 91a42df..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.map +++ /dev/null @@ -1,47 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.md5 deleted file mode 100644 index 9d5f97b..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -929f70b49107e6f743bd2b25aef20442 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.png deleted file mode 100644 index 5bb8843..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.map deleted file mode 100644 index 03febcc..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.md5 deleted file mode 100644 index 05bd7f3..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5d347cbcdf6782d5dd02b8b0f05260fb \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.png deleted file mode 100644 index 537d016..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.map deleted file mode 100644 index ff59f0e..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.md5 deleted file mode 100644 index d0cdc67..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0bcb67872d4562cf2df04c288f7aa7cd \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.png deleted file mode 100644 index 25a7f34..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.map deleted file mode 100644 index 1b708f9..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.map +++ /dev/null @@ -1,47 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.md5 deleted file mode 100644 index 87fa807..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0cf5402b986021f18d727abfd8016780 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.png deleted file mode 100644 index 02d0be1..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.map deleted file mode 100644 index 36f84f0..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.md5 deleted file mode 100644 index 02112bf..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -32c9449332f4804e5633bd3dfeb32871 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.png deleted file mode 100644 index 54659f0..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.map deleted file mode 100644 index 16d406d..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.map +++ /dev/null @@ -1,61 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.md5 deleted file mode 100644 index bf7bcbc..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ff372568fae4ebdee6e2df3cca8caa7b \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.png deleted file mode 100644 index 903f173..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.map b/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.map deleted file mode 100644 index 55b9cff..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.map +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.md5 deleted file mode 100644 index 8a6aca2..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -52a9f26639833730e81baae3be78ef17 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.png b/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.png deleted file mode 100644 index c7d45e5..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.map deleted file mode 100644 index 3c9b86c..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.md5 deleted file mode 100644 index fbcf6f6..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e0950be8c1d6d65b00e3acb1e321f9a0 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.png deleted file mode 100644 index 132c8bf..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.map b/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.map deleted file mode 100644 index 8a9ee79..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.md5 deleted file mode 100644 index db93a71..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -68570fdd8c4d782a541d8277bfc4ff57 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.png b/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.png deleted file mode 100644 index 2108765..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.map deleted file mode 100644 index 5793d63..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.map +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.md5 deleted file mode 100644 index 1dd6dfe..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -40323e79da4ab8f8a0adb1699baaa3b1 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.png deleted file mode 100644 index ae9cfff..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.map b/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.map deleted file mode 100644 index df11287..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.md5 deleted file mode 100644 index e72022e..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -54d426e96d3047aae911ab549a5a689c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.png b/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.png deleted file mode 100644 index 1e57127..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.map deleted file mode 100644 index c042478..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.md5 deleted file mode 100644 index e1c5ac7..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -52a677be9a64f05d5f299bda062dcb97 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.png deleted file mode 100644 index 0d09190..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.map b/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.map deleted file mode 100644 index b8cb5ce..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.md5 deleted file mode 100644 index ed57cad..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8aa2c3c71dab4f843166e8b1b78e5004 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.png b/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.png deleted file mode 100644 index de5a353..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.map deleted file mode 100644 index b7c341c..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.md5 deleted file mode 100644 index ca9e3bb..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -33f6d60f00f0c5091378a8a6cf302589 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.png deleted file mode 100644 index 65c1454..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.map deleted file mode 100644 index cc156d3..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.map +++ /dev/null @@ -1,63 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.md5 deleted file mode 100644 index 251cc15..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d783aad4e4c62a55f974f8033b68e579 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.png deleted file mode 100644 index da3e1fa..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.map b/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.map deleted file mode 100644 index 62bdbdf..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.md5 deleted file mode 100644 index 2e1b184..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3d8cf9e96b0a20b22925d2ae45465aa0 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.png b/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.png deleted file mode 100644 index faba6ff..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.map deleted file mode 100644 index 8b8291c..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.md5 deleted file mode 100644 index fa0ffce..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b84805ece6d4f69c9554fd020b0494fe \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.png deleted file mode 100644 index d57dca7..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.map deleted file mode 100644 index 69d098a..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.map +++ /dev/null @@ -1,33 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.md5 deleted file mode 100644 index db711ab..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b5fadda6a94b649eda865adcb1109cbf \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.png deleted file mode 100644 index b55f5b7..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.map deleted file mode 100644 index 8d2d26b..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.md5 deleted file mode 100644 index 1fdc4ed..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -37a3bb920c6175e21972e66ef5c0e6de \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.png deleted file mode 100644 index cc5e4a2..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.map deleted file mode 100644 index 010b420..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.md5 deleted file mode 100644 index 8c9a5ce..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -afe7f0dcf9b24f722ad5e90a5953aa47 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.png deleted file mode 100644 index 1a3e461..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.map deleted file mode 100644 index 27afdb6..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.md5 deleted file mode 100644 index f60a979..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ad8aa227e9c87c9d515f875ec2578d8f \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.png deleted file mode 100644 index 01133fd..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.map b/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.map deleted file mode 100644 index 3b6e4c5..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.map +++ /dev/null @@ -1,36 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.md5 deleted file mode 100644 index e0939ba..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d90879cdfd0dfc8baf520aa3f5c22584 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.png b/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.png deleted file mode 100644 index e990206..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.map deleted file mode 100644 index 04e9e0a..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.map +++ /dev/null @@ -1,49 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.md5 deleted file mode 100644 index bb68fcf..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -17bae161af122303ff2c5c4a1875ea10 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.png deleted file mode 100644 index 9a9f5ae..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.map deleted file mode 100644 index a2780a6..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.md5 deleted file mode 100644 index f0b2001..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -16628eb240625d0f4e13bcdfc0c1d9da \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.png deleted file mode 100644 index 01fd5eb..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.map deleted file mode 100644 index ad9f3cb..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.md5 deleted file mode 100644 index 296b04b..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -884648d7a402c12cd945a6316bd269a0 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.png deleted file mode 100644 index e0bcefd..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.map deleted file mode 100644 index d1687a0..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.md5 deleted file mode 100644 index 565e778..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fb36bc7b62a5730a3eef34d35b773e8e \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.png deleted file mode 100644 index 10ddff4..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.map deleted file mode 100644 index e163091..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.map +++ /dev/null @@ -1,45 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.md5 deleted file mode 100644 index 465f782..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ade3d82b27b4c54524354cc1d1a5535c \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.png deleted file mode 100644 index a92a1b0..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.map deleted file mode 100644 index ff12fc0..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.map +++ /dev/null @@ -1,19 +0,0 @@ - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.md5 deleted file mode 100644 index f1390bb..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -58ebbbda7f41d0d5583a6926ada7f36f \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.png deleted file mode 100644 index 90ebb85..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.map b/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.map deleted file mode 100644 index 4f0a68a..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.map +++ /dev/null @@ -1,71 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.md5 deleted file mode 100644 index f532eec..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -bf2261d9da9f3a76d4a283e8c5a53136 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.png b/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.png deleted file mode 100644 index ef2fc4a..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.map deleted file mode 100644 index dcd21bb..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.md5 deleted file mode 100644 index e4e83e4..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f5644353d2fccb7d8470f7184a2bca27 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.png deleted file mode 100644 index 5234ddf..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.map deleted file mode 100644 index f8a52ba..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.map +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.md5 deleted file mode 100644 index 1ee405a..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0fdf59a7c6eae912be523cacfc5c5916 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.png deleted file mode 100644 index 239a17d..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.map deleted file mode 100644 index 26721da..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.md5 deleted file mode 100644 index 0305cbb..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6fd176067fe6301ba4095fa970596d8f \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.png deleted file mode 100644 index 5b8b1af..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.map deleted file mode 100644 index f8acd2a..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.map +++ /dev/null @@ -1,15 +0,0 @@ - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.md5 deleted file mode 100644 index 69cc16e..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -63270f468ff9daff9a520064e665b79a \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.png deleted file mode 100644 index a4f597a..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.map b/documentation/html/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.map deleted file mode 100644 index c3739e4..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.md5 b/documentation/html/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.md5 deleted file mode 100644 index b397b75..0000000 --- a/documentation/html/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c07500fd8e06d59a3f6499e103d9c738 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.png b/documentation/html/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.png deleted file mode 100644 index 67be48b..0000000 Binary files a/documentation/html/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_suite-members.html b/documentation/html/class_b_n_o08x_test_suite-members.html deleted file mode 100644 index 28bd5aa..0000000 --- a/documentation/html/class_b_n_o08x_test_suite-members.html +++ /dev/null @@ -1,117 +0,0 @@ - - - - - - - -esp32_BNO08x: Member List - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
BNO08xTestSuite Member List
-
-
- -

This is the complete list of members for BNO08xTestSuite, including all inherited members.

- - - - - - - - -
print_begin_tests_banner(const char *test_set_name)BNO08xTestSuiteinlineprivatestatic
print_end_tests_banner(const char *test_set_name)BNO08xTestSuiteinlineprivatestatic
run_all_tests()BNO08xTestSuiteinlinestatic
run_callback_tests(bool call_unity_end_begin=true)BNO08xTestSuiteinlinestatic
run_init_deinit_tests(bool call_unity_end_begin=true)BNO08xTestSuiteinlinestatic
run_multi_report_tests(bool call_unity_end_begin=true)BNO08xTestSuiteinlinestatic
run_single_report_tests(bool call_unity_end_begin=true)BNO08xTestSuiteinlinestatic
-
- - - - diff --git a/documentation/html/class_b_n_o08x_test_suite.html b/documentation/html/class_b_n_o08x_test_suite.html deleted file mode 100644 index 749c8e0..0000000 --- a/documentation/html/class_b_n_o08x_test_suite.html +++ /dev/null @@ -1,475 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08xTestSuite Class Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- - -
- -

BNO08x unit test launch point class. - More...

- -

#include <BNO08xTestSuite.hpp>

- - - - - - - - - - - - -

-Static Public Member Functions

static void run_all_tests ()
 
static void run_init_deinit_tests (bool call_unity_end_begin=true)
 
static void run_single_report_tests (bool call_unity_end_begin=true)
 
static void run_multi_report_tests (bool call_unity_end_begin=true)
 
static void run_callback_tests (bool call_unity_end_begin=true)
 
- - - - - -

-Static Private Member Functions

static void print_begin_tests_banner (const char *test_set_name)
 
static void print_end_tests_banner (const char *test_set_name)
 
-

Detailed Description

-

BNO08x unit test launch point class.

-

Member Function Documentation

- -

◆ print_begin_tests_banner()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestSuite::print_begin_tests_banner (const char * test_set_name)
-
-inlinestaticprivate
-
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - -
- -
-
- -

◆ print_end_tests_banner()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestSuite::print_end_tests_banner (const char * test_set_name)
-
-inlinestaticprivate
-
-
-Here is the caller graph for this function:
-
-
- - - - - - - - - - - - - - - - -
- -
-
- -

◆ run_all_tests()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestSuite::run_all_tests ()
-
-inlinestatic
-
-
-Here is the call graph for this function:
-
-
- - - - - - - - - - - - - - - - - - - - - -
- -
-
- -

◆ run_callback_tests()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestSuite::run_callback_tests (bool call_unity_end_begin = true)
-
-inlinestatic
-
-
-Here is the call graph for this function:
-
-
- - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ run_init_deinit_tests()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestSuite::run_init_deinit_tests (bool call_unity_end_begin = true)
-
-inlinestatic
-
-
-Here is the call graph for this function:
-
-
- - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ run_multi_report_tests()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestSuite::run_multi_report_tests (bool call_unity_end_begin = true)
-
-inlinestatic
-
-
-Here is the call graph for this function:
-
-
- - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
- -

◆ run_single_report_tests()

- -
-
- - - - - -
- - - - - - - -
static void BNO08xTestSuite::run_single_report_tests (bool call_unity_end_begin = true)
-
-inlinestatic
-
-
-Here is the call graph for this function:
-
-
- - - - - - - -
-
-Here is the caller graph for this function:
-
-
- - - - - -
- -
-
-
The documentation for this class was generated from the following file: -
-
- - - - diff --git a/documentation/html/class_b_n_o08x_test_suite.js b/documentation/html/class_b_n_o08x_test_suite.js deleted file mode 100644 index 0ed939e..0000000 --- a/documentation/html/class_b_n_o08x_test_suite.js +++ /dev/null @@ -1,10 +0,0 @@ -var class_b_n_o08x_test_suite = -[ - [ "print_begin_tests_banner", "class_b_n_o08x_test_suite.html#a2fea3ea192a63c9573c774e772f5c085", null ], - [ "print_end_tests_banner", "class_b_n_o08x_test_suite.html#a5a9b6538773911afed92b16c435ebceb", null ], - [ "run_all_tests", "class_b_n_o08x_test_suite.html#ac12545fe311a98e9c0ae6fea77da95fd", null ], - [ "run_callback_tests", "class_b_n_o08x_test_suite.html#a8e294955bf512e2e88c086f04f6030a8", null ], - [ "run_init_deinit_tests", "class_b_n_o08x_test_suite.html#a53de9b0fe1b28c18e3a1ca4c68a06f16", null ], - [ "run_multi_report_tests", "class_b_n_o08x_test_suite.html#a916cff374791381de61f1035f9935ac5", null ], - [ "run_single_report_tests", "class_b_n_o08x_test_suite.html#a37899d7bf67fce5c3dd77dd5647f8ecb", null ] -]; \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.map b/documentation/html/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.map deleted file mode 100644 index 699192b..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.map +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.md5 b/documentation/html/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.md5 deleted file mode 100644 index ddd7d27..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8a9c5c01e2035b179268b33448d97022 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.png b/documentation/html/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.png deleted file mode 100644 index 826a4a8..0000000 Binary files a/documentation/html/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.map b/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.map deleted file mode 100644 index 4a0f6c6..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.md5 b/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.md5 deleted file mode 100644 index c021696..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -26c0603aa734a9b4e09c9bc29c8542b3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.png b/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.png deleted file mode 100644 index 5c878d8..0000000 Binary files a/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.map b/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.map deleted file mode 100644 index e9ead4d..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.md5 b/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.md5 deleted file mode 100644 index a1f0d59..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -72a44846327a36caccbde60dacafb29a \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.png b/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.png deleted file mode 100644 index d0e162f..0000000 Binary files a/documentation/html/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.map b/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.map deleted file mode 100644 index b2e60e5..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.md5 b/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.md5 deleted file mode 100644 index 5610b2f..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -57d12b3b014497b0a06f21b3c72d46a4 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.png b/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.png deleted file mode 100644 index 68f047a..0000000 Binary files a/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.map b/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.map deleted file mode 100644 index 7514d4c..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.md5 b/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.md5 deleted file mode 100644 index 40bdf3d..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -303c64824171de1e5e2eb7dbfd7a3c37 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.png b/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.png deleted file mode 100644 index 0548e10..0000000 Binary files a/documentation/html/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.map b/documentation/html/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.map deleted file mode 100644 index 7fe80cd..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.map +++ /dev/null @@ -1,16 +0,0 @@ - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.md5 b/documentation/html/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.md5 deleted file mode 100644 index d50e00b..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6efa63251e5634306073f70380975116 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.png b/documentation/html/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.png deleted file mode 100644 index 3b97189..0000000 Binary files a/documentation/html/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.map b/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.map deleted file mode 100644 index 98eeeb9..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.md5 b/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.md5 deleted file mode 100644 index 6b7358a..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -df9fbe68285d277aa174d2c0d8447be4 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.png b/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.png deleted file mode 100644 index ca6e258..0000000 Binary files a/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.map b/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.map deleted file mode 100644 index 7a6eed4..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.md5 b/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.md5 deleted file mode 100644 index 0e2cc41..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7e986828034bf15fdfe5e506fb1b8dc3 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.png b/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.png deleted file mode 100644 index 2f4e040..0000000 Binary files a/documentation/html/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.map b/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.map deleted file mode 100644 index 5d18911..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.md5 b/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.md5 deleted file mode 100644 index c38a73f..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2490779b36838be0d85f9a0f4efbee69 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.png b/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.png deleted file mode 100644 index 76ce394..0000000 Binary files a/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.map b/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.map deleted file mode 100644 index 9a70ca3..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.md5 b/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.md5 deleted file mode 100644 index 13bb3a5..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0f7368fb6b4d3fe98a0db5c38aca0749 \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.png b/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.png deleted file mode 100644 index 45182a1..0000000 Binary files a/documentation/html/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.png and /dev/null differ diff --git a/documentation/html/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.map b/documentation/html/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.map deleted file mode 100644 index b2487c3..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.map +++ /dev/null @@ -1,21 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.md5 b/documentation/html/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.md5 deleted file mode 100644 index 53625e2..0000000 --- a/documentation/html/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9ef7f069d10416e708fdb5a4439d149b \ No newline at end of file diff --git a/documentation/html/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.png b/documentation/html/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.png deleted file mode 100644 index 0a19a38..0000000 Binary files a/documentation/html/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.png and /dev/null differ diff --git a/documentation/html/classes.html b/documentation/html/classes.html deleted file mode 100644 index 36cf754..0000000 --- a/documentation/html/classes.html +++ /dev/null @@ -1,116 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Index - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- - - - - - diff --git a/documentation/html/clipboard.js b/documentation/html/clipboard.js deleted file mode 100644 index 42c1fb0..0000000 --- a/documentation/html/clipboard.js +++ /dev/null @@ -1,61 +0,0 @@ -/** - -The code below is based on the Doxygen Awesome project, see -https://github.com/jothepro/doxygen-awesome-css - -MIT License - -Copyright (c) 2021 - 2022 jothepro - -Permission is hereby granted, free of charge, to any person obtaining a copy -of this software and associated documentation files (the "Software"), to deal -in the Software without restriction, including without limitation the rights -to use, copy, modify, merge, publish, distribute, sublicense, and/or sell -copies of the Software, and to permit persons to whom the Software is -furnished to do so, subject to the following conditions: - -The above copyright notice and this permission notice shall be included in all -copies or substantial portions of the Software. - -THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR -IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, -FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE -AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER -LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, -OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE -SOFTWARE. - -*/ - -let clipboard_title = "Copy to clipboard" -let clipboard_icon = `` -let clipboard_successIcon = `` -let clipboard_successDuration = 1000 - -$(function() { - if(navigator.clipboard) { - const fragments = document.getElementsByClassName("fragment") - for(const fragment of fragments) { - const clipboard_div = document.createElement("div") - clipboard_div.classList.add("clipboard") - clipboard_div.innerHTML = clipboard_icon - clipboard_div.title = clipboard_title - $(clipboard_div).click(function() { - const content = this.parentNode.cloneNode(true) - // filter out line number and folded fragments from file listings - content.querySelectorAll(".lineno, .ttc, .foldclosed").forEach((node) => { node.remove() }) - let text = content.textContent - // remove trailing newlines and trailing spaces from empty lines - text = text.replace(/^\s*\n/gm,'\n').replace(/\n*$/,'') - navigator.clipboard.writeText(text); - this.classList.add("success") - this.innerHTML = clipboard_successIcon - window.setTimeout(() => { // switch back to normal icon after timeout - this.classList.remove("success") - this.innerHTML = clipboard_icon - }, clipboard_successDuration); - }) - fragment.insertBefore(clipboard_div, fragment.firstChild) - } - } -}) diff --git a/documentation/html/closed.png b/documentation/html/closed.png deleted file mode 100644 index 98cc2c9..0000000 Binary files a/documentation/html/closed.png and /dev/null differ diff --git a/documentation/html/cookie.js b/documentation/html/cookie.js deleted file mode 100644 index 53ad21d..0000000 --- a/documentation/html/cookie.js +++ /dev/null @@ -1,58 +0,0 @@ -/*! - Cookie helper functions - Copyright (c) 2023 Dimitri van Heesch - Released under MIT license. -*/ -let Cookie = { - cookie_namespace: 'doxygen_', - - readSetting(cookie,defVal) { - if (window.chrome) { - const val = localStorage.getItem(this.cookie_namespace+cookie) || - sessionStorage.getItem(this.cookie_namespace+cookie); - if (val) return val; - } else { - let myCookie = this.cookie_namespace+cookie+"="; - if (document.cookie) { - const index = document.cookie.indexOf(myCookie); - if (index != -1) { - const valStart = index + myCookie.length; - let valEnd = document.cookie.indexOf(";", valStart); - if (valEnd == -1) { - valEnd = document.cookie.length; - } - return document.cookie.substring(valStart, valEnd); - } - } - } - return defVal; - }, - - writeSetting(cookie,val,days=10*365) { // default days='forever', 0=session cookie, -1=delete - if (window.chrome) { - if (days==0) { - sessionStorage.setItem(this.cookie_namespace+cookie,val); - } else { - localStorage.setItem(this.cookie_namespace+cookie,val); - } - } else { - let date = new Date(); - date.setTime(date.getTime()+(days*24*60*60*1000)); - const expiration = days!=0 ? "expires="+date.toGMTString()+";" : ""; - document.cookie = this.cookie_namespace + cookie + "=" + - val + "; SameSite=Lax;" + expiration + "path=/"; - } - }, - - eraseSetting(cookie) { - if (window.chrome) { - if (localStorage.getItem(this.cookie_namespace+cookie)) { - localStorage.removeItem(this.cookie_namespace+cookie); - } else if (sessionStorage.getItem(this.cookie_namespace+cookie)) { - sessionStorage.removeItem(this.cookie_namespace+cookie); - } - } else { - this.writeSetting(cookie,'',-1); - } - }, -} diff --git a/documentation/html/dir_000005_000004.html b/documentation/html/dir_000005_000004.html deleted file mode 100644 index ce67578..0000000 --- a/documentation/html/dir_000005_000004.html +++ /dev/null @@ -1,105 +0,0 @@ - - - - - - - -esp32_BNO08x: source -> include Relation - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-

source → include Relation

File in imu_update/bno08x_update/components/esp32_BNO08x/sourceIncludes file in imu_update/bno08x_update/components/esp32_BNO08x/include
BNO08x.cppBNO08x.hpp
BNO08x.cppBNO08x_macros.hpp
-
- - - - diff --git a/documentation/html/dir_000006_000004.html b/documentation/html/dir_000006_000004.html deleted file mode 100644 index cafaf02..0000000 --- a/documentation/html/dir_000006_000004.html +++ /dev/null @@ -1,105 +0,0 @@ - - - - - - - -esp32_BNO08x: test -> include Relation - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-

test → include Relation

File in imu_update/bno08x_update/components/esp32_BNO08x/testIncludes file in imu_update/bno08x_update/components/esp32_BNO08x/include
CallbackTests.cppBNO08xTestHelper.hpp
InitDeinitTests.cppBNO08xTestHelper.hpp
MultiReportTests.cppBNO08xTestHelper.hpp
SingleReportTests.cppBNO08xTestHelper.hpp
-
- - - - diff --git a/documentation/html/dir_105fd1ee051c171768c94e464b88861d.html b/documentation/html/dir_105fd1ee051c171768c94e464b88861d.html deleted file mode 100644 index b8eccd4..0000000 --- a/documentation/html/dir_105fd1ee051c171768c94e464b88861d.html +++ /dev/null @@ -1,126 +0,0 @@ - - - - - - - -esp32_BNO08x: source Directory Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
source Directory Reference
-
-
-
-Directory dependency graph for source:
-
-
source
- - - - - - - -
- - - - -

-Files

 BNO08x.cpp
 
-
-
- - - - diff --git a/documentation/html/dir_105fd1ee051c171768c94e464b88861d.js b/documentation/html/dir_105fd1ee051c171768c94e464b88861d.js deleted file mode 100644 index 731e700..0000000 --- a/documentation/html/dir_105fd1ee051c171768c94e464b88861d.js +++ /dev/null @@ -1,4 +0,0 @@ -var dir_105fd1ee051c171768c94e464b88861d = -[ - [ "BNO08x.cpp", "_b_n_o08x_8cpp.html", null ] -]; \ No newline at end of file diff --git a/documentation/html/dir_105fd1ee051c171768c94e464b88861d_dep.map b/documentation/html/dir_105fd1ee051c171768c94e464b88861d_dep.map deleted file mode 100644 index dfc03d2..0000000 --- a/documentation/html/dir_105fd1ee051c171768c94e464b88861d_dep.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/dir_105fd1ee051c171768c94e464b88861d_dep.md5 b/documentation/html/dir_105fd1ee051c171768c94e464b88861d_dep.md5 deleted file mode 100644 index 07db8c0..0000000 --- a/documentation/html/dir_105fd1ee051c171768c94e464b88861d_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -76c1b7531cb9f13814675d55ea700c92 \ No newline at end of file diff --git a/documentation/html/dir_105fd1ee051c171768c94e464b88861d_dep.png b/documentation/html/dir_105fd1ee051c171768c94e464b88861d_dep.png deleted file mode 100644 index 012e2d2..0000000 Binary files a/documentation/html/dir_105fd1ee051c171768c94e464b88861d_dep.png and /dev/null differ diff --git a/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0.html b/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0.html deleted file mode 100644 index b08e010..0000000 --- a/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0.html +++ /dev/null @@ -1,132 +0,0 @@ - - - - - - - -esp32_BNO08x: test Directory Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
test Directory Reference
-
-
-
-Directory dependency graph for test:
-
-
test
- - - - - - - -
- - - - - - - - - - -

-Files

 CallbackTests.cpp
 
 InitDeinitTests.cpp
 
 MultiReportTests.cpp
 
 SingleReportTests.cpp
 
-
-
- - - - diff --git a/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0.js b/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0.js deleted file mode 100644 index 972049e..0000000 --- a/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0.js +++ /dev/null @@ -1,7 +0,0 @@ -var dir_14dea6b744ab39100edf1f9916c217e0 = -[ - [ "CallbackTests.cpp", "_callback_tests_8cpp.html", "_callback_tests_8cpp" ], - [ "InitDeinitTests.cpp", "_init_deinit_tests_8cpp.html", "_init_deinit_tests_8cpp" ], - [ "MultiReportTests.cpp", "_multi_report_tests_8cpp.html", "_multi_report_tests_8cpp" ], - [ "SingleReportTests.cpp", "_single_report_tests_8cpp.html", "_single_report_tests_8cpp" ] -]; \ No newline at end of file diff --git a/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0_dep.map b/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0_dep.map deleted file mode 100644 index 31111f0..0000000 --- a/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0_dep.map +++ /dev/null @@ -1,7 +0,0 @@ - - - - - - - diff --git a/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0_dep.md5 b/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0_dep.md5 deleted file mode 100644 index e80583d..0000000 --- a/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -65d7476f5306b5b8a6e00408a7eb7734 \ No newline at end of file diff --git a/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0_dep.png b/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0_dep.png deleted file mode 100644 index e5a06bf..0000000 Binary files a/documentation/html/dir_14dea6b744ab39100edf1f9916c217e0_dep.png and /dev/null differ diff --git a/documentation/html/dir_85e9385bd83516731053aadc7da3c8af.html b/documentation/html/dir_85e9385bd83516731053aadc7da3c8af.html deleted file mode 100644 index 14d4a9f..0000000 --- a/documentation/html/dir_85e9385bd83516731053aadc7da3c8af.html +++ /dev/null @@ -1,123 +0,0 @@ - - - - - - - -esp32_BNO08x: imu_update Directory Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
imu_update Directory Reference
-
-
-
-Directory dependency graph for imu_update:
-
-
imu_update
- - - - -
- - - - -

-Directories

 bno08x_update
 
-
-
- - - - diff --git a/documentation/html/dir_85e9385bd83516731053aadc7da3c8af.js b/documentation/html/dir_85e9385bd83516731053aadc7da3c8af.js deleted file mode 100644 index 08a618a..0000000 --- a/documentation/html/dir_85e9385bd83516731053aadc7da3c8af.js +++ /dev/null @@ -1,4 +0,0 @@ -var dir_85e9385bd83516731053aadc7da3c8af = -[ - [ "bno08x_update", "dir_c60d9bf80716f90f729fd65c40ec81f7.html", "dir_c60d9bf80716f90f729fd65c40ec81f7" ] -]; \ No newline at end of file diff --git a/documentation/html/dir_85e9385bd83516731053aadc7da3c8af_dep.map b/documentation/html/dir_85e9385bd83516731053aadc7da3c8af_dep.map deleted file mode 100644 index 84748c9..0000000 --- a/documentation/html/dir_85e9385bd83516731053aadc7da3c8af_dep.map +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/documentation/html/dir_85e9385bd83516731053aadc7da3c8af_dep.md5 b/documentation/html/dir_85e9385bd83516731053aadc7da3c8af_dep.md5 deleted file mode 100644 index a856f53..0000000 --- a/documentation/html/dir_85e9385bd83516731053aadc7da3c8af_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -685023a910c171116b6443e88b6f7bf1 \ No newline at end of file diff --git a/documentation/html/dir_85e9385bd83516731053aadc7da3c8af_dep.png b/documentation/html/dir_85e9385bd83516731053aadc7da3c8af_dep.png deleted file mode 100644 index bb6b360..0000000 Binary files a/documentation/html/dir_85e9385bd83516731053aadc7da3c8af_dep.png and /dev/null differ diff --git a/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d.html b/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d.html deleted file mode 100644 index ac9e071..0000000 --- a/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d.html +++ /dev/null @@ -1,131 +0,0 @@ - - - - - - - -esp32_BNO08x: include Directory Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
include Directory Reference
-
-
-
-Directory dependency graph for include:
-
-
include
- - - - -
- - - - - - - - - - - - -

-Files

 BNO08x.hpp
 
 BNO08x_global_types.hpp
 
 BNO08x_macros.hpp
 
 BNO08xTestHelper.hpp
 
 BNO08xTestSuite.hpp
 
-
-
- - - - diff --git a/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d.js b/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d.js deleted file mode 100644 index 2f91a7b..0000000 --- a/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d.js +++ /dev/null @@ -1,8 +0,0 @@ -var dir_9667f1a5b10a5222433e41df91e1bf5d = -[ - [ "BNO08x.hpp", "_b_n_o08x_8hpp.html", "_b_n_o08x_8hpp" ], - [ "BNO08x_global_types.hpp", "_b_n_o08x__global__types_8hpp.html", "_b_n_o08x__global__types_8hpp" ], - [ "BNO08x_macros.hpp", "_b_n_o08x__macros_8hpp.html", "_b_n_o08x__macros_8hpp" ], - [ "BNO08xTestHelper.hpp", "_b_n_o08x_test_helper_8hpp.html", "_b_n_o08x_test_helper_8hpp" ], - [ "BNO08xTestSuite.hpp", "_b_n_o08x_test_suite_8hpp.html", "_b_n_o08x_test_suite_8hpp" ] -]; \ No newline at end of file diff --git a/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.map b/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.map deleted file mode 100644 index 3fc5477..0000000 --- a/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.map +++ /dev/null @@ -1,4 +0,0 @@ - - - - diff --git a/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.md5 b/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.md5 deleted file mode 100644 index 29ab75b..0000000 --- a/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -1a959f5226a0619482e82cf08fc76c15 \ No newline at end of file diff --git a/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.png b/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.png deleted file mode 100644 index 2c33518..0000000 Binary files a/documentation/html/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.png and /dev/null differ diff --git a/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f.html b/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f.html deleted file mode 100644 index 1e6d112..0000000 --- a/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f.html +++ /dev/null @@ -1,134 +0,0 @@ - - - - - - - -esp32_BNO08x: esp32_BNO08x Directory Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
esp32_BNO08x Directory Reference
-
-
-
-Directory dependency graph for esp32_BNO08x:
-
-
esp32_BNO08x
- - - - - - - - - - - -
- - - - - - - - -

-Directories

 include
 
 source
 
 test
 
-
-
- - - - diff --git a/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f.js b/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f.js deleted file mode 100644 index 0d03481..0000000 --- a/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f.js +++ /dev/null @@ -1,6 +0,0 @@ -var dir_a6718ce9703adf4789a693642ffedf7f = -[ - [ "include", "dir_9667f1a5b10a5222433e41df91e1bf5d.html", "dir_9667f1a5b10a5222433e41df91e1bf5d" ], - [ "source", "dir_105fd1ee051c171768c94e464b88861d.html", "dir_105fd1ee051c171768c94e464b88861d" ], - [ "test", "dir_14dea6b744ab39100edf1f9916c217e0.html", "dir_14dea6b744ab39100edf1f9916c217e0" ] -]; \ No newline at end of file diff --git a/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f_dep.map b/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f_dep.map deleted file mode 100644 index 1bd0ee4..0000000 --- a/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f_dep.map +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f_dep.md5 b/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f_dep.md5 deleted file mode 100644 index 59beb8c..0000000 --- a/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -37d251802c676e8c5c4e479554df4db8 \ No newline at end of file diff --git a/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f_dep.png b/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f_dep.png deleted file mode 100644 index 3a7def8..0000000 Binary files a/documentation/html/dir_a6718ce9703adf4789a693642ffedf7f_dep.png and /dev/null differ diff --git a/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7.html b/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7.html deleted file mode 100644 index 14462c0..0000000 --- a/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7.html +++ /dev/null @@ -1,124 +0,0 @@ - - - - - - - -esp32_BNO08x: bno08x_update Directory Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
bno08x_update Directory Reference
-
-
-
-Directory dependency graph for bno08x_update:
-
-
bno08x_update
- - - - - -
- - - - -

-Directories

 components
 
-
-
- - - - diff --git a/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7.js b/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7.js deleted file mode 100644 index 2525b6a..0000000 --- a/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7.js +++ /dev/null @@ -1,4 +0,0 @@ -var dir_c60d9bf80716f90f729fd65c40ec81f7 = -[ - [ "components", "dir_fd670e5d11b8bb731501003ff6578ae1.html", "dir_fd670e5d11b8bb731501003ff6578ae1" ] -]; \ No newline at end of file diff --git a/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.map b/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.map deleted file mode 100644 index 4e3a647..0000000 --- a/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.md5 b/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.md5 deleted file mode 100644 index c80cb87..0000000 --- a/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -63aaadf87a7d982f18fd764f52e28a27 \ No newline at end of file diff --git a/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.png b/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.png deleted file mode 100644 index d87d699..0000000 Binary files a/documentation/html/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.png and /dev/null differ diff --git a/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1.html b/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1.html deleted file mode 100644 index 1b2a3fb..0000000 --- a/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1.html +++ /dev/null @@ -1,124 +0,0 @@ - - - - - - - -esp32_BNO08x: components Directory Reference - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
components Directory Reference
-
-
-
-Directory dependency graph for components:
-
-
components
- - - - - -
- - - - -

-Directories

 esp32_BNO08x
 
-
-
- - - - diff --git a/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1.js b/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1.js deleted file mode 100644 index 3b034b2..0000000 --- a/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1.js +++ /dev/null @@ -1,4 +0,0 @@ -var dir_fd670e5d11b8bb731501003ff6578ae1 = -[ - [ "esp32_BNO08x", "dir_a6718ce9703adf4789a693642ffedf7f.html", "dir_a6718ce9703adf4789a693642ffedf7f" ] -]; \ No newline at end of file diff --git a/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1_dep.map b/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1_dep.map deleted file mode 100644 index 048a67c..0000000 --- a/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1_dep.map +++ /dev/null @@ -1,5 +0,0 @@ - - - - - diff --git a/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1_dep.md5 b/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1_dep.md5 deleted file mode 100644 index 20d5888..0000000 --- a/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -e26c358ec72ae9812a1309c2994c8f8a \ No newline at end of file diff --git a/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1_dep.png b/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1_dep.png deleted file mode 100644 index 98de742..0000000 Binary files a/documentation/html/dir_fd670e5d11b8bb731501003ff6578ae1_dep.png and /dev/null differ diff --git a/documentation/html/doc.svg b/documentation/html/doc.svg deleted file mode 100644 index 0b928a5..0000000 --- a/documentation/html/doc.svg +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/docd.svg b/documentation/html/docd.svg deleted file mode 100644 index ac18b27..0000000 --- a/documentation/html/docd.svg +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/doxygen.css b/documentation/html/doxygen.css deleted file mode 100644 index 7b7d851..0000000 --- a/documentation/html/doxygen.css +++ /dev/null @@ -1,2225 +0,0 @@ -/* The standard CSS for doxygen 1.10.0*/ - -html { -/* page base colors */ ---page-background-color: white; ---page-foreground-color: black; ---page-link-color: #3D578C; ---page-visited-link-color: #4665A2; - -/* index */ ---index-odd-item-bg-color: #F8F9FC; ---index-even-item-bg-color: white; ---index-header-color: black; ---index-separator-color: #A0A0A0; - -/* header */ ---header-background-color: #F9FAFC; ---header-separator-color: #C4CFE5; ---header-gradient-image: url('nav_h.png'); ---group-header-separator-color: #879ECB; ---group-header-color: #354C7B; ---inherit-header-color: gray; - ---footer-foreground-color: #2A3D61; ---footer-logo-width: 104px; ---citation-label-color: #334975; ---glow-color: cyan; - ---title-background-color: white; ---title-separator-color: #5373B4; ---directory-separator-color: #9CAFD4; ---separator-color: #4A6AAA; - ---blockquote-background-color: #F7F8FB; ---blockquote-border-color: #9CAFD4; - ---scrollbar-thumb-color: #9CAFD4; ---scrollbar-background-color: #F9FAFC; - ---icon-background-color: #728DC1; ---icon-foreground-color: white; ---icon-doc-image: url('doc.svg'); ---icon-folder-open-image: url('folderopen.svg'); ---icon-folder-closed-image: url('folderclosed.svg'); - -/* brief member declaration list */ ---memdecl-background-color: #F9FAFC; ---memdecl-separator-color: #DEE4F0; ---memdecl-foreground-color: #555; ---memdecl-template-color: #4665A2; - -/* detailed member list */ ---memdef-border-color: #A8B8D9; ---memdef-title-background-color: #E2E8F2; ---memdef-title-gradient-image: url('nav_f.png'); ---memdef-proto-background-color: #DFE5F1; ---memdef-proto-text-color: #253555; ---memdef-proto-text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); ---memdef-doc-background-color: white; ---memdef-param-name-color: #602020; ---memdef-template-color: #4665A2; - -/* tables */ ---table-cell-border-color: #2D4068; ---table-header-background-color: #374F7F; ---table-header-foreground-color: #FFFFFF; - -/* labels */ ---label-background-color: #728DC1; ---label-left-top-border-color: #5373B4; ---label-right-bottom-border-color: #C4CFE5; ---label-foreground-color: white; - -/** navigation bar/tree/menu */ ---nav-background-color: #F9FAFC; ---nav-foreground-color: #364D7C; ---nav-gradient-image: url('tab_b.png'); ---nav-gradient-hover-image: url('tab_h.png'); ---nav-gradient-active-image: url('tab_a.png'); ---nav-gradient-active-image-parent: url("../tab_a.png"); ---nav-separator-image: url('tab_s.png'); ---nav-breadcrumb-image: url('bc_s.png'); ---nav-breadcrumb-border-color: #C2CDE4; ---nav-splitbar-image: url('splitbar.png'); ---nav-font-size-level1: 13px; ---nav-font-size-level2: 10px; ---nav-font-size-level3: 9px; ---nav-text-normal-color: #283A5D; ---nav-text-hover-color: white; ---nav-text-active-color: white; ---nav-text-normal-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); ---nav-text-hover-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); ---nav-text-active-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); ---nav-menu-button-color: #364D7C; ---nav-menu-background-color: white; ---nav-menu-foreground-color: #555555; ---nav-menu-toggle-color: rgba(255, 255, 255, 0.5); ---nav-arrow-color: #9CAFD4; ---nav-arrow-selected-color: #9CAFD4; - -/* table of contents */ ---toc-background-color: #F4F6FA; ---toc-border-color: #D8DFEE; ---toc-header-color: #4665A2; ---toc-down-arrow-image: url("data:image/svg+xml;utf8,&%238595;"); - -/** search field */ ---search-background-color: white; ---search-foreground-color: #909090; ---search-magnification-image: url('mag.svg'); ---search-magnification-select-image: url('mag_sel.svg'); ---search-active-color: black; ---search-filter-background-color: #F9FAFC; ---search-filter-foreground-color: black; ---search-filter-border-color: #90A5CE; ---search-filter-highlight-text-color: white; ---search-filter-highlight-bg-color: #3D578C; ---search-results-foreground-color: #425E97; ---search-results-background-color: #EEF1F7; ---search-results-border-color: black; ---search-box-shadow: inset 0.5px 0.5px 3px 0px #555; - -/** code fragments */ ---code-keyword-color: #008000; ---code-type-keyword-color: #604020; ---code-flow-keyword-color: #E08000; ---code-comment-color: #800000; ---code-preprocessor-color: #806020; ---code-string-literal-color: #002080; ---code-char-literal-color: #008080; ---code-xml-cdata-color: black; ---code-vhdl-digit-color: #FF00FF; ---code-vhdl-char-color: #000000; ---code-vhdl-keyword-color: #700070; ---code-vhdl-logic-color: #FF0000; ---code-link-color: #4665A2; ---code-external-link-color: #4665A2; ---fragment-foreground-color: black; ---fragment-background-color: #FBFCFD; ---fragment-border-color: #C4CFE5; ---fragment-lineno-border-color: #00FF00; ---fragment-lineno-background-color: #E8E8E8; ---fragment-lineno-foreground-color: black; ---fragment-lineno-link-fg-color: #4665A2; ---fragment-lineno-link-bg-color: #D8D8D8; ---fragment-lineno-link-hover-fg-color: #4665A2; ---fragment-lineno-link-hover-bg-color: #C8C8C8; ---fragment-copy-ok-color: #2EC82E; ---tooltip-foreground-color: black; ---tooltip-background-color: white; ---tooltip-border-color: gray; ---tooltip-doc-color: grey; ---tooltip-declaration-color: #006318; ---tooltip-link-color: #4665A2; ---tooltip-shadow: 1px 1px 7px gray; ---fold-line-color: #808080; ---fold-minus-image: url('minus.svg'); ---fold-plus-image: url('plus.svg'); ---fold-minus-image-relpath: url('../../minus.svg'); ---fold-plus-image-relpath: url('../../plus.svg'); - -/** font-family */ ---font-family-normal: Roboto,sans-serif; ---font-family-monospace: 'JetBrains Mono',Consolas,Monaco,'Andale Mono','Ubuntu Mono',monospace,fixed; ---font-family-nav: 'Lucida Grande',Geneva,Helvetica,Arial,sans-serif; ---font-family-title: Tahoma,Arial,sans-serif; ---font-family-toc: Verdana,'DejaVu Sans',Geneva,sans-serif; ---font-family-search: Arial,Verdana,sans-serif; ---font-family-icon: Arial,Helvetica; ---font-family-tooltip: Roboto,sans-serif; - -/** special sections */ ---warning-color-bg: #f8d1cc; ---warning-color-hl: #b61825; ---warning-color-text: #75070f; ---note-color-bg: #faf3d8; ---note-color-hl: #f3a600; ---note-color-text: #5f4204; ---todo-color-bg: #e4f3ff; ---todo-color-hl: #1879C4; ---todo-color-text: #274a5c; ---test-color-bg: #e8e8ff; ---test-color-hl: #3939C4; ---test-color-text: #1a1a5c; ---deprecated-color-bg: #ecf0f3; ---deprecated-color-hl: #5b6269; ---deprecated-color-text: #43454a; ---bug-color-bg: #e4dafd; ---bug-color-hl: #5b2bdd; ---bug-color-text: #2a0d72; ---invariant-color-bg: #d8f1e3; ---invariant-color-hl: #44b86f; ---invariant-color-text: #265532; -} - -@media (prefers-color-scheme: dark) { - html:not(.dark-mode) { - color-scheme: dark; - -/* page base colors */ ---page-background-color: black; ---page-foreground-color: #C9D1D9; ---page-link-color: #90A5CE; ---page-visited-link-color: #A3B4D7; - -/* index */ ---index-odd-item-bg-color: #0B101A; ---index-even-item-bg-color: black; ---index-header-color: #C4CFE5; ---index-separator-color: #334975; - -/* header */ ---header-background-color: #070B11; ---header-separator-color: #141C2E; ---header-gradient-image: url('nav_hd.png'); ---group-header-separator-color: #283A5D; ---group-header-color: #90A5CE; ---inherit-header-color: #A0A0A0; - ---footer-foreground-color: #5B7AB7; ---footer-logo-width: 60px; ---citation-label-color: #90A5CE; ---glow-color: cyan; - ---title-background-color: #090D16; ---title-separator-color: #354C79; ---directory-separator-color: #283A5D; ---separator-color: #283A5D; - ---blockquote-background-color: #101826; ---blockquote-border-color: #283A5D; - ---scrollbar-thumb-color: #283A5D; ---scrollbar-background-color: #070B11; - ---icon-background-color: #334975; ---icon-foreground-color: #C4CFE5; ---icon-doc-image: url('docd.svg'); ---icon-folder-open-image: url('folderopend.svg'); ---icon-folder-closed-image: url('folderclosedd.svg'); - -/* brief member declaration list */ ---memdecl-background-color: #0B101A; ---memdecl-separator-color: #2C3F65; ---memdecl-foreground-color: #BBB; ---memdecl-template-color: #7C95C6; - -/* detailed member list */ ---memdef-border-color: #233250; ---memdef-title-background-color: #1B2840; ---memdef-title-gradient-image: url('nav_fd.png'); ---memdef-proto-background-color: #19243A; ---memdef-proto-text-color: #9DB0D4; ---memdef-proto-text-shadow: 0px 1px 1px rgba(0, 0, 0, 0.9); ---memdef-doc-background-color: black; ---memdef-param-name-color: #D28757; ---memdef-template-color: #7C95C6; - -/* tables */ ---table-cell-border-color: #283A5D; ---table-header-background-color: #283A5D; ---table-header-foreground-color: #C4CFE5; - -/* labels */ ---label-background-color: #354C7B; ---label-left-top-border-color: #4665A2; ---label-right-bottom-border-color: #283A5D; ---label-foreground-color: #CCCCCC; - -/** navigation bar/tree/menu */ ---nav-background-color: #101826; ---nav-foreground-color: #364D7C; ---nav-gradient-image: url('tab_bd.png'); ---nav-gradient-hover-image: url('tab_hd.png'); ---nav-gradient-active-image: url('tab_ad.png'); ---nav-gradient-active-image-parent: url("../tab_ad.png"); ---nav-separator-image: url('tab_sd.png'); ---nav-breadcrumb-image: url('bc_sd.png'); ---nav-breadcrumb-border-color: #2A3D61; ---nav-splitbar-image: url('splitbard.png'); ---nav-font-size-level1: 13px; ---nav-font-size-level2: 10px; ---nav-font-size-level3: 9px; ---nav-text-normal-color: #B6C4DF; ---nav-text-hover-color: #DCE2EF; ---nav-text-active-color: #DCE2EF; ---nav-text-normal-shadow: 0px 1px 1px black; ---nav-text-hover-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); ---nav-text-active-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); ---nav-menu-button-color: #B6C4DF; ---nav-menu-background-color: #05070C; ---nav-menu-foreground-color: #BBBBBB; ---nav-menu-toggle-color: rgba(255, 255, 255, 0.2); ---nav-arrow-color: #334975; ---nav-arrow-selected-color: #90A5CE; - -/* table of contents */ ---toc-background-color: #151E30; ---toc-border-color: #202E4A; ---toc-header-color: #A3B4D7; ---toc-down-arrow-image: url("data:image/svg+xml;utf8,&%238595;"); - -/** search field */ ---search-background-color: black; ---search-foreground-color: #C5C5C5; ---search-magnification-image: url('mag_d.svg'); ---search-magnification-select-image: url('mag_seld.svg'); ---search-active-color: #C5C5C5; ---search-filter-background-color: #101826; ---search-filter-foreground-color: #90A5CE; ---search-filter-border-color: #7C95C6; ---search-filter-highlight-text-color: #BCC9E2; ---search-filter-highlight-bg-color: #283A5D; ---search-results-background-color: #101826; ---search-results-foreground-color: #90A5CE; ---search-results-border-color: #7C95C6; ---search-box-shadow: inset 0.5px 0.5px 3px 0px #2F436C; - -/** code fragments */ ---code-keyword-color: #CC99CD; ---code-type-keyword-color: #AB99CD; ---code-flow-keyword-color: #E08000; ---code-comment-color: #717790; ---code-preprocessor-color: #65CABE; ---code-string-literal-color: #7EC699; ---code-char-literal-color: #00E0F0; ---code-xml-cdata-color: #C9D1D9; ---code-vhdl-digit-color: #FF00FF; ---code-vhdl-char-color: #C0C0C0; ---code-vhdl-keyword-color: #CF53C9; ---code-vhdl-logic-color: #FF0000; ---code-link-color: #79C0FF; ---code-external-link-color: #79C0FF; ---fragment-foreground-color: #C9D1D9; ---fragment-background-color: #090D16; ---fragment-border-color: #30363D; ---fragment-lineno-border-color: #30363D; ---fragment-lineno-background-color: black; ---fragment-lineno-foreground-color: #6E7681; ---fragment-lineno-link-fg-color: #6E7681; ---fragment-lineno-link-bg-color: #303030; ---fragment-lineno-link-hover-fg-color: #8E96A1; ---fragment-lineno-link-hover-bg-color: #505050; ---fragment-copy-ok-color: #0EA80E; ---tooltip-foreground-color: #C9D1D9; ---tooltip-background-color: #202020; ---tooltip-border-color: #C9D1D9; ---tooltip-doc-color: #D9E1E9; ---tooltip-declaration-color: #20C348; ---tooltip-link-color: #79C0FF; ---tooltip-shadow: none; ---fold-line-color: #808080; ---fold-minus-image: url('minusd.svg'); ---fold-plus-image: url('plusd.svg'); ---fold-minus-image-relpath: url('../../minusd.svg'); ---fold-plus-image-relpath: url('../../plusd.svg'); - -/** font-family */ ---font-family-normal: Roboto,sans-serif; ---font-family-monospace: 'JetBrains Mono',Consolas,Monaco,'Andale Mono','Ubuntu Mono',monospace,fixed; ---font-family-nav: 'Lucida Grande',Geneva,Helvetica,Arial,sans-serif; ---font-family-title: Tahoma,Arial,sans-serif; ---font-family-toc: Verdana,'DejaVu Sans',Geneva,sans-serif; ---font-family-search: Arial,Verdana,sans-serif; ---font-family-icon: Arial,Helvetica; ---font-family-tooltip: Roboto,sans-serif; - -/** special sections */ ---warning-color-bg: #2e1917; ---warning-color-hl: #ad2617; ---warning-color-text: #f5b1aa; ---note-color-bg: #3b2e04; ---note-color-hl: #f1b602; ---note-color-text: #ceb670; ---todo-color-bg: #163750; ---todo-color-hl: #1982D2; ---todo-color-text: #dcf0fa; ---test-color-bg: #121258; ---test-color-hl: #4242cf; ---test-color-text: #c0c0da; ---deprecated-color-bg: #2e323b; ---deprecated-color-hl: #738396; ---deprecated-color-text: #abb0bd; ---bug-color-bg: #2a2536; ---bug-color-hl: #7661b3; ---bug-color-text: #ae9ed6; ---invariant-color-bg: #303a35; ---invariant-color-hl: #76ce96; ---invariant-color-text: #cceed5; -}} -body { - background-color: var(--page-background-color); - color: var(--page-foreground-color); -} - -body, table, div, p, dl { - font-weight: 400; - font-size: 14px; - font-family: var(--font-family-normal); - line-height: 22px; -} - -/* @group Heading Levels */ - -.title { - font-family: var(--font-family-normal); - line-height: 28px; - font-size: 150%; - font-weight: bold; - margin: 10px 2px; -} - -h1.groupheader { - font-size: 150%; -} - -h2.groupheader { - border-bottom: 1px solid var(--group-header-separator-color); - color: var(--group-header-color); - font-size: 150%; - font-weight: normal; - margin-top: 1.75em; - padding-top: 8px; - padding-bottom: 4px; - width: 100%; -} - -h3.groupheader { - font-size: 100%; -} - -h1, h2, h3, h4, h5, h6 { - -webkit-transition: text-shadow 0.5s linear; - -moz-transition: text-shadow 0.5s linear; - -ms-transition: text-shadow 0.5s linear; - -o-transition: text-shadow 0.5s linear; - transition: text-shadow 0.5s linear; - margin-right: 15px; -} - -h1.glow, h2.glow, h3.glow, h4.glow, h5.glow, h6.glow { - text-shadow: 0 0 15px var(--glow-color); -} - -dt { - font-weight: bold; -} - -p.startli, p.startdd { - margin-top: 2px; -} - -th p.starttd, th p.intertd, th p.endtd { - font-size: 100%; - font-weight: 700; -} - -p.starttd { - margin-top: 0px; -} - -p.endli { - margin-bottom: 0px; -} - -p.enddd { - margin-bottom: 4px; -} - -p.endtd { - margin-bottom: 2px; -} - -p.interli { -} - -p.interdd { -} - -p.intertd { -} - -/* @end */ - -caption { - font-weight: bold; -} - -span.legend { - font-size: 70%; - text-align: center; -} - -h3.version { - font-size: 90%; - text-align: center; -} - -div.navtab { - padding-right: 15px; - text-align: right; - line-height: 110%; -} - -div.navtab table { - border-spacing: 0; -} - -td.navtab { - padding-right: 6px; - padding-left: 6px; -} - -td.navtabHL { - background-image: var(--nav-gradient-active-image); - background-repeat:repeat-x; - padding-right: 6px; - padding-left: 6px; -} - -td.navtabHL a, td.navtabHL a:visited { - color: var(--nav-text-hover-color); - text-shadow: var(--nav-text-hover-shadow); -} - -a.navtab { - font-weight: bold; -} - -div.qindex{ - text-align: center; - width: 100%; - line-height: 140%; - font-size: 130%; - color: var(--index-separator-color); -} - -#main-menu a:focus { - outline: auto; - z-index: 10; - position: relative; -} - -dt.alphachar{ - font-size: 180%; - font-weight: bold; -} - -.alphachar a{ - color: var(--index-header-color); -} - -.alphachar a:hover, .alphachar a:visited{ - text-decoration: none; -} - -.classindex dl { - padding: 25px; - column-count:1 -} - -.classindex dd { - display:inline-block; - margin-left: 50px; - width: 90%; - line-height: 1.15em; -} - -.classindex dl.even { - background-color: var(--index-even-item-bg-color); -} - -.classindex dl.odd { - background-color: var(--index-odd-item-bg-color); -} - -@media(min-width: 1120px) { - .classindex dl { - column-count:2 - } -} - -@media(min-width: 1320px) { - .classindex dl { - column-count:3 - } -} - - -/* @group Link Styling */ - -a { - color: var(--page-link-color); - font-weight: normal; - text-decoration: none; -} - -.contents a:visited { - color: var(--page-visited-link-color); -} - -a:hover { - text-decoration: none; - background: linear-gradient(to bottom, transparent 0,transparent calc(100% - 1px), currentColor 100%); -} - -a:hover > span.arrow { - text-decoration: none; - background : var(--nav-background-color); -} - -a.el { - font-weight: bold; -} - -a.elRef { -} - -a.code, a.code:visited, a.line, a.line:visited { - color: var(--code-link-color); -} - -a.codeRef, a.codeRef:visited, a.lineRef, a.lineRef:visited { - color: var(--code-external-link-color); -} - -a.code.hl_class { /* style for links to class names in code snippets */ } -a.code.hl_struct { /* style for links to struct names in code snippets */ } -a.code.hl_union { /* style for links to union names in code snippets */ } -a.code.hl_interface { /* style for links to interface names in code snippets */ } -a.code.hl_protocol { /* style for links to protocol names in code snippets */ } -a.code.hl_category { /* style for links to category names in code snippets */ } -a.code.hl_exception { /* style for links to exception names in code snippets */ } -a.code.hl_service { /* style for links to service names in code snippets */ } -a.code.hl_singleton { /* style for links to singleton names in code snippets */ } -a.code.hl_concept { /* style for links to concept names in code snippets */ } -a.code.hl_namespace { /* style for links to namespace names in code snippets */ } -a.code.hl_package { /* style for links to package names in code snippets */ } -a.code.hl_define { /* style for links to macro names in code snippets */ } -a.code.hl_function { /* style for links to function names in code snippets */ } -a.code.hl_variable { /* style for links to variable names in code snippets */ } -a.code.hl_typedef { /* style for links to typedef names in code snippets */ } -a.code.hl_enumvalue { /* style for links to enum value names in code snippets */ } -a.code.hl_enumeration { /* style for links to enumeration names in code snippets */ } -a.code.hl_signal { /* style for links to Qt signal names in code snippets */ } -a.code.hl_slot { /* style for links to Qt slot names in code snippets */ } -a.code.hl_friend { /* style for links to friend names in code snippets */ } -a.code.hl_dcop { /* style for links to KDE3 DCOP names in code snippets */ } -a.code.hl_property { /* style for links to property names in code snippets */ } -a.code.hl_event { /* style for links to event names in code snippets */ } -a.code.hl_sequence { /* style for links to sequence names in code snippets */ } -a.code.hl_dictionary { /* style for links to dictionary names in code snippets */ } - -/* @end */ - -dl.el { - margin-left: -1cm; -} - -ul { - overflow: visible; -} - -ul.multicol { - -moz-column-gap: 1em; - -webkit-column-gap: 1em; - column-gap: 1em; - -moz-column-count: 3; - -webkit-column-count: 3; - column-count: 3; - list-style-type: none; -} - -#side-nav ul { - overflow: visible; /* reset ul rule for scroll bar in GENERATE_TREEVIEW window */ -} - -#main-nav ul { - overflow: visible; /* reset ul rule for the navigation bar drop down lists */ -} - -.fragment { - text-align: left; - direction: ltr; - overflow-x: auto; - overflow-y: hidden; - position: relative; - min-height: 12px; - margin: 10px 0px; - padding: 10px 10px; - border: 1px solid var(--fragment-border-color); - border-radius: 4px; - background-color: var(--fragment-background-color); - color: var(--fragment-foreground-color); -} - -pre.fragment { - word-wrap: break-word; - font-size: 10pt; - line-height: 125%; - font-family: var(--font-family-monospace); -} - -.clipboard { - width: 24px; - height: 24px; - right: 5px; - top: 5px; - opacity: 0; - position: absolute; - display: inline; - overflow: auto; - fill: var(--fragment-foreground-color); - justify-content: center; - align-items: center; - cursor: pointer; -} - -.clipboard.success { - border: 1px solid var(--fragment-foreground-color); - border-radius: 4px; -} - -.fragment:hover .clipboard, .clipboard.success { - opacity: .28; -} - -.clipboard:hover, .clipboard.success { - opacity: 1 !important; -} - -.clipboard:active:not([class~=success]) svg { - transform: scale(.91); -} - -.clipboard.success svg { - fill: var(--fragment-copy-ok-color); -} - -.clipboard.success { - border-color: var(--fragment-copy-ok-color); -} - -div.line { - font-family: var(--font-family-monospace); - font-size: 13px; - min-height: 13px; - line-height: 1.2; - text-wrap: unrestricted; - white-space: -moz-pre-wrap; /* Moz */ - white-space: -pre-wrap; /* Opera 4-6 */ - white-space: -o-pre-wrap; /* Opera 7 */ - white-space: pre-wrap; /* CSS3 */ - word-wrap: break-word; /* IE 5.5+ */ - text-indent: -53px; - padding-left: 53px; - padding-bottom: 0px; - margin: 0px; - -webkit-transition-property: background-color, box-shadow; - -webkit-transition-duration: 0.5s; - -moz-transition-property: background-color, box-shadow; - -moz-transition-duration: 0.5s; - -ms-transition-property: background-color, box-shadow; - -ms-transition-duration: 0.5s; - -o-transition-property: background-color, box-shadow; - -o-transition-duration: 0.5s; - transition-property: background-color, box-shadow; - transition-duration: 0.5s; -} - -div.line:after { - content:"\000A"; - white-space: pre; -} - -div.line.glow { - background-color: var(--glow-color); - box-shadow: 0 0 10px var(--glow-color); -} - -span.fold { - margin-left: 5px; - margin-right: 1px; - margin-top: 0px; - margin-bottom: 0px; - padding: 0px; - display: inline-block; - width: 12px; - height: 12px; - background-repeat:no-repeat; - background-position:center; -} - -span.lineno { - padding-right: 4px; - margin-right: 9px; - text-align: right; - border-right: 2px solid var(--fragment-lineno-border-color); - color: var(--fragment-lineno-foreground-color); - background-color: var(--fragment-lineno-background-color); - white-space: pre; -} -span.lineno a, span.lineno a:visited { - color: var(--fragment-lineno-link-fg-color); - background-color: var(--fragment-lineno-link-bg-color); -} - -span.lineno a:hover { - color: var(--fragment-lineno-link-hover-fg-color); - background-color: var(--fragment-lineno-link-hover-bg-color); -} - -.lineno { - -webkit-touch-callout: none; - -webkit-user-select: none; - -khtml-user-select: none; - -moz-user-select: none; - -ms-user-select: none; - user-select: none; -} - -div.classindex ul { - list-style: none; - padding-left: 0; -} - -div.classindex span.ai { - display: inline-block; -} - -div.groupHeader { - margin-left: 16px; - margin-top: 12px; - font-weight: bold; -} - -div.groupText { - margin-left: 16px; - font-style: italic; -} - -body { - color: var(--page-foreground-color); - margin: 0; -} - -div.contents { - margin-top: 10px; - margin-left: 12px; - margin-right: 8px; -} - -p.formulaDsp { - text-align: center; -} - -img.dark-mode-visible { - display: none; -} -img.light-mode-visible { - display: none; -} - -img.formulaInl, img.inline { - vertical-align: middle; -} - -div.center { - text-align: center; - margin-top: 0px; - margin-bottom: 0px; - padding: 0px; -} - -div.center img { - border: 0px; -} - -address.footer { - text-align: right; - padding-right: 12px; -} - -img.footer { - border: 0px; - vertical-align: middle; - width: var(--footer-logo-width); -} - -.compoundTemplParams { - color: var(--memdecl-template-color); - font-size: 80%; - line-height: 120%; -} - -/* @group Code Colorization */ - -span.keyword { - color: var(--code-keyword-color); -} - -span.keywordtype { - color: var(--code-type-keyword-color); -} - -span.keywordflow { - color: var(--code-flow-keyword-color); -} - -span.comment { - color: var(--code-comment-color); -} - -span.preprocessor { - color: var(--code-preprocessor-color); -} - -span.stringliteral { - color: var(--code-string-literal-color); -} - -span.charliteral { - color: var(--code-char-literal-color); -} - -span.xmlcdata { - color: var(--code-xml-cdata-color); -} - -span.vhdldigit { - color: var(--code-vhdl-digit-color); -} - -span.vhdlchar { - color: var(--code-vhdl-char-color); -} - -span.vhdlkeyword { - color: var(--code-vhdl-keyword-color); -} - -span.vhdllogic { - color: var(--code-vhdl-logic-color); -} - -blockquote { - background-color: var(--blockquote-background-color); - border-left: 2px solid var(--blockquote-border-color); - margin: 0 24px 0 4px; - padding: 0 12px 0 16px; -} - -/* @end */ - -td.tiny { - font-size: 75%; -} - -.dirtab { - padding: 4px; - border-collapse: collapse; - border: 1px solid var(--table-cell-border-color); -} - -th.dirtab { - background-color: var(--table-header-background-color); - color: var(--table-header-foreground-color); - font-weight: bold; -} - -hr { - height: 0px; - border: none; - border-top: 1px solid var(--separator-color); -} - -hr.footer { - height: 1px; -} - -/* @group Member Descriptions */ - -table.memberdecls { - border-spacing: 0px; - padding: 0px; -} - -.memberdecls td, .fieldtable tr { - -webkit-transition-property: background-color, box-shadow; - -webkit-transition-duration: 0.5s; - -moz-transition-property: background-color, box-shadow; - -moz-transition-duration: 0.5s; - -ms-transition-property: background-color, box-shadow; - -ms-transition-duration: 0.5s; - -o-transition-property: background-color, box-shadow; - -o-transition-duration: 0.5s; - transition-property: background-color, box-shadow; - transition-duration: 0.5s; -} - -.memberdecls td.glow, .fieldtable tr.glow { - background-color: var(--glow-color); - box-shadow: 0 0 15px var(--glow-color); -} - -.mdescLeft, .mdescRight, -.memItemLeft, .memItemRight, -.memTemplItemLeft, .memTemplItemRight, .memTemplParams { - background-color: var(--memdecl-background-color); - border: none; - margin: 4px; - padding: 1px 0 0 8px; -} - -.mdescLeft, .mdescRight { - padding: 0px 8px 4px 8px; - color: var(--memdecl-foreground-color); -} - -.memSeparator { - border-bottom: 1px solid var(--memdecl-separator-color); - line-height: 1px; - margin: 0px; - padding: 0px; -} - -.memItemLeft, .memTemplItemLeft { - white-space: nowrap; -} - -.memItemRight, .memTemplItemRight { - width: 100%; -} - -.memTemplParams { - color: var(--memdecl-template-color); - white-space: nowrap; - font-size: 80%; -} - -/* @end */ - -/* @group Member Details */ - -/* Styles for detailed member documentation */ - -.memtitle { - padding: 8px; - border-top: 1px solid var(--memdef-border-color); - border-left: 1px solid var(--memdef-border-color); - border-right: 1px solid var(--memdef-border-color); - border-top-right-radius: 4px; - border-top-left-radius: 4px; - margin-bottom: -1px; - background-image: var(--memdef-title-gradient-image); - background-repeat: repeat-x; - background-color: var(--memdef-title-background-color); - line-height: 1.25; - font-weight: 300; - float:left; -} - -.permalink -{ - font-size: 65%; - display: inline-block; - vertical-align: middle; -} - -.memtemplate { - font-size: 80%; - color: var(--memdef-template-color); - font-weight: normal; - margin-left: 9px; -} - -.mempage { - width: 100%; -} - -.memitem { - padding: 0; - margin-bottom: 10px; - margin-right: 5px; - -webkit-transition: box-shadow 0.5s linear; - -moz-transition: box-shadow 0.5s linear; - -ms-transition: box-shadow 0.5s linear; - -o-transition: box-shadow 0.5s linear; - transition: box-shadow 0.5s linear; - display: table !important; - width: 100%; -} - -.memitem.glow { - box-shadow: 0 0 15px var(--glow-color); -} - -.memname { - font-weight: 400; - margin-left: 6px; -} - -.memname td { - vertical-align: bottom; -} - -.memproto, dl.reflist dt { - border-top: 1px solid var(--memdef-border-color); - border-left: 1px solid var(--memdef-border-color); - border-right: 1px solid var(--memdef-border-color); - padding: 6px 0px 6px 0px; - color: var(--memdef-proto-text-color); - font-weight: bold; - text-shadow: var(--memdef-proto-text-shadow); - background-color: var(--memdef-proto-background-color); - box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); - border-top-right-radius: 4px; -} - -.overload { - font-family: var(--font-family-monospace); - font-size: 65%; -} - -.memdoc, dl.reflist dd { - border-bottom: 1px solid var(--memdef-border-color); - border-left: 1px solid var(--memdef-border-color); - border-right: 1px solid var(--memdef-border-color); - padding: 6px 10px 2px 10px; - border-top-width: 0; - background-image:url('nav_g.png'); - background-repeat:repeat-x; - background-color: var(--memdef-doc-background-color); - /* opera specific markup */ - border-bottom-left-radius: 4px; - border-bottom-right-radius: 4px; - box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); - /* firefox specific markup */ - -moz-border-radius-bottomleft: 4px; - -moz-border-radius-bottomright: 4px; - -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; - /* webkit specific markup */ - -webkit-border-bottom-left-radius: 4px; - -webkit-border-bottom-right-radius: 4px; - -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); -} - -dl.reflist dt { - padding: 5px; -} - -dl.reflist dd { - margin: 0px 0px 10px 0px; - padding: 5px; -} - -.paramkey { - text-align: right; -} - -.paramtype { - white-space: nowrap; - padding: 0px; - padding-bottom: 1px; -} - -.paramname { - white-space: nowrap; - padding: 0px; - padding-bottom: 1px; - margin-left: 2px; -} - -.paramname em { - color: var(--memdef-param-name-color); - font-style: normal; - margin-right: 1px; -} - -.paramname .paramdefval { - font-family: var(--font-family-monospace); -} - -.params, .retval, .exception, .tparams { - margin-left: 0px; - padding-left: 0px; -} - -.params .paramname, .retval .paramname, .tparams .paramname, .exception .paramname { - font-weight: bold; - vertical-align: top; -} - -.params .paramtype, .tparams .paramtype { - font-style: italic; - vertical-align: top; -} - -.params .paramdir, .tparams .paramdir { - font-family: var(--font-family-monospace); - vertical-align: top; -} - -table.mlabels { - border-spacing: 0px; -} - -td.mlabels-left { - width: 100%; - padding: 0px; -} - -td.mlabels-right { - vertical-align: bottom; - padding: 0px; - white-space: nowrap; -} - -span.mlabels { - margin-left: 8px; -} - -span.mlabel { - background-color: var(--label-background-color); - border-top:1px solid var(--label-left-top-border-color); - border-left:1px solid var(--label-left-top-border-color); - border-right:1px solid var(--label-right-bottom-border-color); - border-bottom:1px solid var(--label-right-bottom-border-color); - text-shadow: none; - color: var(--label-foreground-color); - margin-right: 4px; - padding: 2px 3px; - border-radius: 3px; - font-size: 7pt; - white-space: nowrap; - vertical-align: middle; -} - - - -/* @end */ - -/* these are for tree view inside a (index) page */ - -div.directory { - margin: 10px 0px; - border-top: 1px solid var(--directory-separator-color); - border-bottom: 1px solid var(--directory-separator-color); - width: 100%; -} - -.directory table { - border-collapse:collapse; -} - -.directory td { - margin: 0px; - padding: 0px; - vertical-align: top; -} - -.directory td.entry { - white-space: nowrap; - padding-right: 6px; - padding-top: 3px; -} - -.directory td.entry a { - outline:none; -} - -.directory td.entry a img { - border: none; -} - -.directory td.desc { - width: 100%; - padding-left: 6px; - padding-right: 6px; - padding-top: 3px; - border-left: 1px solid rgba(0,0,0,0.05); -} - -.directory tr.odd { - padding-left: 6px; - background-color: var(--index-odd-item-bg-color); -} - -.directory tr.even { - padding-left: 6px; - background-color: var(--index-even-item-bg-color); -} - -.directory img { - vertical-align: -30%; -} - -.directory .levels { - white-space: nowrap; - width: 100%; - text-align: right; - font-size: 9pt; -} - -.directory .levels span { - cursor: pointer; - padding-left: 2px; - padding-right: 2px; - color: var(--page-link-color); -} - -.arrow { - color: var(--nav-arrow-color); - -webkit-user-select: none; - -khtml-user-select: none; - -moz-user-select: none; - -ms-user-select: none; - user-select: none; - cursor: pointer; - font-size: 80%; - display: inline-block; - width: 16px; - height: 22px; -} - -.icon { - font-family: var(--font-family-icon); - line-height: normal; - font-weight: bold; - font-size: 12px; - height: 14px; - width: 16px; - display: inline-block; - background-color: var(--icon-background-color); - color: var(--icon-foreground-color); - text-align: center; - border-radius: 4px; - margin-left: 2px; - margin-right: 2px; -} - -.icona { - width: 24px; - height: 22px; - display: inline-block; -} - -.iconfopen { - width: 24px; - height: 18px; - margin-bottom: 4px; - background-image:var(--icon-folder-open-image); - background-repeat: repeat-y; - vertical-align:top; - display: inline-block; -} - -.iconfclosed { - width: 24px; - height: 18px; - margin-bottom: 4px; - background-image:var(--icon-folder-closed-image); - background-repeat: repeat-y; - vertical-align:top; - display: inline-block; -} - -.icondoc { - width: 24px; - height: 18px; - margin-bottom: 4px; - background-image:var(--icon-doc-image); - background-position: 0px -4px; - background-repeat: repeat-y; - vertical-align:top; - display: inline-block; -} - -/* @end */ - -div.dynheader { - margin-top: 8px; - -webkit-touch-callout: none; - -webkit-user-select: none; - -khtml-user-select: none; - -moz-user-select: none; - -ms-user-select: none; - user-select: none; -} - -address { - font-style: normal; - color: var(--footer-foreground-color); -} - -table.doxtable caption { - caption-side: top; -} - -table.doxtable { - border-collapse:collapse; - margin-top: 4px; - margin-bottom: 4px; -} - -table.doxtable td, table.doxtable th { - border: 1px solid var(--table-cell-border-color); - padding: 3px 7px 2px; -} - -table.doxtable th { - background-color: var(--table-header-background-color); - color: var(--table-header-foreground-color); - font-size: 110%; - padding-bottom: 4px; - padding-top: 5px; -} - -table.fieldtable { - margin-bottom: 10px; - border: 1px solid var(--memdef-border-color); - border-spacing: 0px; - border-radius: 4px; - box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15); -} - -.fieldtable td, .fieldtable th { - padding: 3px 7px 2px; -} - -.fieldtable td.fieldtype, .fieldtable td.fieldname { - white-space: nowrap; - border-right: 1px solid var(--memdef-border-color); - border-bottom: 1px solid var(--memdef-border-color); - vertical-align: top; -} - -.fieldtable td.fieldname { - padding-top: 3px; -} - -.fieldtable td.fielddoc { - border-bottom: 1px solid var(--memdef-border-color); -} - -.fieldtable td.fielddoc p:first-child { - margin-top: 0px; -} - -.fieldtable td.fielddoc p:last-child { - margin-bottom: 2px; -} - -.fieldtable tr:last-child td { - border-bottom: none; -} - -.fieldtable th { - background-image: var(--memdef-title-gradient-image); - background-repeat:repeat-x; - background-color: var(--memdef-title-background-color); - font-size: 90%; - color: var(--memdef-proto-text-color); - padding-bottom: 4px; - padding-top: 5px; - text-align:left; - font-weight: 400; - border-top-left-radius: 4px; - border-top-right-radius: 4px; - border-bottom: 1px solid var(--memdef-border-color); -} - - -.tabsearch { - top: 0px; - left: 10px; - height: 36px; - background-image: var(--nav-gradient-image); - z-index: 101; - overflow: hidden; - font-size: 13px; -} - -.navpath ul -{ - font-size: 11px; - background-image: var(--nav-gradient-image); - background-repeat:repeat-x; - background-position: 0 -5px; - height:30px; - line-height:30px; - color:var(--nav-text-normal-color); - border:solid 1px var(--nav-breadcrumb-border-color); - overflow:hidden; - margin:0px; - padding:0px; -} - -.navpath li -{ - list-style-type:none; - float:left; - padding-left:10px; - padding-right:15px; - background-image:var(--nav-breadcrumb-image); - background-repeat:no-repeat; - background-position:right; - color: var(--nav-foreground-color); -} - -.navpath li.navelem a -{ - height:32px; - display:block; - outline: none; - color: var(--nav-text-normal-color); - font-family: var(--font-family-nav); - text-shadow: var(--nav-text-normal-shadow); - text-decoration: none; -} - -.navpath li.navelem a:hover -{ - color: var(--nav-text-hover-color); - text-shadow: var(--nav-text-hover-shadow); -} - -.navpath li.footer -{ - list-style-type:none; - float:right; - padding-left:10px; - padding-right:15px; - background-image:none; - background-repeat:no-repeat; - background-position:right; - color: var(--footer-foreground-color); - font-size: 8pt; -} - - -div.summary -{ - float: right; - font-size: 8pt; - padding-right: 5px; - width: 50%; - text-align: right; -} - -div.summary a -{ - white-space: nowrap; -} - -table.classindex -{ - margin: 10px; - white-space: nowrap; - margin-left: 3%; - margin-right: 3%; - width: 94%; - border: 0; - border-spacing: 0; - padding: 0; -} - -div.ingroups -{ - font-size: 8pt; - width: 50%; - text-align: left; -} - -div.ingroups a -{ - white-space: nowrap; -} - -div.header -{ - background-image: var(--header-gradient-image); - background-repeat:repeat-x; - background-color: var(--header-background-color); - margin: 0px; - border-bottom: 1px solid var(--header-separator-color); -} - -div.headertitle -{ - padding: 5px 5px 5px 10px; -} - -.PageDocRTL-title div.headertitle { - text-align: right; - direction: rtl; -} - -dl { - padding: 0 0 0 0; -} - -/* - -dl.section { - margin-left: 0px; - padding-left: 0px; -} - -dl.note { - margin-left: -7px; - padding-left: 3px; - border-left: 4px solid; - border-color: #D0C000; -} - -dl.warning, dl.attention { - margin-left: -7px; - padding-left: 3px; - border-left: 4px solid; - border-color: #FF0000; -} - -dl.pre, dl.post, dl.invariant { - margin-left: -7px; - padding-left: 3px; - border-left: 4px solid; - border-color: #00D000; -} - -dl.deprecated { - margin-left: -7px; - padding-left: 3px; - border-left: 4px solid; - border-color: #505050; -} - -dl.todo { - margin-left: -7px; - padding-left: 3px; - border-left: 4px solid; - border-color: #00C0E0; -} - -dl.test { - margin-left: -7px; - padding-left: 3px; - border-left: 4px solid; - border-color: #3030E0; -} - -dl.bug { - margin-left: -7px; - padding-left: 3px; - border-left: 4px solid; - border-color: #C08050; -} - -*/ - -dl.bug dt a, dl.deprecated dt a, dl.todo dt a, dl.test a { - font-weight: bold !important; -} - -dl.warning, dl.attention, dl.note, dl.deprecated, dl.bug, -dl.invariant, dl.pre, dl.post, dl.todo, dl.test, dl.remark { - padding: 10px; - margin: 10px 0px; - overflow: hidden; - margin-left: 0; - border-radius: 4px; -} - -dl.section dd { - margin-bottom: 2px; -} - -dl.warning, dl.attention { - background: var(--warning-color-bg); - border-left: 8px solid var(--warning-color-hl); - color: var(--warning-color-text); -} - -dl.warning dt, dl.attention dt { - color: var(--warning-color-hl); -} - -dl.note, dl.remark { - background: var(--note-color-bg); - border-left: 8px solid var(--note-color-hl); - color: var(--note-color-text); -} - -dl.note dt, dl.remark dt { - color: var(--note-color-hl); -} - -dl.todo { - background: var(--todo-color-bg); - border-left: 8px solid var(--todo-color-hl); - color: var(--todo-color-text); -} - -dl.todo dt { - color: var(--todo-color-hl); -} - -dl.test { - background: var(--test-color-bg); - border-left: 8px solid var(--test-color-hl); - color: var(--test-color-text); -} - -dl.test dt { - color: var(--test-color-hl); -} - -dl.bug dt a { - color: var(--bug-color-hl) !important; -} - -dl.bug { - background: var(--bug-color-bg); - border-left: 8px solid var(--bug-color-hl); - color: var(--bug-color-text); -} - -dl.bug dt a { - color: var(--bug-color-hl) !important; -} - -dl.deprecated { - background: var(--deprecated-color-bg); - border-left: 8px solid var(--deprecated-color-hl); - color: var(--deprecated-color-text); -} - -dl.deprecated dt a { - color: var(--deprecated-color-hl) !important; -} - -dl.section dd, dl.bug dd, dl.deprecated dd, dl.todo dd, dl.test dd { - margin-inline-start: 0px; -} - -dl.invariant, dl.pre, dl.post { - background: var(--invariant-color-bg); - border-left: 8px solid var(--invariant-color-hl); - color: var(--invariant-color-text); -} - -dl.invariant dt, dl.pre dt, dl.post dt { - color: var(--invariant-color-hl); -} - - -#projectrow -{ - height: 56px; -} - -#projectlogo -{ - text-align: center; - vertical-align: bottom; - border-collapse: separate; -} - -#projectlogo img -{ - border: 0px none; -} - -#projectalign -{ - vertical-align: middle; - padding-left: 0.5em; -} - -#projectname -{ - font-size: 200%; - font-family: var(--font-family-title); - margin: 0px; - padding: 2px 0px; -} - -#projectbrief -{ - font-size: 90%; - font-family: var(--font-family-title); - margin: 0px; - padding: 0px; -} - -#projectnumber -{ - font-size: 50%; - font-family: 50% var(--font-family-title); - margin: 0px; - padding: 0px; -} - -#titlearea -{ - padding: 0px; - margin: 0px; - width: 100%; - border-bottom: 1px solid var(--title-separator-color); - background-color: var(--title-background-color); -} - -.image -{ - text-align: center; -} - -.dotgraph -{ - text-align: center; -} - -.mscgraph -{ - text-align: center; -} - -.plantumlgraph -{ - text-align: center; -} - -.diagraph -{ - text-align: center; -} - -.caption -{ - font-weight: bold; -} - -dl.citelist { - margin-bottom:50px; -} - -dl.citelist dt { - color:var(--citation-label-color); - float:left; - font-weight:bold; - margin-right:10px; - padding:5px; - text-align:right; - width:52px; -} - -dl.citelist dd { - margin:2px 0 2px 72px; - padding:5px 0; -} - -div.toc { - padding: 14px 25px; - background-color: var(--toc-background-color); - border: 1px solid var(--toc-border-color); - border-radius: 7px 7px 7px 7px; - float: right; - height: auto; - margin: 0 8px 10px 10px; - width: 200px; -} - -div.toc li { - background: var(--toc-down-arrow-image) no-repeat scroll 0 5px transparent; - font: 10px/1.2 var(--font-family-toc); - margin-top: 5px; - padding-left: 10px; - padding-top: 2px; -} - -div.toc h3 { - font: bold 12px/1.2 var(--font-family-toc); - color: var(--toc-header-color); - border-bottom: 0 none; - margin: 0; -} - -div.toc ul { - list-style: none outside none; - border: medium none; - padding: 0px; -} - -div.toc li.level1 { - margin-left: 0px; -} - -div.toc li.level2 { - margin-left: 15px; -} - -div.toc li.level3 { - margin-left: 15px; -} - -div.toc li.level4 { - margin-left: 15px; -} - -span.emoji { - /* font family used at the site: https://unicode.org/emoji/charts/full-emoji-list.html - * font-family: "Noto Color Emoji", "Apple Color Emoji", "Segoe UI Emoji", Times, Symbola, Aegyptus, Code2000, Code2001, Code2002, Musica, serif, LastResort; - */ -} - -span.obfuscator { - display: none; -} - -.inherit_header { - font-weight: bold; - color: var(--inherit-header-color); - cursor: pointer; - -webkit-touch-callout: none; - -webkit-user-select: none; - -khtml-user-select: none; - -moz-user-select: none; - -ms-user-select: none; - user-select: none; -} - -.inherit_header td { - padding: 6px 0px 2px 5px; -} - -.inherit { - display: none; -} - -tr.heading h2 { - margin-top: 12px; - margin-bottom: 4px; -} - -/* tooltip related style info */ - -.ttc { - position: absolute; - display: none; -} - -#powerTip { - cursor: default; - /*white-space: nowrap;*/ - color: var(--tooltip-foreground-color); - background-color: var(--tooltip-background-color); - border: 1px solid var(--tooltip-border-color); - border-radius: 4px 4px 4px 4px; - box-shadow: var(--tooltip-shadow); - display: none; - font-size: smaller; - max-width: 80%; - opacity: 0.9; - padding: 1ex 1em 1em; - position: absolute; - z-index: 2147483647; -} - -#powerTip div.ttdoc { - color: var(--tooltip-doc-color); - font-style: italic; -} - -#powerTip div.ttname a { - font-weight: bold; -} - -#powerTip a { - color: var(--tooltip-link-color); -} - -#powerTip div.ttname { - font-weight: bold; -} - -#powerTip div.ttdeci { - color: var(--tooltip-declaration-color); -} - -#powerTip div { - margin: 0px; - padding: 0px; - font-size: 12px; - font-family: var(--font-family-tooltip); - line-height: 16px; -} - -#powerTip:before, #powerTip:after { - content: ""; - position: absolute; - margin: 0px; -} - -#powerTip.n:after, #powerTip.n:before, -#powerTip.s:after, #powerTip.s:before, -#powerTip.w:after, #powerTip.w:before, -#powerTip.e:after, #powerTip.e:before, -#powerTip.ne:after, #powerTip.ne:before, -#powerTip.se:after, #powerTip.se:before, -#powerTip.nw:after, #powerTip.nw:before, -#powerTip.sw:after, #powerTip.sw:before { - border: solid transparent; - content: " "; - height: 0; - width: 0; - position: absolute; -} - -#powerTip.n:after, #powerTip.s:after, -#powerTip.w:after, #powerTip.e:after, -#powerTip.nw:after, #powerTip.ne:after, -#powerTip.sw:after, #powerTip.se:after { - border-color: rgba(255, 255, 255, 0); -} - -#powerTip.n:before, #powerTip.s:before, -#powerTip.w:before, #powerTip.e:before, -#powerTip.nw:before, #powerTip.ne:before, -#powerTip.sw:before, #powerTip.se:before { - border-color: rgba(128, 128, 128, 0); -} - -#powerTip.n:after, #powerTip.n:before, -#powerTip.ne:after, #powerTip.ne:before, -#powerTip.nw:after, #powerTip.nw:before { - top: 100%; -} - -#powerTip.n:after, #powerTip.ne:after, #powerTip.nw:after { - border-top-color: var(--tooltip-background-color); - border-width: 10px; - margin: 0px -10px; -} -#powerTip.n:before, #powerTip.ne:before, #powerTip.nw:before { - border-top-color: var(--tooltip-border-color); - border-width: 11px; - margin: 0px -11px; -} -#powerTip.n:after, #powerTip.n:before { - left: 50%; -} - -#powerTip.nw:after, #powerTip.nw:before { - right: 14px; -} - -#powerTip.ne:after, #powerTip.ne:before { - left: 14px; -} - -#powerTip.s:after, #powerTip.s:before, -#powerTip.se:after, #powerTip.se:before, -#powerTip.sw:after, #powerTip.sw:before { - bottom: 100%; -} - -#powerTip.s:after, #powerTip.se:after, #powerTip.sw:after { - border-bottom-color: var(--tooltip-background-color); - border-width: 10px; - margin: 0px -10px; -} - -#powerTip.s:before, #powerTip.se:before, #powerTip.sw:before { - border-bottom-color: var(--tooltip-border-color); - border-width: 11px; - margin: 0px -11px; -} - -#powerTip.s:after, #powerTip.s:before { - left: 50%; -} - -#powerTip.sw:after, #powerTip.sw:before { - right: 14px; -} - -#powerTip.se:after, #powerTip.se:before { - left: 14px; -} - -#powerTip.e:after, #powerTip.e:before { - left: 100%; -} -#powerTip.e:after { - border-left-color: var(--tooltip-border-color); - border-width: 10px; - top: 50%; - margin-top: -10px; -} -#powerTip.e:before { - border-left-color: var(--tooltip-border-color); - border-width: 11px; - top: 50%; - margin-top: -11px; -} - -#powerTip.w:after, #powerTip.w:before { - right: 100%; -} -#powerTip.w:after { - border-right-color: var(--tooltip-border-color); - border-width: 10px; - top: 50%; - margin-top: -10px; -} -#powerTip.w:before { - border-right-color: var(--tooltip-border-color); - border-width: 11px; - top: 50%; - margin-top: -11px; -} - -@media print -{ - #top { display: none; } - #side-nav { display: none; } - #nav-path { display: none; } - body { overflow:visible; } - h1, h2, h3, h4, h5, h6 { page-break-after: avoid; } - .summary { display: none; } - .memitem { page-break-inside: avoid; } - #doc-content - { - margin-left:0 !important; - height:auto !important; - width:auto !important; - overflow:inherit; - display:inline; - } -} - -/* @group Markdown */ - -table.markdownTable { - border-collapse:collapse; - margin-top: 4px; - margin-bottom: 4px; -} - -table.markdownTable td, table.markdownTable th { - border: 1px solid var(--table-cell-border-color); - padding: 3px 7px 2px; -} - -table.markdownTable tr { -} - -th.markdownTableHeadLeft, th.markdownTableHeadRight, th.markdownTableHeadCenter, th.markdownTableHeadNone { - background-color: var(--table-header-background-color); - color: var(--table-header-foreground-color); - font-size: 110%; - padding-bottom: 4px; - padding-top: 5px; -} - -th.markdownTableHeadLeft, td.markdownTableBodyLeft { - text-align: left -} - -th.markdownTableHeadRight, td.markdownTableBodyRight { - text-align: right -} - -th.markdownTableHeadCenter, td.markdownTableBodyCenter { - text-align: center -} - -tt, code, kbd, samp -{ - display: inline-block; -} -/* @end */ - -u { - text-decoration: underline; -} - -details>summary { - list-style-type: none; -} - -details > summary::-webkit-details-marker { - display: none; -} - -details>summary::before { - content: "\25ba"; - padding-right:4px; - font-size: 80%; -} - -details[open]>summary::before { - content: "\25bc"; - padding-right:4px; - font-size: 80%; -} - -body { - scrollbar-color: var(--scrollbar-thumb-color) var(--scrollbar-background-color); -} - -::-webkit-scrollbar { - background-color: var(--scrollbar-background-color); - height: 12px; - width: 12px; -} -::-webkit-scrollbar-thumb { - border-radius: 6px; - box-shadow: inset 0 0 12px 12px var(--scrollbar-thumb-color); - border: solid 2px transparent; -} -::-webkit-scrollbar-corner { - background-color: var(--scrollbar-background-color); -} - diff --git a/documentation/html/doxygen.svg b/documentation/html/doxygen.svg deleted file mode 100644 index 79a7635..0000000 --- a/documentation/html/doxygen.svg +++ /dev/null @@ -1,28 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/doxygen_crawl.html b/documentation/html/doxygen_crawl.html deleted file mode 100644 index 7592d75..0000000 --- a/documentation/html/doxygen_crawl.html +++ /dev/null @@ -1,155 +0,0 @@ - - - -Validator / crawler helper - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - diff --git a/documentation/html/dynsections.js b/documentation/html/dynsections.js deleted file mode 100644 index 8f49326..0000000 --- a/documentation/html/dynsections.js +++ /dev/null @@ -1,194 +0,0 @@ -/* - @licstart The following is the entire license notice for the JavaScript code in this file. - - The MIT License (MIT) - - Copyright (C) 1997-2020 by Dimitri van Heesch - - Permission is hereby granted, free of charge, to any person obtaining a copy of this software - and associated documentation files (the "Software"), to deal in the Software without restriction, - including without limitation the rights to use, copy, modify, merge, publish, distribute, - sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in all copies or - substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - - @licend The above is the entire license notice for the JavaScript code in this file - */ - -let dynsection = { - - // helper function - updateStripes : function() { - $('table.directory tr'). - removeClass('even').filter(':visible:even').addClass('even'); - $('table.directory tr'). - removeClass('odd').filter(':visible:odd').addClass('odd'); - }, - - toggleVisibility : function(linkObj) { - const base = $(linkObj).attr('id'); - const summary = $('#'+base+'-summary'); - const content = $('#'+base+'-content'); - const trigger = $('#'+base+'-trigger'); - const src=$(trigger).attr('src'); - if (content.is(':visible')===true) { - content.hide(); - summary.show(); - $(linkObj).addClass('closed').removeClass('opened'); - $(trigger).attr('src',src.substring(0,src.length-8)+'closed.png'); - } else { - content.show(); - summary.hide(); - $(linkObj).removeClass('closed').addClass('opened'); - $(trigger).attr('src',src.substring(0,src.length-10)+'open.png'); - } - return false; - }, - - toggleLevel : function(level) { - $('table.directory tr').each(function() { - const l = this.id.split('_').length-1; - const i = $('#img'+this.id.substring(3)); - const a = $('#arr'+this.id.substring(3)); - if (l'); - // add vertical lines to other rows - $('span[class=lineno]').not(':eq(0)').append(''); - // add toggle controls to lines with fold divs - $('div[class=foldopen]').each(function() { - // extract specific id to use - const id = $(this).attr('id').replace('foldopen',''); - // extract start and end foldable fragment attributes - const start = $(this).attr('data-start'); - const end = $(this).attr('data-end'); - // replace normal fold span with controls for the first line of a foldable fragment - $(this).find('span[class=fold]:first').replaceWith(''); - // append div for folded (closed) representation - $(this).after(''); - // extract the first line from the "open" section to represent closed content - const line = $(this).children().first().clone(); - // remove any glow that might still be active on the original line - $(line).removeClass('glow'); - if (start) { - // if line already ends with a start marker (e.g. trailing {), remove it - $(line).html($(line).html().replace(new RegExp('\\s*'+start+'\\s*$','g'),'')); - } - // replace minus with plus symbol - $(line).find('span[class=fold]').css('background-image',codefold.plusImg[relPath]); - // append ellipsis - $(line).append(' '+start+''+end); - // insert constructed line into closed div - $('#foldclosed'+id).html(line); - }); - }, -}; -/* @license-end */ diff --git a/documentation/html/files.html b/documentation/html/files.html deleted file mode 100644 index ad38614..0000000 --- a/documentation/html/files.html +++ /dev/null @@ -1,128 +0,0 @@ - - - - - - - -esp32_BNO08x: File List - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
File List
-
-
-
Here is a list of all files with brief descriptions:
-
-
- - - - diff --git a/documentation/html/files_dup.js b/documentation/html/files_dup.js deleted file mode 100644 index 064c6c8..0000000 --- a/documentation/html/files_dup.js +++ /dev/null @@ -1,4 +0,0 @@ -var files_dup = -[ - [ "imu_update", "dir_85e9385bd83516731053aadc7da3c8af.html", "dir_85e9385bd83516731053aadc7da3c8af" ] -]; \ No newline at end of file diff --git a/documentation/html/folderclosed.svg b/documentation/html/folderclosed.svg deleted file mode 100644 index b04bed2..0000000 --- a/documentation/html/folderclosed.svg +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - diff --git a/documentation/html/folderclosedd.svg b/documentation/html/folderclosedd.svg deleted file mode 100644 index 52f0166..0000000 --- a/documentation/html/folderclosedd.svg +++ /dev/null @@ -1,11 +0,0 @@ - - - - - - - - - - diff --git a/documentation/html/folderopen.svg b/documentation/html/folderopen.svg deleted file mode 100644 index f6896dd..0000000 --- a/documentation/html/folderopen.svg +++ /dev/null @@ -1,17 +0,0 @@ - - - - - - - - - - diff --git a/documentation/html/folderopend.svg b/documentation/html/folderopend.svg deleted file mode 100644 index 2d1f06e..0000000 --- a/documentation/html/folderopend.svg +++ /dev/null @@ -1,12 +0,0 @@ - - - - - - - - - - - diff --git a/documentation/html/functions.html b/documentation/html/functions.html deleted file mode 100644 index c5346d1..0000000 --- a/documentation/html/functions.html +++ /dev/null @@ -1,119 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- a -

-
-
- - - - diff --git a/documentation/html/functions_b.html b/documentation/html/functions_b.html deleted file mode 100644 index 9896ed4..0000000 --- a/documentation/html/functions_b.html +++ /dev/null @@ -1,120 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- b -

-
-
- - - - diff --git a/documentation/html/functions_c.html b/documentation/html/functions_c.html deleted file mode 100644 index 609d1a4..0000000 --- a/documentation/html/functions_c.html +++ /dev/null @@ -1,151 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- c -

-
-
- - - - diff --git a/documentation/html/functions_d.html b/documentation/html/functions_d.html deleted file mode 100644 index 0831951..0000000 --- a/documentation/html/functions_d.html +++ /dev/null @@ -1,137 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- d -

    -
  • data_available() : BNO08x
  • -
  • data_proc_task : BNO08x::bno08x_init_status_t, BNO08x
  • -
  • data_proc_task_hdl : BNO08x
  • -
  • data_proc_task_trampoline() : BNO08x
  • -
  • deinit_gpio() : BNO08x
  • -
  • deinit_gpio_inputs() : BNO08x
  • -
  • deinit_gpio_outputs() : BNO08x
  • -
  • deinit_hint_isr() : BNO08x
  • -
  • deinit_spi() : BNO08x
  • -
  • destroy_test_imu() : BNO08xTestHelper
  • -
  • disable_accelerometer() : BNO08x
  • -
  • disable_activity_classifier() : BNO08x
  • -
  • disable_ARVR_stabilized_game_rotation_vector() : BNO08x
  • -
  • disable_ARVR_stabilized_rotation_vector() : BNO08x
  • -
  • disable_calibrated_gyro() : BNO08x
  • -
  • disable_game_rotation_vector() : BNO08x
  • -
  • disable_gravity() : BNO08x
  • -
  • disable_gyro_integrated_rotation_vector() : BNO08x
  • -
  • disable_linear_accelerometer() : BNO08x
  • -
  • disable_magnetometer() : BNO08x
  • -
  • disable_raw_mems_accelerometer() : BNO08x
  • -
  • disable_raw_mems_gyro() : BNO08x
  • -
  • disable_raw_mems_magnetometer() : BNO08x
  • -
  • disable_report() : BNO08x
  • -
  • disable_rotation_vector() : BNO08x
  • -
  • disable_stability_classifier() : BNO08x
  • -
  • disable_step_counter() : BNO08x
  • -
  • disable_tap_detector() : BNO08x
  • -
  • disable_uncalibrated_gyro() : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_dup.js b/documentation/html/functions_dup.js deleted file mode 100644 index 30c78b6..0000000 --- a/documentation/html/functions_dup.js +++ /dev/null @@ -1,23 +0,0 @@ -var functions_dup = -[ - [ "a", "functions.html", null ], - [ "b", "functions_b.html", null ], - [ "c", "functions_c.html", null ], - [ "d", "functions_d.html", null ], - [ "e", "functions_e.html", null ], - [ "f", "functions_f.html", null ], - [ "g", "functions_g.html", null ], - [ "h", "functions_h.html", null ], - [ "i", "functions_i.html", null ], - [ "k", "functions_k.html", null ], - [ "l", "functions_l.html", null ], - [ "m", "functions_m.html", null ], - [ "p", "functions_p.html", null ], - [ "q", "functions_q.html", null ], - [ "r", "functions_r.html", null ], - [ "s", "functions_s.html", null ], - [ "t", "functions_t.html", null ], - [ "u", "functions_u.html", null ], - [ "w", "functions_w.html", null ], - [ "~", "functions_~.html", null ] -]; \ No newline at end of file diff --git a/documentation/html/functions_e.html b/documentation/html/functions_e.html deleted file mode 100644 index 02f91ca..0000000 --- a/documentation/html/functions_e.html +++ /dev/null @@ -1,155 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- e -

    -
  • enable_accelerometer() : BNO08x
  • -
  • enable_activity_classifier() : BNO08x
  • -
  • enable_ARVR_stabilized_game_rotation_vector() : BNO08x
  • -
  • enable_ARVR_stabilized_rotation_vector() : BNO08x
  • -
  • enable_calibrated_gyro() : BNO08x
  • -
  • enable_game_rotation_vector() : BNO08x
  • -
  • enable_gravity() : BNO08x
  • -
  • enable_gyro_integrated_rotation_vector() : BNO08x
  • -
  • enable_linear_accelerometer() : BNO08x
  • -
  • enable_magnetometer() : BNO08x
  • -
  • enable_raw_mems_accelerometer() : BNO08x
  • -
  • enable_raw_mems_gyro() : BNO08x
  • -
  • enable_raw_mems_magnetometer() : BNO08x
  • -
  • enable_report() : BNO08x
  • -
  • enable_rotation_vector() : BNO08x
  • -
  • enable_stability_classifier() : BNO08x
  • -
  • enable_step_counter() : BNO08x
  • -
  • enable_tap_detector() : BNO08x
  • -
  • enable_uncalibrated_gyro() : BNO08x
  • -
  • end_calibration() : BNO08x
  • -
  • evt_grp_report_en : BNO08x
  • -
  • EVT_GRP_RPT_ACCELEROMETER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_ALL_BITS : BNO08x
  • -
  • EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BIT : BNO08x
  • -
  • EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BIT : BNO08x
  • -
  • EVT_GRP_RPT_GAME_ROTATION_VECTOR_BIT : BNO08x
  • -
  • EVT_GRP_RPT_GRAVITY_BIT : BNO08x
  • -
  • EVT_GRP_RPT_GYRO_BIT : BNO08x
  • -
  • EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BIT : BNO08x
  • -
  • EVT_GRP_RPT_GYRO_UNCALIBRATED_BIT : BNO08x
  • -
  • EVT_GRP_RPT_LINEAR_ACCELEROMETER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_MAGNETOMETER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_RAW_ACCELEROMETER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_RAW_GYRO_BIT : BNO08x
  • -
  • EVT_GRP_RPT_RAW_MAGNETOMETER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_ROTATION_VECTOR_BIT : BNO08x
  • -
  • EVT_GRP_RPT_STABILITY_CLASSIFIER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_STEP_COUNTER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_TAP_DETECTOR_BIT : BNO08x
  • -
  • evt_grp_spi : BNO08x
  • -
  • EVT_GRP_SPI_RX_DONE_BIT : BNO08x
  • -
  • EVT_GRP_SPI_RX_INVALID_PACKET_BIT : BNO08x
  • -
  • EVT_GRP_SPI_RX_VALID_PACKET_BIT : BNO08x
  • -
  • EVT_GRP_SPI_TX_DONE_BIT : BNO08x
  • -
  • evt_grp_task_flow : BNO08x
  • -
  • EVT_GRP_TSK_FLW_RUNNING_BIT : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_enum.html b/documentation/html/functions_enum.html deleted file mode 100644 index a544354..0000000 --- a/documentation/html/functions_enum.html +++ /dev/null @@ -1,107 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Enumerations - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all enums with links to the classes they belong to:
-
-
- - - - diff --git a/documentation/html/functions_eval.html b/documentation/html/functions_eval.html deleted file mode 100644 index 0abee6a..0000000 --- a/documentation/html/functions_eval.html +++ /dev/null @@ -1,112 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Enumerator - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all enum values with links to the classes they belong to:
-
-
- - - - diff --git a/documentation/html/functions_f.html b/documentation/html/functions_f.html deleted file mode 100644 index 40aa9f1..0000000 --- a/documentation/html/functions_f.html +++ /dev/null @@ -1,117 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- f -

    -
  • first_boot : BNO08x
  • -
  • flush_rx_packets() : BNO08x
  • -
  • FRS_read_data() : BNO08x
  • -
  • FRS_read_request() : BNO08x
  • -
  • FRS_read_word() : BNO08x
  • -
  • FRS_RECORD_ID_ACCELEROMETER : BNO08x
  • -
  • FRS_RECORD_ID_GYROSCOPE_CALIBRATED : BNO08x
  • -
  • FRS_RECORD_ID_MAGNETIC_FIELD_CALIBRATED : BNO08x
  • -
  • FRS_RECORD_ID_ROTATION_VECTOR : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_func.html b/documentation/html/functions_func.html deleted file mode 100644 index a293f69..0000000 --- a/documentation/html/functions_func.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- a -

-
-
- - - - diff --git a/documentation/html/functions_func.js b/documentation/html/functions_func.js deleted file mode 100644 index ed08dda..0000000 --- a/documentation/html/functions_func.js +++ /dev/null @@ -1,23 +0,0 @@ -var functions_func = -[ - [ "a", "functions_func.html", null ], - [ "b", "functions_func_b.html", null ], - [ "c", "functions_func_c.html", null ], - [ "d", "functions_func_d.html", null ], - [ "e", "functions_func_e.html", null ], - [ "f", "functions_func_f.html", null ], - [ "g", "functions_func_g.html", null ], - [ "h", "functions_func_h.html", null ], - [ "i", "functions_func_i.html", null ], - [ "k", "functions_func_k.html", null ], - [ "l", "functions_func_l.html", null ], - [ "m", "functions_func_m.html", null ], - [ "p", "functions_func_p.html", null ], - [ "q", "functions_func_q.html", null ], - [ "r", "functions_func_r.html", null ], - [ "s", "functions_func_s.html", null ], - [ "t", "functions_func_t.html", null ], - [ "u", "functions_func_u.html", null ], - [ "w", "functions_func_w.html", null ], - [ "~", "functions_func_~.html", null ] -]; \ No newline at end of file diff --git a/documentation/html/functions_func_b.html b/documentation/html/functions_func_b.html deleted file mode 100644 index 20abb43..0000000 --- a/documentation/html/functions_func_b.html +++ /dev/null @@ -1,114 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- b -

-
-
- - - - diff --git a/documentation/html/functions_func_c.html b/documentation/html/functions_func_c.html deleted file mode 100644 index 5f32b0e..0000000 --- a/documentation/html/functions_func_c.html +++ /dev/null @@ -1,122 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- c -

-
-
- - - - diff --git a/documentation/html/functions_func_d.html b/documentation/html/functions_func_d.html deleted file mode 100644 index c9452b7..0000000 --- a/documentation/html/functions_func_d.html +++ /dev/null @@ -1,136 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- d -

    -
  • data_available() : BNO08x
  • -
  • data_proc_task() : BNO08x
  • -
  • data_proc_task_trampoline() : BNO08x
  • -
  • deinit_gpio() : BNO08x
  • -
  • deinit_gpio_inputs() : BNO08x
  • -
  • deinit_gpio_outputs() : BNO08x
  • -
  • deinit_hint_isr() : BNO08x
  • -
  • deinit_spi() : BNO08x
  • -
  • destroy_test_imu() : BNO08xTestHelper
  • -
  • disable_accelerometer() : BNO08x
  • -
  • disable_activity_classifier() : BNO08x
  • -
  • disable_ARVR_stabilized_game_rotation_vector() : BNO08x
  • -
  • disable_ARVR_stabilized_rotation_vector() : BNO08x
  • -
  • disable_calibrated_gyro() : BNO08x
  • -
  • disable_game_rotation_vector() : BNO08x
  • -
  • disable_gravity() : BNO08x
  • -
  • disable_gyro_integrated_rotation_vector() : BNO08x
  • -
  • disable_linear_accelerometer() : BNO08x
  • -
  • disable_magnetometer() : BNO08x
  • -
  • disable_raw_mems_accelerometer() : BNO08x
  • -
  • disable_raw_mems_gyro() : BNO08x
  • -
  • disable_raw_mems_magnetometer() : BNO08x
  • -
  • disable_report() : BNO08x
  • -
  • disable_rotation_vector() : BNO08x
  • -
  • disable_stability_classifier() : BNO08x
  • -
  • disable_step_counter() : BNO08x
  • -
  • disable_tap_detector() : BNO08x
  • -
  • disable_uncalibrated_gyro() : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_func_e.html b/documentation/html/functions_func_e.html deleted file mode 100644 index 1700a9b..0000000 --- a/documentation/html/functions_func_e.html +++ /dev/null @@ -1,128 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- e -

    -
  • enable_accelerometer() : BNO08x
  • -
  • enable_activity_classifier() : BNO08x
  • -
  • enable_ARVR_stabilized_game_rotation_vector() : BNO08x
  • -
  • enable_ARVR_stabilized_rotation_vector() : BNO08x
  • -
  • enable_calibrated_gyro() : BNO08x
  • -
  • enable_game_rotation_vector() : BNO08x
  • -
  • enable_gravity() : BNO08x
  • -
  • enable_gyro_integrated_rotation_vector() : BNO08x
  • -
  • enable_linear_accelerometer() : BNO08x
  • -
  • enable_magnetometer() : BNO08x
  • -
  • enable_raw_mems_accelerometer() : BNO08x
  • -
  • enable_raw_mems_gyro() : BNO08x
  • -
  • enable_raw_mems_magnetometer() : BNO08x
  • -
  • enable_report() : BNO08x
  • -
  • enable_rotation_vector() : BNO08x
  • -
  • enable_stability_classifier() : BNO08x
  • -
  • enable_step_counter() : BNO08x
  • -
  • enable_tap_detector() : BNO08x
  • -
  • enable_uncalibrated_gyro() : BNO08x
  • -
  • end_calibration() : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_func_f.html b/documentation/html/functions_func_f.html deleted file mode 100644 index 7407183..0000000 --- a/documentation/html/functions_func_f.html +++ /dev/null @@ -1,112 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- f -

    -
  • flush_rx_packets() : BNO08x
  • -
  • FRS_read_data() : BNO08x
  • -
  • FRS_read_request() : BNO08x
  • -
  • FRS_read_word() : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_func_g.html b/documentation/html/functions_func_g.html deleted file mode 100644 index d7e01bf..0000000 --- a/documentation/html/functions_func_g.html +++ /dev/null @@ -1,182 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- g -

    -
  • get_accel() : BNO08x
  • -
  • get_accel_accuracy() : BNO08x
  • -
  • get_accel_X() : BNO08x
  • -
  • get_accel_Y() : BNO08x
  • -
  • get_accel_Z() : BNO08x
  • -
  • get_activity_classifier() : BNO08x
  • -
  • get_calibrated_gyro_velocity() : BNO08x
  • -
  • get_calibrated_gyro_velocity_X() : BNO08x
  • -
  • get_calibrated_gyro_velocity_Y() : BNO08x
  • -
  • get_calibrated_gyro_velocity_Z() : BNO08x
  • -
  • get_gravity() : BNO08x
  • -
  • get_gravity_accuracy() : BNO08x
  • -
  • get_gravity_X() : BNO08x
  • -
  • get_gravity_Y() : BNO08x
  • -
  • get_gravity_Z() : BNO08x
  • -
  • get_integrated_gyro_velocity() : BNO08x
  • -
  • get_integrated_gyro_velocity_X() : BNO08x
  • -
  • get_integrated_gyro_velocity_Y() : BNO08x
  • -
  • get_integrated_gyro_velocity_Z() : BNO08x
  • -
  • get_linear_accel() : BNO08x
  • -
  • get_linear_accel_accuracy() : BNO08x
  • -
  • get_linear_accel_X() : BNO08x
  • -
  • get_linear_accel_Y() : BNO08x
  • -
  • get_linear_accel_Z() : BNO08x
  • -
  • get_magf() : BNO08x
  • -
  • get_magf_accuracy() : BNO08x
  • -
  • get_magf_X() : BNO08x
  • -
  • get_magf_Y() : BNO08x
  • -
  • get_magf_Z() : BNO08x
  • -
  • get_pitch() : BNO08x
  • -
  • get_pitch_deg() : BNO08x
  • -
  • get_Q1() : BNO08x
  • -
  • get_Q2() : BNO08x
  • -
  • get_Q3() : BNO08x
  • -
  • get_quat() : BNO08x
  • -
  • get_quat_accuracy() : BNO08x
  • -
  • get_quat_I() : BNO08x
  • -
  • get_quat_J() : BNO08x
  • -
  • get_quat_K() : BNO08x
  • -
  • get_quat_radian_accuracy() : BNO08x
  • -
  • get_quat_real() : BNO08x
  • -
  • get_range() : BNO08x
  • -
  • get_raw_mems_accel() : BNO08x
  • -
  • get_raw_mems_accel_X() : BNO08x
  • -
  • get_raw_mems_accel_Y() : BNO08x
  • -
  • get_raw_mems_accel_Z() : BNO08x
  • -
  • get_raw_mems_gyro() : BNO08x
  • -
  • get_raw_mems_gyro_X() : BNO08x
  • -
  • get_raw_mems_gyro_Y() : BNO08x
  • -
  • get_raw_mems_gyro_Z() : BNO08x
  • -
  • get_raw_mems_magf() : BNO08x
  • -
  • get_raw_mems_magf_X() : BNO08x
  • -
  • get_raw_mems_magf_Y() : BNO08x
  • -
  • get_raw_mems_magf_Z() : BNO08x
  • -
  • get_reset_reason() : BNO08x
  • -
  • get_resolution() : BNO08x
  • -
  • get_roll() : BNO08x
  • -
  • get_roll_deg() : BNO08x
  • -
  • get_stability_classifier() : BNO08x
  • -
  • get_step_count() : BNO08x
  • -
  • get_tap_detector() : BNO08x
  • -
  • get_test_imu() : BNO08xTestHelper
  • -
  • get_time_stamp() : BNO08x
  • -
  • get_uncalibrated_gyro_bias_X() : BNO08x
  • -
  • get_uncalibrated_gyro_bias_Y() : BNO08x
  • -
  • get_uncalibrated_gyro_bias_Z() : BNO08x
  • -
  • get_uncalibrated_gyro_velocity() : BNO08x
  • -
  • get_uncalibrated_gyro_velocity_X() : BNO08x
  • -
  • get_uncalibrated_gyro_velocity_Y() : BNO08x
  • -
  • get_uncalibrated_gyro_velocity_Z() : BNO08x
  • -
  • get_yaw() : BNO08x
  • -
  • get_yaw_deg() : BNO08x
  • -
  • gravity_data_is_new() : BNO08xTestHelper
  • -
  • gyro_integrated_rotation_vector_data_is_new() : BNO08xTestHelper
  • -
-
-
- - - - diff --git a/documentation/html/functions_func_h.html b/documentation/html/functions_func_h.html deleted file mode 100644 index b8eb617..0000000 --- a/documentation/html/functions_func_h.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- h -

-
-
- - - - diff --git a/documentation/html/functions_func_i.html b/documentation/html/functions_func_i.html deleted file mode 100644 index ae1b21c..0000000 --- a/documentation/html/functions_func_i.html +++ /dev/null @@ -1,115 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- i -

-
-
- - - - diff --git a/documentation/html/functions_func_k.html b/documentation/html/functions_func_k.html deleted file mode 100644 index 694b859..0000000 --- a/documentation/html/functions_func_k.html +++ /dev/null @@ -1,109 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- k -

    -
  • kill_all_tasks() : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_func_l.html b/documentation/html/functions_func_l.html deleted file mode 100644 index 3ab300c..0000000 --- a/documentation/html/functions_func_l.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- l -

-
-
- - - - diff --git a/documentation/html/functions_func_m.html b/documentation/html/functions_func_m.html deleted file mode 100644 index 9761cac..0000000 --- a/documentation/html/functions_func_m.html +++ /dev/null @@ -1,111 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- m -

-
-
- - - - diff --git a/documentation/html/functions_func_p.html b/documentation/html/functions_func_p.html deleted file mode 100644 index 0b119e5..0000000 --- a/documentation/html/functions_func_p.html +++ /dev/null @@ -1,123 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- p -

-
-
- - - - diff --git a/documentation/html/functions_func_q.html b/documentation/html/functions_func_q.html deleted file mode 100644 index 6adeefc..0000000 --- a/documentation/html/functions_func_q.html +++ /dev/null @@ -1,115 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- q -

    -
  • q_to_float() : BNO08x
  • -
  • queue_calibrate_command() : BNO08x
  • -
  • queue_command() : BNO08x
  • -
  • queue_feature_command() : BNO08x
  • -
  • queue_packet() : BNO08x
  • -
  • queue_request_product_id_command() : BNO08x
  • -
  • queue_tare_command() : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_func_r.html b/documentation/html/functions_func_r.html deleted file mode 100644 index 92282b4..0000000 --- a/documentation/html/functions_func_r.html +++ /dev/null @@ -1,123 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- r -

-
-
- - - - diff --git a/documentation/html/functions_func_s.html b/documentation/html/functions_func_s.html deleted file mode 100644 index afd6e79..0000000 --- a/documentation/html/functions_func_s.html +++ /dev/null @@ -1,117 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- s -

-
-
- - - - diff --git a/documentation/html/functions_func_t.html b/documentation/html/functions_func_t.html deleted file mode 100644 index 921f559..0000000 --- a/documentation/html/functions_func_t.html +++ /dev/null @@ -1,109 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- t -

-
-
- - - - diff --git a/documentation/html/functions_func_u.html b/documentation/html/functions_func_u.html deleted file mode 100644 index 8b68358..0000000 --- a/documentation/html/functions_func_u.html +++ /dev/null @@ -1,127 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- u -

    -
  • uncalibrated_gyro_data_is_new() : BNO08xTestHelper
  • -
  • update_accelerometer_data() : BNO08x
  • -
  • update_calibrated_gyro_data() : BNO08x
  • -
  • update_command_data() : BNO08x
  • -
  • update_gravity_data() : BNO08x
  • -
  • update_integrated_gyro_rotation_vector_data() : BNO08x
  • -
  • update_lin_accelerometer_data() : BNO08x
  • -
  • update_magf_data() : BNO08x
  • -
  • update_personal_activity_classifier_data() : BNO08x
  • -
  • update_raw_accelerometer_data() : BNO08x
  • -
  • update_raw_gyro_data() : BNO08x
  • -
  • update_raw_magf_data() : BNO08x
  • -
  • update_report_data() : BNO08xTestHelper
  • -
  • update_report_period_trackers() : BNO08x
  • -
  • update_rotation_vector_data() : BNO08x
  • -
  • update_stability_classifier_data() : BNO08x
  • -
  • update_step_counter_data() : BNO08x
  • -
  • update_tap_detector_data() : BNO08x
  • -
  • update_uncalibrated_gyro_data() : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_func_w.html b/documentation/html/functions_func_w.html deleted file mode 100644 index d2b3978..0000000 --- a/documentation/html/functions_func_w.html +++ /dev/null @@ -1,111 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- w -

    -
  • wait_for_data() : BNO08x
  • -
  • wait_for_rx_done() : BNO08x
  • -
  • wait_for_tx_done() : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_func_~.html b/documentation/html/functions_func_~.html deleted file mode 100644 index 88ea8b9..0000000 --- a/documentation/html/functions_func_~.html +++ /dev/null @@ -1,109 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Functions - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the classes they belong to:
- -

- ~ -

-
-
- - - - diff --git a/documentation/html/functions_g.html b/documentation/html/functions_g.html deleted file mode 100644 index 8ce5bcd..0000000 --- a/documentation/html/functions_g.html +++ /dev/null @@ -1,194 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- g -

-
-
- - - - diff --git a/documentation/html/functions_h.html b/documentation/html/functions_h.html deleted file mode 100644 index f999984..0000000 --- a/documentation/html/functions_h.html +++ /dev/null @@ -1,114 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- h -

-
-
- - - - diff --git a/documentation/html/functions_i.html b/documentation/html/functions_i.html deleted file mode 100644 index 5c70b9a..0000000 --- a/documentation/html/functions_i.html +++ /dev/null @@ -1,136 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- i -

-
-
- - - - diff --git a/documentation/html/functions_k.html b/documentation/html/functions_k.html deleted file mode 100644 index b93f6bf..0000000 --- a/documentation/html/functions_k.html +++ /dev/null @@ -1,109 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- k -

    -
  • kill_all_tasks() : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_l.html b/documentation/html/functions_l.html deleted file mode 100644 index b2b29cd..0000000 --- a/documentation/html/functions_l.html +++ /dev/null @@ -1,117 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- l -

-
-
- - - - diff --git a/documentation/html/functions_m.html b/documentation/html/functions_m.html deleted file mode 100644 index 3bc01c1..0000000 --- a/documentation/html/functions_m.html +++ /dev/null @@ -1,127 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- m -

-
-
- - - - diff --git a/documentation/html/functions_p.html b/documentation/html/functions_p.html deleted file mode 100644 index 94197dd..0000000 --- a/documentation/html/functions_p.html +++ /dev/null @@ -1,124 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- p -

-
-
- - - - diff --git a/documentation/html/functions_q.html b/documentation/html/functions_q.html deleted file mode 100644 index 9d03fb4..0000000 --- a/documentation/html/functions_q.html +++ /dev/null @@ -1,125 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- q -

-
-
- - - - diff --git a/documentation/html/functions_r.html b/documentation/html/functions_r.html deleted file mode 100644 index d75ed49..0000000 --- a/documentation/html/functions_r.html +++ /dev/null @@ -1,155 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- r -

-
-
- - - - diff --git a/documentation/html/functions_rela.html b/documentation/html/functions_rela.html deleted file mode 100644 index 1a060c3..0000000 --- a/documentation/html/functions_rela.html +++ /dev/null @@ -1,107 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Related Symbols - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all related symbols with links to the classes they belong to:
    -
  • BNO08xTestHelper : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_s.html b/documentation/html/functions_s.html deleted file mode 100644 index c725c15..0000000 --- a/documentation/html/functions_s.html +++ /dev/null @@ -1,156 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- s -

-
-
- - - - diff --git a/documentation/html/functions_t.html b/documentation/html/functions_t.html deleted file mode 100644 index 4be1c00..0000000 --- a/documentation/html/functions_t.html +++ /dev/null @@ -1,126 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- t -

-
-
- - - - diff --git a/documentation/html/functions_type.html b/documentation/html/functions_type.html deleted file mode 100644 index 0dfa1c8..0000000 --- a/documentation/html/functions_type.html +++ /dev/null @@ -1,111 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Typedefs - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all typedefs with links to the classes they belong to:
-
-
- - - - diff --git a/documentation/html/functions_u.html b/documentation/html/functions_u.html deleted file mode 100644 index 9ff032e..0000000 --- a/documentation/html/functions_u.html +++ /dev/null @@ -1,133 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- u -

-
-
- - - - diff --git a/documentation/html/functions_vars.html b/documentation/html/functions_vars.html deleted file mode 100644 index a3ca4a8..0000000 --- a/documentation/html/functions_vars.html +++ /dev/null @@ -1,117 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- a -

-
-
- - - - diff --git a/documentation/html/functions_vars.js b/documentation/html/functions_vars.js deleted file mode 100644 index 6a01f27..0000000 --- a/documentation/html/functions_vars.js +++ /dev/null @@ -1,20 +0,0 @@ -var functions_vars = -[ - [ "a", "functions_vars.html", null ], - [ "b", "functions_vars_b.html", null ], - [ "c", "functions_vars_c.html", null ], - [ "d", "functions_vars_d.html", null ], - [ "e", "functions_vars_e.html", null ], - [ "f", "functions_vars_f.html", null ], - [ "g", "functions_vars_g.html", null ], - [ "h", "functions_vars_h.html", null ], - [ "i", "functions_vars_i.html", null ], - [ "l", "functions_vars_l.html", null ], - [ "m", "functions_vars_m.html", null ], - [ "p", "functions_vars_p.html", null ], - [ "q", "functions_vars_q.html", null ], - [ "r", "functions_vars_r.html", null ], - [ "s", "functions_vars_s.html", null ], - [ "t", "functions_vars_t.html", null ], - [ "u", "functions_vars_u.html", null ] -]; \ No newline at end of file diff --git a/documentation/html/functions_vars_b.html b/documentation/html/functions_vars_b.html deleted file mode 100644 index ee0ce79..0000000 --- a/documentation/html/functions_vars_b.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- b -

-
-
- - - - diff --git a/documentation/html/functions_vars_c.html b/documentation/html/functions_vars_c.html deleted file mode 100644 index 0fd4dc0..0000000 --- a/documentation/html/functions_vars_c.html +++ /dev/null @@ -1,130 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- c -

-
-
- - - - diff --git a/documentation/html/functions_vars_d.html b/documentation/html/functions_vars_d.html deleted file mode 100644 index 5374e1f..0000000 --- a/documentation/html/functions_vars_d.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- d -

-
-
- - - - diff --git a/documentation/html/functions_vars_e.html b/documentation/html/functions_vars_e.html deleted file mode 100644 index ee5f668..0000000 --- a/documentation/html/functions_vars_e.html +++ /dev/null @@ -1,135 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- e -

    -
  • evt_grp_report_en : BNO08x
  • -
  • EVT_GRP_RPT_ACCELEROMETER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_ALL_BITS : BNO08x
  • -
  • EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BIT : BNO08x
  • -
  • EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BIT : BNO08x
  • -
  • EVT_GRP_RPT_GAME_ROTATION_VECTOR_BIT : BNO08x
  • -
  • EVT_GRP_RPT_GRAVITY_BIT : BNO08x
  • -
  • EVT_GRP_RPT_GYRO_BIT : BNO08x
  • -
  • EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BIT : BNO08x
  • -
  • EVT_GRP_RPT_GYRO_UNCALIBRATED_BIT : BNO08x
  • -
  • EVT_GRP_RPT_LINEAR_ACCELEROMETER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_MAGNETOMETER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_RAW_ACCELEROMETER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_RAW_GYRO_BIT : BNO08x
  • -
  • EVT_GRP_RPT_RAW_MAGNETOMETER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_ROTATION_VECTOR_BIT : BNO08x
  • -
  • EVT_GRP_RPT_STABILITY_CLASSIFIER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_STEP_COUNTER_BIT : BNO08x
  • -
  • EVT_GRP_RPT_TAP_DETECTOR_BIT : BNO08x
  • -
  • evt_grp_spi : BNO08x
  • -
  • EVT_GRP_SPI_RX_DONE_BIT : BNO08x
  • -
  • EVT_GRP_SPI_RX_INVALID_PACKET_BIT : BNO08x
  • -
  • EVT_GRP_SPI_RX_VALID_PACKET_BIT : BNO08x
  • -
  • EVT_GRP_SPI_TX_DONE_BIT : BNO08x
  • -
  • evt_grp_task_flow : BNO08x
  • -
  • EVT_GRP_TSK_FLW_RUNNING_BIT : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_vars_f.html b/documentation/html/functions_vars_f.html deleted file mode 100644 index 6da50d2..0000000 --- a/documentation/html/functions_vars_f.html +++ /dev/null @@ -1,113 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- f -

    -
  • first_boot : BNO08x
  • -
  • FRS_RECORD_ID_ACCELEROMETER : BNO08x
  • -
  • FRS_RECORD_ID_GYROSCOPE_CALIBRATED : BNO08x
  • -
  • FRS_RECORD_ID_MAGNETIC_FIELD_CALIBRATED : BNO08x
  • -
  • FRS_RECORD_ID_ROTATION_VECTOR : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_vars_g.html b/documentation/html/functions_vars_g.html deleted file mode 100644 index c9edc09..0000000 --- a/documentation/html/functions_vars_g.html +++ /dev/null @@ -1,120 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- g -

-
-
- - - - diff --git a/documentation/html/functions_vars_h.html b/documentation/html/functions_vars_h.html deleted file mode 100644 index ba9765f..0000000 --- a/documentation/html/functions_vars_h.html +++ /dev/null @@ -1,112 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- h -

-
-
- - - - diff --git a/documentation/html/functions_vars_i.html b/documentation/html/functions_vars_i.html deleted file mode 100644 index 5901e52..0000000 --- a/documentation/html/functions_vars_i.html +++ /dev/null @@ -1,128 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- i -

-
-
- - - - diff --git a/documentation/html/functions_vars_l.html b/documentation/html/functions_vars_l.html deleted file mode 100644 index b0c399a..0000000 --- a/documentation/html/functions_vars_l.html +++ /dev/null @@ -1,115 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- l -

-
-
- - - - diff --git a/documentation/html/functions_vars_m.html b/documentation/html/functions_vars_m.html deleted file mode 100644 index 4befcb3..0000000 --- a/documentation/html/functions_vars_m.html +++ /dev/null @@ -1,124 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- m -

-
-
- - - - diff --git a/documentation/html/functions_vars_p.html b/documentation/html/functions_vars_p.html deleted file mode 100644 index cba0e53..0000000 --- a/documentation/html/functions_vars_p.html +++ /dev/null @@ -1,109 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- p -

-
-
- - - - diff --git a/documentation/html/functions_vars_q.html b/documentation/html/functions_vars_q.html deleted file mode 100644 index 8b7f2af..0000000 --- a/documentation/html/functions_vars_q.html +++ /dev/null @@ -1,118 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- q -

-
-
- - - - diff --git a/documentation/html/functions_vars_r.html b/documentation/html/functions_vars_r.html deleted file mode 100644 index 67f49a9..0000000 --- a/documentation/html/functions_vars_r.html +++ /dev/null @@ -1,140 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- r -

-
-
- - - - diff --git a/documentation/html/functions_vars_s.html b/documentation/html/functions_vars_s.html deleted file mode 100644 index 978f17c..0000000 --- a/documentation/html/functions_vars_s.html +++ /dev/null @@ -1,148 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- s -

-
-
- - - - diff --git a/documentation/html/functions_vars_t.html b/documentation/html/functions_vars_t.html deleted file mode 100644 index 910f7a8..0000000 --- a/documentation/html/functions_vars_t.html +++ /dev/null @@ -1,125 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- t -

-
-
- - - - diff --git a/documentation/html/functions_vars_u.html b/documentation/html/functions_vars_u.html deleted file mode 100644 index 01449ac..0000000 --- a/documentation/html/functions_vars_u.html +++ /dev/null @@ -1,114 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - Variables - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the classes they belong to:
- -

- u -

-
-
- - - - diff --git a/documentation/html/functions_w.html b/documentation/html/functions_w.html deleted file mode 100644 index 12857dc..0000000 --- a/documentation/html/functions_w.html +++ /dev/null @@ -1,111 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- w -

    -
  • wait_for_data() : BNO08x
  • -
  • wait_for_rx_done() : BNO08x
  • -
  • wait_for_tx_done() : BNO08x
  • -
-
-
- - - - diff --git a/documentation/html/functions_~.html b/documentation/html/functions_~.html deleted file mode 100644 index 893cc95..0000000 --- a/documentation/html/functions_~.html +++ /dev/null @@ -1,109 +0,0 @@ - - - - - - - -esp32_BNO08x: Class Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all class members with links to the classes they belong to:
- -

- ~ -

-
-
- - - - diff --git a/documentation/html/globals.html b/documentation/html/globals.html deleted file mode 100644 index 58afc61..0000000 --- a/documentation/html/globals.html +++ /dev/null @@ -1,210 +0,0 @@ - - - - - - - -esp32_BNO08x: File Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all file members with links to the files they belong to:
- -

- b -

- - -

- c -

- - -

- d -

- - -

- e -

- - -

- f -

- - -

- i -

- - -

- m -

- - -

- n -

- - -

- p -

- - -

- r -

- - -

- t -

- - -

- u -

-
-
- - - - diff --git a/documentation/html/globals_defs.html b/documentation/html/globals_defs.html deleted file mode 100644 index db98bb5..0000000 --- a/documentation/html/globals_defs.html +++ /dev/null @@ -1,153 +0,0 @@ - - - - - - - -esp32_BNO08x: File Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all macros with links to the files they belong to:
- -

- c -

- - -

- i -

- - -

- p -

- - -

- u -

-
-
- - - - diff --git a/documentation/html/globals_enum.html b/documentation/html/globals_enum.html deleted file mode 100644 index afeb6a1..0000000 --- a/documentation/html/globals_enum.html +++ /dev/null @@ -1,111 +0,0 @@ - - - - - - - -esp32_BNO08x: File Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all enums with links to the files they belong to:
-
-
- - - - diff --git a/documentation/html/globals_func.html b/documentation/html/globals_func.html deleted file mode 100644 index 1b22b77..0000000 --- a/documentation/html/globals_func.html +++ /dev/null @@ -1,132 +0,0 @@ - - - - - - - -esp32_BNO08x: File Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all functions with links to the files they belong to:
- -

- d -

- - -

- e -

- - -

- f -

- - -

- r -

- - -

- t -

-
-
- - - - diff --git a/documentation/html/globals_type.html b/documentation/html/globals_type.html deleted file mode 100644 index 22df633..0000000 --- a/documentation/html/globals_type.html +++ /dev/null @@ -1,110 +0,0 @@ - - - - - - - -esp32_BNO08x: File Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all typedefs with links to the files they belong to:
-
-
- - - - diff --git a/documentation/html/globals_vars.html b/documentation/html/globals_vars.html deleted file mode 100644 index 18d2436..0000000 --- a/documentation/html/globals_vars.html +++ /dev/null @@ -1,114 +0,0 @@ - - - - - - - -esp32_BNO08x: File Members - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Here is a list of all variables with links to the files they belong to:
-
-
- - - - diff --git a/documentation/html/graph_legend.html b/documentation/html/graph_legend.html deleted file mode 100644 index 2e8a503..0000000 --- a/documentation/html/graph_legend.html +++ /dev/null @@ -1,167 +0,0 @@ - - - - - - - -esp32_BNO08x: Graph Legend - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
Graph Legend
-
-
-

This page explains how to interpret the graphs that are generated by doxygen.

-

Consider the following example:

/*! Invisible class because of truncation */
-
class Invisible { };
-
-
/*! Truncated class, inheritance relation is hidden */
-
class Truncated : public Invisible { };
-
-
/* Class not documented with doxygen comments */
-
class Undocumented { };
-
-
/*! Class that is inherited using public inheritance */
-
class PublicBase : public Truncated { };
-
-
/*! A template class */
-
template<class T> class Templ { };
-
-
/*! Class that is inherited using protected inheritance */
-
class ProtectedBase { };
-
-
/*! Class that is inherited using private inheritance */
-
class PrivateBase { };
-
-
/*! Class that is used by the Inherited class */
-
class Used { };
-
-
/*! Super class that inherits a number of other classes */
-
class Inherited : public PublicBase,
-
protected ProtectedBase,
-
private PrivateBase,
-
public Undocumented,
-
public Templ<int>
-
{
-
private:
-
Used *m_usedClass;
-
};
-

This will result in the following graph:

-

The boxes in the above graph have the following meaning:

-
    -
  • -A filled gray box represents the struct or class for which the graph is generated.
  • -
  • -A box with a black border denotes a documented struct or class.
  • -
  • -A box with a gray border denotes an undocumented struct or class.
  • -
  • -A box with a red border denotes a documented struct or class forwhich not all inheritance/containment relations are shown. A graph is truncated if it does not fit within the specified boundaries.
  • -
-

The arrows have the following meaning:

-
    -
  • -A blue arrow is used to visualize a public inheritance relation between two classes.
  • -
  • -A dark green arrow is used for protected inheritance.
  • -
  • -A dark red arrow is used for private inheritance.
  • -
  • -A purple dashed arrow is used if a class is contained or used by another class. The arrow is labelled with the variable(s) through which the pointed class or struct is accessible.
  • -
  • -A yellow dashed arrow denotes a relation between a template instance and the template class it was instantiated from. The arrow is labelled with the template parameters of the instance.
  • -
-
-
- - - - diff --git a/documentation/html/graph_legend.md5 b/documentation/html/graph_legend.md5 deleted file mode 100644 index da515da..0000000 --- a/documentation/html/graph_legend.md5 +++ /dev/null @@ -1 +0,0 @@ -f74606a252eb303675caf37987d0b7af \ No newline at end of file diff --git a/documentation/html/graph_legend.png b/documentation/html/graph_legend.png deleted file mode 100644 index 22d00a2..0000000 Binary files a/documentation/html/graph_legend.png and /dev/null differ diff --git a/documentation/html/index.html b/documentation/html/index.html deleted file mode 100644 index c4e8333..0000000 --- a/documentation/html/index.html +++ /dev/null @@ -1,108 +0,0 @@ - - - - - - - -esp32_BNO08x: Main Page - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
esp32_BNO08x Documentation
-
-
- -
-
- - - - diff --git a/documentation/html/jquery.js b/documentation/html/jquery.js deleted file mode 100644 index 1dffb65..0000000 --- a/documentation/html/jquery.js +++ /dev/null @@ -1,34 +0,0 @@ -/*! jQuery v3.6.0 | (c) OpenJS Foundation and other contributors | jquery.org/license */ -!function(e,t){"use strict";"object"==typeof module&&"object"==typeof module.exports?module.exports=e.document?t(e,!0):function(e){if(!e.document)throw new Error("jQuery requires a window with a document");return t(e)}:t(e)}("undefined"!=typeof window?window:this,function(C,e){"use strict";var t=[],r=Object.getPrototypeOf,s=t.slice,g=t.flat?function(e){return t.flat.call(e)}:function(e){return t.concat.apply([],e)},u=t.push,i=t.indexOf,n={},o=n.toString,v=n.hasOwnProperty,a=v.toString,l=a.call(Object),y={},m=function(e){return"function"==typeof e&&"number"!=typeof e.nodeType&&"function"!=typeof e.item},x=function(e){return null!=e&&e===e.window},E=C.document,c={type:!0,src:!0,nonce:!0,noModule:!0};function b(e,t,n){var r,i,o=(n=n||E).createElement("script");if(o.text=e,t)for(r in c)(i=t[r]||t.getAttribute&&t.getAttribute(r))&&o.setAttribute(r,i);n.head.appendChild(o).parentNode.removeChild(o)}function w(e){return null==e?e+"":"object"==typeof e||"function"==typeof e?n[o.call(e)]||"object":typeof e}var f="3.6.0",S=function(e,t){return new S.fn.init(e,t)};function p(e){var t=!!e&&"length"in e&&e.length,n=w(e);return!m(e)&&!x(e)&&("array"===n||0===t||"number"==typeof t&&0+~]|"+M+")"+M+"*"),U=new RegExp(M+"|>"),X=new RegExp(F),V=new RegExp("^"+I+"$"),G={ID:new RegExp("^#("+I+")"),CLASS:new RegExp("^\\.("+I+")"),TAG:new RegExp("^("+I+"|[*])"),ATTR:new RegExp("^"+W),PSEUDO:new RegExp("^"+F),CHILD:new RegExp("^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\("+M+"*(even|odd|(([+-]|)(\\d*)n|)"+M+"*(?:([+-]|)"+M+"*(\\d+)|))"+M+"*\\)|)","i"),bool:new RegExp("^(?:"+R+")$","i"),needsContext:new RegExp("^"+M+"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\("+M+"*((?:-\\d)?\\d*)"+M+"*\\)|)(?=[^-]|$)","i")},Y=/HTML$/i,Q=/^(?:input|select|textarea|button)$/i,J=/^h\d$/i,K=/^[^{]+\{\s*\[native \w/,Z=/^(?:#([\w-]+)|(\w+)|\.([\w-]+))$/,ee=/[+~]/,te=new RegExp("\\\\[\\da-fA-F]{1,6}"+M+"?|\\\\([^\\r\\n\\f])","g"),ne=function(e,t){var n="0x"+e.slice(1)-65536;return t||(n<0?String.fromCharCode(n+65536):String.fromCharCode(n>>10|55296,1023&n|56320))},re=/([\0-\x1f\x7f]|^-?\d)|^-$|[^\0-\x1f\x7f-\uFFFF\w-]/g,ie=function(e,t){return t?"\0"===e?"\ufffd":e.slice(0,-1)+"\\"+e.charCodeAt(e.length-1).toString(16)+" ":"\\"+e},oe=function(){T()},ae=be(function(e){return!0===e.disabled&&"fieldset"===e.nodeName.toLowerCase()},{dir:"parentNode",next:"legend"});try{H.apply(t=O.call(p.childNodes),p.childNodes),t[p.childNodes.length].nodeType}catch(e){H={apply:t.length?function(e,t){L.apply(e,O.call(t))}:function(e,t){var n=e.length,r=0;while(e[n++]=t[r++]);e.length=n-1}}}function se(t,e,n,r){var i,o,a,s,u,l,c,f=e&&e.ownerDocument,p=e?e.nodeType:9;if(n=n||[],"string"!=typeof t||!t||1!==p&&9!==p&&11!==p)return n;if(!r&&(T(e),e=e||C,E)){if(11!==p&&(u=Z.exec(t)))if(i=u[1]){if(9===p){if(!(a=e.getElementById(i)))return n;if(a.id===i)return n.push(a),n}else if(f&&(a=f.getElementById(i))&&y(e,a)&&a.id===i)return n.push(a),n}else{if(u[2])return H.apply(n,e.getElementsByTagName(t)),n;if((i=u[3])&&d.getElementsByClassName&&e.getElementsByClassName)return H.apply(n,e.getElementsByClassName(i)),n}if(d.qsa&&!N[t+" "]&&(!v||!v.test(t))&&(1!==p||"object"!==e.nodeName.toLowerCase())){if(c=t,f=e,1===p&&(U.test(t)||z.test(t))){(f=ee.test(t)&&ye(e.parentNode)||e)===e&&d.scope||((s=e.getAttribute("id"))?s=s.replace(re,ie):e.setAttribute("id",s=S)),o=(l=h(t)).length;while(o--)l[o]=(s?"#"+s:":scope")+" "+xe(l[o]);c=l.join(",")}try{return H.apply(n,f.querySelectorAll(c)),n}catch(e){N(t,!0)}finally{s===S&&e.removeAttribute("id")}}}return g(t.replace($,"$1"),e,n,r)}function ue(){var r=[];return function e(t,n){return r.push(t+" ")>b.cacheLength&&delete e[r.shift()],e[t+" "]=n}}function le(e){return e[S]=!0,e}function ce(e){var t=C.createElement("fieldset");try{return!!e(t)}catch(e){return!1}finally{t.parentNode&&t.parentNode.removeChild(t),t=null}}function fe(e,t){var n=e.split("|"),r=n.length;while(r--)b.attrHandle[n[r]]=t}function pe(e,t){var n=t&&e,r=n&&1===e.nodeType&&1===t.nodeType&&e.sourceIndex-t.sourceIndex;if(r)return r;if(n)while(n=n.nextSibling)if(n===t)return-1;return e?1:-1}function de(t){return function(e){return"input"===e.nodeName.toLowerCase()&&e.type===t}}function he(n){return function(e){var t=e.nodeName.toLowerCase();return("input"===t||"button"===t)&&e.type===n}}function ge(t){return function(e){return"form"in e?e.parentNode&&!1===e.disabled?"label"in e?"label"in e.parentNode?e.parentNode.disabled===t:e.disabled===t:e.isDisabled===t||e.isDisabled!==!t&&ae(e)===t:e.disabled===t:"label"in e&&e.disabled===t}}function ve(a){return le(function(o){return o=+o,le(function(e,t){var n,r=a([],e.length,o),i=r.length;while(i--)e[n=r[i]]&&(e[n]=!(t[n]=e[n]))})})}function ye(e){return e&&"undefined"!=typeof e.getElementsByTagName&&e}for(e in d=se.support={},i=se.isXML=function(e){var t=e&&e.namespaceURI,n=e&&(e.ownerDocument||e).documentElement;return!Y.test(t||n&&n.nodeName||"HTML")},T=se.setDocument=function(e){var t,n,r=e?e.ownerDocument||e:p;return r!=C&&9===r.nodeType&&r.documentElement&&(a=(C=r).documentElement,E=!i(C),p!=C&&(n=C.defaultView)&&n.top!==n&&(n.addEventListener?n.addEventListener("unload",oe,!1):n.attachEvent&&n.attachEvent("onunload",oe)),d.scope=ce(function(e){return a.appendChild(e).appendChild(C.createElement("div")),"undefined"!=typeof e.querySelectorAll&&!e.querySelectorAll(":scope fieldset div").length}),d.attributes=ce(function(e){return e.className="i",!e.getAttribute("className")}),d.getElementsByTagName=ce(function(e){return e.appendChild(C.createComment("")),!e.getElementsByTagName("*").length}),d.getElementsByClassName=K.test(C.getElementsByClassName),d.getById=ce(function(e){return a.appendChild(e).id=S,!C.getElementsByName||!C.getElementsByName(S).length}),d.getById?(b.filter.ID=function(e){var t=e.replace(te,ne);return function(e){return e.getAttribute("id")===t}},b.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&E){var n=t.getElementById(e);return n?[n]:[]}}):(b.filter.ID=function(e){var n=e.replace(te,ne);return function(e){var t="undefined"!=typeof e.getAttributeNode&&e.getAttributeNode("id");return t&&t.value===n}},b.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&E){var n,r,i,o=t.getElementById(e);if(o){if((n=o.getAttributeNode("id"))&&n.value===e)return[o];i=t.getElementsByName(e),r=0;while(o=i[r++])if((n=o.getAttributeNode("id"))&&n.value===e)return[o]}return[]}}),b.find.TAG=d.getElementsByTagName?function(e,t){return"undefined"!=typeof t.getElementsByTagName?t.getElementsByTagName(e):d.qsa?t.querySelectorAll(e):void 0}:function(e,t){var n,r=[],i=0,o=t.getElementsByTagName(e);if("*"===e){while(n=o[i++])1===n.nodeType&&r.push(n);return r}return o},b.find.CLASS=d.getElementsByClassName&&function(e,t){if("undefined"!=typeof t.getElementsByClassName&&E)return t.getElementsByClassName(e)},s=[],v=[],(d.qsa=K.test(C.querySelectorAll))&&(ce(function(e){var t;a.appendChild(e).innerHTML="",e.querySelectorAll("[msallowcapture^='']").length&&v.push("[*^$]="+M+"*(?:''|\"\")"),e.querySelectorAll("[selected]").length||v.push("\\["+M+"*(?:value|"+R+")"),e.querySelectorAll("[id~="+S+"-]").length||v.push("~="),(t=C.createElement("input")).setAttribute("name",""),e.appendChild(t),e.querySelectorAll("[name='']").length||v.push("\\["+M+"*name"+M+"*="+M+"*(?:''|\"\")"),e.querySelectorAll(":checked").length||v.push(":checked"),e.querySelectorAll("a#"+S+"+*").length||v.push(".#.+[+~]"),e.querySelectorAll("\\\f"),v.push("[\\r\\n\\f]")}),ce(function(e){e.innerHTML="";var t=C.createElement("input");t.setAttribute("type","hidden"),e.appendChild(t).setAttribute("name","D"),e.querySelectorAll("[name=d]").length&&v.push("name"+M+"*[*^$|!~]?="),2!==e.querySelectorAll(":enabled").length&&v.push(":enabled",":disabled"),a.appendChild(e).disabled=!0,2!==e.querySelectorAll(":disabled").length&&v.push(":enabled",":disabled"),e.querySelectorAll("*,:x"),v.push(",.*:")})),(d.matchesSelector=K.test(c=a.matches||a.webkitMatchesSelector||a.mozMatchesSelector||a.oMatchesSelector||a.msMatchesSelector))&&ce(function(e){d.disconnectedMatch=c.call(e,"*"),c.call(e,"[s!='']:x"),s.push("!=",F)}),v=v.length&&new RegExp(v.join("|")),s=s.length&&new RegExp(s.join("|")),t=K.test(a.compareDocumentPosition),y=t||K.test(a.contains)?function(e,t){var n=9===e.nodeType?e.documentElement:e,r=t&&t.parentNode;return e===r||!(!r||1!==r.nodeType||!(n.contains?n.contains(r):e.compareDocumentPosition&&16&e.compareDocumentPosition(r)))}:function(e,t){if(t)while(t=t.parentNode)if(t===e)return!0;return!1},j=t?function(e,t){if(e===t)return l=!0,0;var n=!e.compareDocumentPosition-!t.compareDocumentPosition;return n||(1&(n=(e.ownerDocument||e)==(t.ownerDocument||t)?e.compareDocumentPosition(t):1)||!d.sortDetached&&t.compareDocumentPosition(e)===n?e==C||e.ownerDocument==p&&y(p,e)?-1:t==C||t.ownerDocument==p&&y(p,t)?1:u?P(u,e)-P(u,t):0:4&n?-1:1)}:function(e,t){if(e===t)return l=!0,0;var n,r=0,i=e.parentNode,o=t.parentNode,a=[e],s=[t];if(!i||!o)return e==C?-1:t==C?1:i?-1:o?1:u?P(u,e)-P(u,t):0;if(i===o)return pe(e,t);n=e;while(n=n.parentNode)a.unshift(n);n=t;while(n=n.parentNode)s.unshift(n);while(a[r]===s[r])r++;return r?pe(a[r],s[r]):a[r]==p?-1:s[r]==p?1:0}),C},se.matches=function(e,t){return se(e,null,null,t)},se.matchesSelector=function(e,t){if(T(e),d.matchesSelector&&E&&!N[t+" "]&&(!s||!s.test(t))&&(!v||!v.test(t)))try{var n=c.call(e,t);if(n||d.disconnectedMatch||e.document&&11!==e.document.nodeType)return n}catch(e){N(t,!0)}return 0":{dir:"parentNode",first:!0}," ":{dir:"parentNode"},"+":{dir:"previousSibling",first:!0},"~":{dir:"previousSibling"}},preFilter:{ATTR:function(e){return e[1]=e[1].replace(te,ne),e[3]=(e[3]||e[4]||e[5]||"").replace(te,ne),"~="===e[2]&&(e[3]=" "+e[3]+" "),e.slice(0,4)},CHILD:function(e){return e[1]=e[1].toLowerCase(),"nth"===e[1].slice(0,3)?(e[3]||se.error(e[0]),e[4]=+(e[4]?e[5]+(e[6]||1):2*("even"===e[3]||"odd"===e[3])),e[5]=+(e[7]+e[8]||"odd"===e[3])):e[3]&&se.error(e[0]),e},PSEUDO:function(e){var t,n=!e[6]&&e[2];return G.CHILD.test(e[0])?null:(e[3]?e[2]=e[4]||e[5]||"":n&&X.test(n)&&(t=h(n,!0))&&(t=n.indexOf(")",n.length-t)-n.length)&&(e[0]=e[0].slice(0,t),e[2]=n.slice(0,t)),e.slice(0,3))}},filter:{TAG:function(e){var t=e.replace(te,ne).toLowerCase();return"*"===e?function(){return!0}:function(e){return e.nodeName&&e.nodeName.toLowerCase()===t}},CLASS:function(e){var t=m[e+" "];return t||(t=new RegExp("(^|"+M+")"+e+"("+M+"|$)"))&&m(e,function(e){return t.test("string"==typeof e.className&&e.className||"undefined"!=typeof e.getAttribute&&e.getAttribute("class")||"")})},ATTR:function(n,r,i){return function(e){var t=se.attr(e,n);return null==t?"!="===r:!r||(t+="","="===r?t===i:"!="===r?t!==i:"^="===r?i&&0===t.indexOf(i):"*="===r?i&&-1:\x20\t\r\n\f]*)[\x20\t\r\n\f]*\/?>(?:<\/\1>|)$/i;function j(e,n,r){return m(n)?S.grep(e,function(e,t){return!!n.call(e,t,e)!==r}):n.nodeType?S.grep(e,function(e){return e===n!==r}):"string"!=typeof n?S.grep(e,function(e){return-1)[^>]*|#([\w-]+))$/;(S.fn.init=function(e,t,n){var r,i;if(!e)return this;if(n=n||D,"string"==typeof e){if(!(r="<"===e[0]&&">"===e[e.length-1]&&3<=e.length?[null,e,null]:q.exec(e))||!r[1]&&t)return!t||t.jquery?(t||n).find(e):this.constructor(t).find(e);if(r[1]){if(t=t instanceof S?t[0]:t,S.merge(this,S.parseHTML(r[1],t&&t.nodeType?t.ownerDocument||t:E,!0)),N.test(r[1])&&S.isPlainObject(t))for(r in t)m(this[r])?this[r](t[r]):this.attr(r,t[r]);return this}return(i=E.getElementById(r[2]))&&(this[0]=i,this.length=1),this}return e.nodeType?(this[0]=e,this.length=1,this):m(e)?void 0!==n.ready?n.ready(e):e(S):S.makeArray(e,this)}).prototype=S.fn,D=S(E);var L=/^(?:parents|prev(?:Until|All))/,H={children:!0,contents:!0,next:!0,prev:!0};function O(e,t){while((e=e[t])&&1!==e.nodeType);return e}S.fn.extend({has:function(e){var t=S(e,this),n=t.length;return this.filter(function(){for(var e=0;e\x20\t\r\n\f]*)/i,he=/^$|^module$|\/(?:java|ecma)script/i;ce=E.createDocumentFragment().appendChild(E.createElement("div")),(fe=E.createElement("input")).setAttribute("type","radio"),fe.setAttribute("checked","checked"),fe.setAttribute("name","t"),ce.appendChild(fe),y.checkClone=ce.cloneNode(!0).cloneNode(!0).lastChild.checked,ce.innerHTML="",y.noCloneChecked=!!ce.cloneNode(!0).lastChild.defaultValue,ce.innerHTML="",y.option=!!ce.lastChild;var ge={thead:[1,"","
"],col:[2,"","
"],tr:[2,"","
"],td:[3,"","
"],_default:[0,"",""]};function ve(e,t){var n;return n="undefined"!=typeof e.getElementsByTagName?e.getElementsByTagName(t||"*"):"undefined"!=typeof e.querySelectorAll?e.querySelectorAll(t||"*"):[],void 0===t||t&&A(e,t)?S.merge([e],n):n}function ye(e,t){for(var n=0,r=e.length;n",""]);var me=/<|&#?\w+;/;function xe(e,t,n,r,i){for(var o,a,s,u,l,c,f=t.createDocumentFragment(),p=[],d=0,h=e.length;d\s*$/g;function je(e,t){return A(e,"table")&&A(11!==t.nodeType?t:t.firstChild,"tr")&&S(e).children("tbody")[0]||e}function De(e){return e.type=(null!==e.getAttribute("type"))+"/"+e.type,e}function qe(e){return"true/"===(e.type||"").slice(0,5)?e.type=e.type.slice(5):e.removeAttribute("type"),e}function Le(e,t){var n,r,i,o,a,s;if(1===t.nodeType){if(Y.hasData(e)&&(s=Y.get(e).events))for(i in Y.remove(t,"handle events"),s)for(n=0,r=s[i].length;n").attr(n.scriptAttrs||{}).prop({charset:n.scriptCharset,src:n.url}).on("load error",i=function(e){r.remove(),i=null,e&&t("error"===e.type?404:200,e.type)}),E.head.appendChild(r[0])},abort:function(){i&&i()}}});var _t,zt=[],Ut=/(=)\?(?=&|$)|\?\?/;S.ajaxSetup({jsonp:"callback",jsonpCallback:function(){var e=zt.pop()||S.expando+"_"+wt.guid++;return this[e]=!0,e}}),S.ajaxPrefilter("json jsonp",function(e,t,n){var r,i,o,a=!1!==e.jsonp&&(Ut.test(e.url)?"url":"string"==typeof e.data&&0===(e.contentType||"").indexOf("application/x-www-form-urlencoded")&&Ut.test(e.data)&&"data");if(a||"jsonp"===e.dataTypes[0])return r=e.jsonpCallback=m(e.jsonpCallback)?e.jsonpCallback():e.jsonpCallback,a?e[a]=e[a].replace(Ut,"$1"+r):!1!==e.jsonp&&(e.url+=(Tt.test(e.url)?"&":"?")+e.jsonp+"="+r),e.converters["script json"]=function(){return o||S.error(r+" was not called"),o[0]},e.dataTypes[0]="json",i=C[r],C[r]=function(){o=arguments},n.always(function(){void 0===i?S(C).removeProp(r):C[r]=i,e[r]&&(e.jsonpCallback=t.jsonpCallback,zt.push(r)),o&&m(i)&&i(o[0]),o=i=void 0}),"script"}),y.createHTMLDocument=((_t=E.implementation.createHTMLDocument("").body).innerHTML="
",2===_t.childNodes.length),S.parseHTML=function(e,t,n){return"string"!=typeof e?[]:("boolean"==typeof t&&(n=t,t=!1),t||(y.createHTMLDocument?((r=(t=E.implementation.createHTMLDocument("")).createElement("base")).href=E.location.href,t.head.appendChild(r)):t=E),o=!n&&[],(i=N.exec(e))?[t.createElement(i[1])]:(i=xe([e],t,o),o&&o.length&&S(o).remove(),S.merge([],i.childNodes)));var r,i,o},S.fn.load=function(e,t,n){var r,i,o,a=this,s=e.indexOf(" ");return-1").append(S.parseHTML(e)).find(r):e)}).always(n&&function(e,t){a.each(function(){n.apply(this,o||[e.responseText,t,e])})}),this},S.expr.pseudos.animated=function(t){return S.grep(S.timers,function(e){return t===e.elem}).length},S.offset={setOffset:function(e,t,n){var r,i,o,a,s,u,l=S.css(e,"position"),c=S(e),f={};"static"===l&&(e.style.position="relative"),s=c.offset(),o=S.css(e,"top"),u=S.css(e,"left"),("absolute"===l||"fixed"===l)&&-1<(o+u).indexOf("auto")?(a=(r=c.position()).top,i=r.left):(a=parseFloat(o)||0,i=parseFloat(u)||0),m(t)&&(t=t.call(e,n,S.extend({},s))),null!=t.top&&(f.top=t.top-s.top+a),null!=t.left&&(f.left=t.left-s.left+i),"using"in t?t.using.call(e,f):c.css(f)}},S.fn.extend({offset:function(t){if(arguments.length)return void 0===t?this:this.each(function(e){S.offset.setOffset(this,t,e)});var e,n,r=this[0];return r?r.getClientRects().length?(e=r.getBoundingClientRect(),n=r.ownerDocument.defaultView,{top:e.top+n.pageYOffset,left:e.left+n.pageXOffset}):{top:0,left:0}:void 0},position:function(){if(this[0]){var e,t,n,r=this[0],i={top:0,left:0};if("fixed"===S.css(r,"position"))t=r.getBoundingClientRect();else{t=this.offset(),n=r.ownerDocument,e=r.offsetParent||n.documentElement;while(e&&(e===n.body||e===n.documentElement)&&"static"===S.css(e,"position"))e=e.parentNode;e&&e!==r&&1===e.nodeType&&((i=S(e).offset()).top+=S.css(e,"borderTopWidth",!0),i.left+=S.css(e,"borderLeftWidth",!0))}return{top:t.top-i.top-S.css(r,"marginTop",!0),left:t.left-i.left-S.css(r,"marginLeft",!0)}}},offsetParent:function(){return this.map(function(){var e=this.offsetParent;while(e&&"static"===S.css(e,"position"))e=e.offsetParent;return e||re})}}),S.each({scrollLeft:"pageXOffset",scrollTop:"pageYOffset"},function(t,i){var o="pageYOffset"===i;S.fn[t]=function(e){return $(this,function(e,t,n){var r;if(x(e)?r=e:9===e.nodeType&&(r=e.defaultView),void 0===n)return r?r[i]:e[t];r?r.scrollTo(o?r.pageXOffset:n,o?n:r.pageYOffset):e[t]=n},t,e,arguments.length)}}),S.each(["top","left"],function(e,n){S.cssHooks[n]=Fe(y.pixelPosition,function(e,t){if(t)return t=We(e,n),Pe.test(t)?S(e).position()[n]+"px":t})}),S.each({Height:"height",Width:"width"},function(a,s){S.each({padding:"inner"+a,content:s,"":"outer"+a},function(r,o){S.fn[o]=function(e,t){var n=arguments.length&&(r||"boolean"!=typeof e),i=r||(!0===e||!0===t?"margin":"border");return $(this,function(e,t,n){var r;return x(e)?0===o.indexOf("outer")?e["inner"+a]:e.document.documentElement["client"+a]:9===e.nodeType?(r=e.documentElement,Math.max(e.body["scroll"+a],r["scroll"+a],e.body["offset"+a],r["offset"+a],r["client"+a])):void 0===n?S.css(e,t,i):S.style(e,t,n,i)},s,n?e:void 0,n)}})}),S.each(["ajaxStart","ajaxStop","ajaxComplete","ajaxError","ajaxSuccess","ajaxSend"],function(e,t){S.fn[t]=function(e){return this.on(t,e)}}),S.fn.extend({bind:function(e,t,n){return this.on(e,null,t,n)},unbind:function(e,t){return this.off(e,null,t)},delegate:function(e,t,n,r){return this.on(t,e,n,r)},undelegate:function(e,t,n){return 1===arguments.length?this.off(e,"**"):this.off(t,e||"**",n)},hover:function(e,t){return this.mouseenter(e).mouseleave(t||e)}}),S.each("blur focus focusin focusout resize scroll click dblclick mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave change select submit keydown keypress keyup contextmenu".split(" "),function(e,n){S.fn[n]=function(e,t){return 0",options:{classes:{},disabled:!1,create:null},_createWidget:function(t,e){e=y(e||this.defaultElement||this)[0],this.element=y(e),this.uuid=i++,this.eventNamespace="."+this.widgetName+this.uuid,this.bindings=y(),this.hoverable=y(),this.focusable=y(),this.classesElementLookup={},e!==this&&(y.data(e,this.widgetFullName,this),this._on(!0,this.element,{remove:function(t){t.target===e&&this.destroy()}}),this.document=y(e.style?e.ownerDocument:e.document||e),this.window=y(this.document[0].defaultView||this.document[0].parentWindow)),this.options=y.widget.extend({},this.options,this._getCreateOptions(),t),this._create(),this.options.disabled&&this._setOptionDisabled(this.options.disabled),this._trigger("create",null,this._getCreateEventData()),this._init()},_getCreateOptions:function(){return{}},_getCreateEventData:y.noop,_create:y.noop,_init:y.noop,destroy:function(){var i=this;this._destroy(),y.each(this.classesElementLookup,function(t,e){i._removeClass(e,t)}),this.element.off(this.eventNamespace).removeData(this.widgetFullName),this.widget().off(this.eventNamespace).removeAttr("aria-disabled"),this.bindings.off(this.eventNamespace)},_destroy:y.noop,widget:function(){return this.element},option:function(t,e){var i,s,n,o=t;if(0===arguments.length)return y.widget.extend({},this.options);if("string"==typeof t)if(o={},t=(i=t.split(".")).shift(),i.length){for(s=o[t]=y.widget.extend({},this.options[t]),n=0;n
"),i=e.children()[0];return y("body").append(e),t=i.offsetWidth,e.css("overflow","scroll"),t===(i=i.offsetWidth)&&(i=e[0].clientWidth),e.remove(),s=t-i},getScrollInfo:function(t){var e=t.isWindow||t.isDocument?"":t.element.css("overflow-x"),i=t.isWindow||t.isDocument?"":t.element.css("overflow-y"),e="scroll"===e||"auto"===e&&t.widthx(D(s),D(n))?o.important="horizontal":o.important="vertical",p.using.call(this,t,o)}),h.offset(y.extend(l,{using:t}))})},y.ui.position={fit:{left:function(t,e){var i=e.within,s=i.isWindow?i.scrollLeft:i.offset.left,n=i.width,o=t.left-e.collisionPosition.marginLeft,h=s-o,a=o+e.collisionWidth-n-s;e.collisionWidth>n?0n?0=this.options.distance},_mouseDelayMet:function(){return this.mouseDelayMet},_mouseStart:function(){},_mouseDrag:function(){},_mouseStop:function(){},_mouseCapture:function(){return!0}}),y.ui.plugin={add:function(t,e,i){var s,n=y.ui[t].prototype;for(s in i)n.plugins[s]=n.plugins[s]||[],n.plugins[s].push([e,i[s]])},call:function(t,e,i,s){var n,o=t.plugins[e];if(o&&(s||t.element[0].parentNode&&11!==t.element[0].parentNode.nodeType))for(n=0;n").css({overflow:"hidden",position:this.element.css("position"),width:this.element.outerWidth(),height:this.element.outerHeight(),top:this.element.css("top"),left:this.element.css("left")})),this.element=this.element.parent().data("ui-resizable",this.element.resizable("instance")),this.elementIsWrapper=!0,t={marginTop:this.originalElement.css("marginTop"),marginRight:this.originalElement.css("marginRight"),marginBottom:this.originalElement.css("marginBottom"),marginLeft:this.originalElement.css("marginLeft")},this.element.css(t),this.originalElement.css("margin",0),this.originalResizeStyle=this.originalElement.css("resize"),this.originalElement.css("resize","none"),this._proportionallyResizeElements.push(this.originalElement.css({position:"static",zoom:1,display:"block"})),this.originalElement.css(t),this._proportionallyResize()),this._setupHandles(),e.autoHide&&y(this.element).on("mouseenter",function(){e.disabled||(i._removeClass("ui-resizable-autohide"),i._handles.show())}).on("mouseleave",function(){e.disabled||i.resizing||(i._addClass("ui-resizable-autohide"),i._handles.hide())}),this._mouseInit()},_destroy:function(){this._mouseDestroy(),this._addedHandles.remove();function t(t){y(t).removeData("resizable").removeData("ui-resizable").off(".resizable")}var e;return this.elementIsWrapper&&(t(this.element),e=this.element,this.originalElement.css({position:e.css("position"),width:e.outerWidth(),height:e.outerHeight(),top:e.css("top"),left:e.css("left")}).insertAfter(e),e.remove()),this.originalElement.css("resize",this.originalResizeStyle),t(this.originalElement),this},_setOption:function(t,e){switch(this._super(t,e),t){case"handles":this._removeHandles(),this._setupHandles();break;case"aspectRatio":this._aspectRatio=!!e}},_setupHandles:function(){var t,e,i,s,n,o=this.options,h=this;if(this.handles=o.handles||(y(".ui-resizable-handle",this.element).length?{n:".ui-resizable-n",e:".ui-resizable-e",s:".ui-resizable-s",w:".ui-resizable-w",se:".ui-resizable-se",sw:".ui-resizable-sw",ne:".ui-resizable-ne",nw:".ui-resizable-nw"}:"e,s,se"),this._handles=y(),this._addedHandles=y(),this.handles.constructor===String)for("all"===this.handles&&(this.handles="n,e,s,w,se,sw,ne,nw"),i=this.handles.split(","),this.handles={},e=0;e"),this._addClass(n,"ui-resizable-handle "+s),n.css({zIndex:o.zIndex}),this.handles[t]=".ui-resizable-"+t,this.element.children(this.handles[t]).length||(this.element.append(n),this._addedHandles=this._addedHandles.add(n));this._renderAxis=function(t){var e,i,s;for(e in t=t||this.element,this.handles)this.handles[e].constructor===String?this.handles[e]=this.element.children(this.handles[e]).first().show():(this.handles[e].jquery||this.handles[e].nodeType)&&(this.handles[e]=y(this.handles[e]),this._on(this.handles[e],{mousedown:h._mouseDown})),this.elementIsWrapper&&this.originalElement[0].nodeName.match(/^(textarea|input|select|button)$/i)&&(i=y(this.handles[e],this.element),s=/sw|ne|nw|se|n|s/.test(e)?i.outerHeight():i.outerWidth(),i=["padding",/ne|nw|n/.test(e)?"Top":/se|sw|s/.test(e)?"Bottom":/^e$/.test(e)?"Right":"Left"].join(""),t.css(i,s),this._proportionallyResize()),this._handles=this._handles.add(this.handles[e])},this._renderAxis(this.element),this._handles=this._handles.add(this.element.find(".ui-resizable-handle")),this._handles.disableSelection(),this._handles.on("mouseover",function(){h.resizing||(this.className&&(n=this.className.match(/ui-resizable-(se|sw|ne|nw|n|e|s|w)/i)),h.axis=n&&n[1]?n[1]:"se")}),o.autoHide&&(this._handles.hide(),this._addClass("ui-resizable-autohide"))},_removeHandles:function(){this._addedHandles.remove()},_mouseCapture:function(t){var e,i,s=!1;for(e in this.handles)(i=y(this.handles[e])[0])!==t.target&&!y.contains(i,t.target)||(s=!0);return!this.options.disabled&&s},_mouseStart:function(t){var e,i,s=this.options,n=this.element;return this.resizing=!0,this._renderProxy(),e=this._num(this.helper.css("left")),i=this._num(this.helper.css("top")),s.containment&&(e+=y(s.containment).scrollLeft()||0,i+=y(s.containment).scrollTop()||0),this.offset=this.helper.offset(),this.position={left:e,top:i},this.size=this._helper?{width:this.helper.width(),height:this.helper.height()}:{width:n.width(),height:n.height()},this.originalSize=this._helper?{width:n.outerWidth(),height:n.outerHeight()}:{width:n.width(),height:n.height()},this.sizeDiff={width:n.outerWidth()-n.width(),height:n.outerHeight()-n.height()},this.originalPosition={left:e,top:i},this.originalMousePosition={left:t.pageX,top:t.pageY},this.aspectRatio="number"==typeof s.aspectRatio?s.aspectRatio:this.originalSize.width/this.originalSize.height||1,s=y(".ui-resizable-"+this.axis).css("cursor"),y("body").css("cursor","auto"===s?this.axis+"-resize":s),this._addClass("ui-resizable-resizing"),this._propagate("start",t),!0},_mouseDrag:function(t){var e=this.originalMousePosition,i=this.axis,s=t.pageX-e.left||0,e=t.pageY-e.top||0,i=this._change[i];return this._updatePrevProperties(),i&&(e=i.apply(this,[t,s,e]),this._updateVirtualBoundaries(t.shiftKey),(this._aspectRatio||t.shiftKey)&&(e=this._updateRatio(e,t)),e=this._respectSize(e,t),this._updateCache(e),this._propagate("resize",t),e=this._applyChanges(),!this._helper&&this._proportionallyResizeElements.length&&this._proportionallyResize(),y.isEmptyObject(e)||(this._updatePrevProperties(),this._trigger("resize",t,this.ui()),this._applyChanges())),!1},_mouseStop:function(t){this.resizing=!1;var e,i,s,n=this.options,o=this;return this._helper&&(s=(e=(i=this._proportionallyResizeElements).length&&/textarea/i.test(i[0].nodeName))&&this._hasScroll(i[0],"left")?0:o.sizeDiff.height,i=e?0:o.sizeDiff.width,e={width:o.helper.width()-i,height:o.helper.height()-s},i=parseFloat(o.element.css("left"))+(o.position.left-o.originalPosition.left)||null,s=parseFloat(o.element.css("top"))+(o.position.top-o.originalPosition.top)||null,n.animate||this.element.css(y.extend(e,{top:s,left:i})),o.helper.height(o.size.height),o.helper.width(o.size.width),this._helper&&!n.animate&&this._proportionallyResize()),y("body").css("cursor","auto"),this._removeClass("ui-resizable-resizing"),this._propagate("stop",t),this._helper&&this.helper.remove(),!1},_updatePrevProperties:function(){this.prevPosition={top:this.position.top,left:this.position.left},this.prevSize={width:this.size.width,height:this.size.height}},_applyChanges:function(){var t={};return this.position.top!==this.prevPosition.top&&(t.top=this.position.top+"px"),this.position.left!==this.prevPosition.left&&(t.left=this.position.left+"px"),this.size.width!==this.prevSize.width&&(t.width=this.size.width+"px"),this.size.height!==this.prevSize.height&&(t.height=this.size.height+"px"),this.helper.css(t),t},_updateVirtualBoundaries:function(t){var e,i,s=this.options,n={minWidth:this._isNumber(s.minWidth)?s.minWidth:0,maxWidth:this._isNumber(s.maxWidth)?s.maxWidth:1/0,minHeight:this._isNumber(s.minHeight)?s.minHeight:0,maxHeight:this._isNumber(s.maxHeight)?s.maxHeight:1/0};(this._aspectRatio||t)&&(e=n.minHeight*this.aspectRatio,i=n.minWidth/this.aspectRatio,s=n.maxHeight*this.aspectRatio,t=n.maxWidth/this.aspectRatio,e>n.minWidth&&(n.minWidth=e),i>n.minHeight&&(n.minHeight=i),st.width,h=this._isNumber(t.height)&&e.minHeight&&e.minHeight>t.height,a=this.originalPosition.left+this.originalSize.width,r=this.originalPosition.top+this.originalSize.height,l=/sw|nw|w/.test(i),i=/nw|ne|n/.test(i);return o&&(t.width=e.minWidth),h&&(t.height=e.minHeight),s&&(t.width=e.maxWidth),n&&(t.height=e.maxHeight),o&&l&&(t.left=a-e.minWidth),s&&l&&(t.left=a-e.maxWidth),h&&i&&(t.top=r-e.minHeight),n&&i&&(t.top=r-e.maxHeight),t.width||t.height||t.left||!t.top?t.width||t.height||t.top||!t.left||(t.left=null):t.top=null,t},_getPaddingPlusBorderDimensions:function(t){for(var e=0,i=[],s=[t.css("borderTopWidth"),t.css("borderRightWidth"),t.css("borderBottomWidth"),t.css("borderLeftWidth")],n=[t.css("paddingTop"),t.css("paddingRight"),t.css("paddingBottom"),t.css("paddingLeft")];e<4;e++)i[e]=parseFloat(s[e])||0,i[e]+=parseFloat(n[e])||0;return{height:i[0]+i[2],width:i[1]+i[3]}},_proportionallyResize:function(){if(this._proportionallyResizeElements.length)for(var t,e=0,i=this.helper||this.element;e").css({overflow:"hidden"}),this._addClass(this.helper,this._helper),this.helper.css({width:this.element.outerWidth(),height:this.element.outerHeight(),position:"absolute",left:this.elementOffset.left+"px",top:this.elementOffset.top+"px",zIndex:++e.zIndex}),this.helper.appendTo("body").disableSelection()):this.helper=this.element},_change:{e:function(t,e){return{width:this.originalSize.width+e}},w:function(t,e){var i=this.originalSize;return{left:this.originalPosition.left+e,width:i.width-e}},n:function(t,e,i){var s=this.originalSize;return{top:this.originalPosition.top+i,height:s.height-i}},s:function(t,e,i){return{height:this.originalSize.height+i}},se:function(t,e,i){return y.extend(this._change.s.apply(this,arguments),this._change.e.apply(this,[t,e,i]))},sw:function(t,e,i){return y.extend(this._change.s.apply(this,arguments),this._change.w.apply(this,[t,e,i]))},ne:function(t,e,i){return y.extend(this._change.n.apply(this,arguments),this._change.e.apply(this,[t,e,i]))},nw:function(t,e,i){return y.extend(this._change.n.apply(this,arguments),this._change.w.apply(this,[t,e,i]))}},_propagate:function(t,e){y.ui.plugin.call(this,t,[e,this.ui()]),"resize"!==t&&this._trigger(t,e,this.ui())},plugins:{},ui:function(){return{originalElement:this.originalElement,element:this.element,helper:this.helper,position:this.position,size:this.size,originalSize:this.originalSize,originalPosition:this.originalPosition}}}),y.ui.plugin.add("resizable","animate",{stop:function(e){var i=y(this).resizable("instance"),t=i.options,s=i._proportionallyResizeElements,n=s.length&&/textarea/i.test(s[0].nodeName),o=n&&i._hasScroll(s[0],"left")?0:i.sizeDiff.height,h=n?0:i.sizeDiff.width,n={width:i.size.width-h,height:i.size.height-o},h=parseFloat(i.element.css("left"))+(i.position.left-i.originalPosition.left)||null,o=parseFloat(i.element.css("top"))+(i.position.top-i.originalPosition.top)||null;i.element.animate(y.extend(n,o&&h?{top:o,left:h}:{}),{duration:t.animateDuration,easing:t.animateEasing,step:function(){var t={width:parseFloat(i.element.css("width")),height:parseFloat(i.element.css("height")),top:parseFloat(i.element.css("top")),left:parseFloat(i.element.css("left"))};s&&s.length&&y(s[0]).css({width:t.width,height:t.height}),i._updateCache(t),i._propagate("resize",e)}})}}),y.ui.plugin.add("resizable","containment",{start:function(){var i,s,n=y(this).resizable("instance"),t=n.options,e=n.element,o=t.containment,h=o instanceof y?o.get(0):/parent/.test(o)?e.parent().get(0):o;h&&(n.containerElement=y(h),/document/.test(o)||o===document?(n.containerOffset={left:0,top:0},n.containerPosition={left:0,top:0},n.parentData={element:y(document),left:0,top:0,width:y(document).width(),height:y(document).height()||document.body.parentNode.scrollHeight}):(i=y(h),s=[],y(["Top","Right","Left","Bottom"]).each(function(t,e){s[t]=n._num(i.css("padding"+e))}),n.containerOffset=i.offset(),n.containerPosition=i.position(),n.containerSize={height:i.innerHeight()-s[3],width:i.innerWidth()-s[1]},t=n.containerOffset,e=n.containerSize.height,o=n.containerSize.width,o=n._hasScroll(h,"left")?h.scrollWidth:o,e=n._hasScroll(h)?h.scrollHeight:e,n.parentData={element:h,left:t.left,top:t.top,width:o,height:e}))},resize:function(t){var e=y(this).resizable("instance"),i=e.options,s=e.containerOffset,n=e.position,o=e._aspectRatio||t.shiftKey,h={top:0,left:0},a=e.containerElement,t=!0;a[0]!==document&&/static/.test(a.css("position"))&&(h=s),n.left<(e._helper?s.left:0)&&(e.size.width=e.size.width+(e._helper?e.position.left-s.left:e.position.left-h.left),o&&(e.size.height=e.size.width/e.aspectRatio,t=!1),e.position.left=i.helper?s.left:0),n.top<(e._helper?s.top:0)&&(e.size.height=e.size.height+(e._helper?e.position.top-s.top:e.position.top),o&&(e.size.width=e.size.height*e.aspectRatio,t=!1),e.position.top=e._helper?s.top:0),i=e.containerElement.get(0)===e.element.parent().get(0),n=/relative|absolute/.test(e.containerElement.css("position")),i&&n?(e.offset.left=e.parentData.left+e.position.left,e.offset.top=e.parentData.top+e.position.top):(e.offset.left=e.element.offset().left,e.offset.top=e.element.offset().top),n=Math.abs(e.sizeDiff.width+(e._helper?e.offset.left-h.left:e.offset.left-s.left)),s=Math.abs(e.sizeDiff.height+(e._helper?e.offset.top-h.top:e.offset.top-s.top)),n+e.size.width>=e.parentData.width&&(e.size.width=e.parentData.width-n,o&&(e.size.height=e.size.width/e.aspectRatio,t=!1)),s+e.size.height>=e.parentData.height&&(e.size.height=e.parentData.height-s,o&&(e.size.width=e.size.height*e.aspectRatio,t=!1)),t||(e.position.left=e.prevPosition.left,e.position.top=e.prevPosition.top,e.size.width=e.prevSize.width,e.size.height=e.prevSize.height)},stop:function(){var t=y(this).resizable("instance"),e=t.options,i=t.containerOffset,s=t.containerPosition,n=t.containerElement,o=y(t.helper),h=o.offset(),a=o.outerWidth()-t.sizeDiff.width,o=o.outerHeight()-t.sizeDiff.height;t._helper&&!e.animate&&/relative/.test(n.css("position"))&&y(this).css({left:h.left-s.left-i.left,width:a,height:o}),t._helper&&!e.animate&&/static/.test(n.css("position"))&&y(this).css({left:h.left-s.left-i.left,width:a,height:o})}}),y.ui.plugin.add("resizable","alsoResize",{start:function(){var t=y(this).resizable("instance").options;y(t.alsoResize).each(function(){var t=y(this);t.data("ui-resizable-alsoresize",{width:parseFloat(t.width()),height:parseFloat(t.height()),left:parseFloat(t.css("left")),top:parseFloat(t.css("top"))})})},resize:function(t,i){var e=y(this).resizable("instance"),s=e.options,n=e.originalSize,o=e.originalPosition,h={height:e.size.height-n.height||0,width:e.size.width-n.width||0,top:e.position.top-o.top||0,left:e.position.left-o.left||0};y(s.alsoResize).each(function(){var t=y(this),s=y(this).data("ui-resizable-alsoresize"),n={},e=t.parents(i.originalElement[0]).length?["width","height"]:["width","height","top","left"];y.each(e,function(t,e){var i=(s[e]||0)+(h[e]||0);i&&0<=i&&(n[e]=i||null)}),t.css(n)})},stop:function(){y(this).removeData("ui-resizable-alsoresize")}}),y.ui.plugin.add("resizable","ghost",{start:function(){var t=y(this).resizable("instance"),e=t.size;t.ghost=t.originalElement.clone(),t.ghost.css({opacity:.25,display:"block",position:"relative",height:e.height,width:e.width,margin:0,left:0,top:0}),t._addClass(t.ghost,"ui-resizable-ghost"),!1!==y.uiBackCompat&&"string"==typeof t.options.ghost&&t.ghost.addClass(this.options.ghost),t.ghost.appendTo(t.helper)},resize:function(){var t=y(this).resizable("instance");t.ghost&&t.ghost.css({position:"relative",height:t.size.height,width:t.size.width})},stop:function(){var t=y(this).resizable("instance");t.ghost&&t.helper&&t.helper.get(0).removeChild(t.ghost.get(0))}}),y.ui.plugin.add("resizable","grid",{resize:function(){var t,e=y(this).resizable("instance"),i=e.options,s=e.size,n=e.originalSize,o=e.originalPosition,h=e.axis,a="number"==typeof i.grid?[i.grid,i.grid]:i.grid,r=a[0]||1,l=a[1]||1,u=Math.round((s.width-n.width)/r)*r,p=Math.round((s.height-n.height)/l)*l,d=n.width+u,c=n.height+p,f=i.maxWidth&&i.maxWidthd,s=i.minHeight&&i.minHeight>c;i.grid=a,m&&(d+=r),s&&(c+=l),f&&(d-=r),g&&(c-=l),/^(se|s|e)$/.test(h)?(e.size.width=d,e.size.height=c):/^(ne)$/.test(h)?(e.size.width=d,e.size.height=c,e.position.top=o.top-p):/^(sw)$/.test(h)?(e.size.width=d,e.size.height=c,e.position.left=o.left-u):((c-l<=0||d-r<=0)&&(t=e._getPaddingPlusBorderDimensions(this)),0=f[g]?0:Math.min(f[g],n));!a&&1-1){targetElements.on(evt+EVENT_NAMESPACE,function elementToggle(event){$.powerTip.toggle(this,event)})}else{targetElements.on(evt+EVENT_NAMESPACE,function elementOpen(event){$.powerTip.show(this,event)})}});$.each(options.closeEvents,function(idx,evt){if($.inArray(evt,options.openEvents)<0){targetElements.on(evt+EVENT_NAMESPACE,function elementClose(event){$.powerTip.hide(this,!isMouseEvent(event))})}});targetElements.on("keydown"+EVENT_NAMESPACE,function elementKeyDown(event){if(event.keyCode===27){$.powerTip.hide(this,true)}})}return targetElements};$.fn.powerTip.defaults={fadeInTime:200,fadeOutTime:100,followMouse:false,popupId:"powerTip",popupClass:null,intentSensitivity:7,intentPollInterval:100,closeDelay:100,placement:"n",smartPlacement:false,offset:10,mouseOnToPopup:false,manual:false,openEvents:["mouseenter","focus"],closeEvents:["mouseleave","blur"]};$.fn.powerTip.smartPlacementLists={n:["n","ne","nw","s"],e:["e","ne","se","w","nw","sw","n","s","e"],s:["s","se","sw","n"],w:["w","nw","sw","e","ne","se","n","s","w"],nw:["nw","w","sw","n","s","se","nw"],ne:["ne","e","se","n","s","sw","ne"],sw:["sw","w","nw","s","n","ne","sw"],se:["se","e","ne","s","n","nw","se"],"nw-alt":["nw-alt","n","ne-alt","sw-alt","s","se-alt","w","e"],"ne-alt":["ne-alt","n","nw-alt","se-alt","s","sw-alt","e","w"],"sw-alt":["sw-alt","s","se-alt","nw-alt","n","ne-alt","w","e"],"se-alt":["se-alt","s","sw-alt","ne-alt","n","nw-alt","e","w"]};$.powerTip={show:function apiShowTip(element,event){if(isMouseEvent(event)){trackMouse(event);session.previousX=event.pageX;session.previousY=event.pageY;$(element).data(DATA_DISPLAYCONTROLLER).show()}else{$(element).first().data(DATA_DISPLAYCONTROLLER).show(true,true)}return element},reposition:function apiResetPosition(element){$(element).first().data(DATA_DISPLAYCONTROLLER).resetPosition();return element},hide:function apiCloseTip(element,immediate){var displayController;immediate=element?immediate:true;if(element){displayController=$(element).first().data(DATA_DISPLAYCONTROLLER)}else if(session.activeHover){displayController=session.activeHover.data(DATA_DISPLAYCONTROLLER)}if(displayController){displayController.hide(immediate)}return element},toggle:function apiToggle(element,event){if(session.activeHover&&session.activeHover.is(element)){$.powerTip.hide(element,!isMouseEvent(event))}else{$.powerTip.show(element,event)}return element}};$.powerTip.showTip=$.powerTip.show;$.powerTip.closeTip=$.powerTip.hide;function CSSCoordinates(){var me=this;me.top="auto";me.left="auto";me.right="auto";me.bottom="auto";me.set=function(property,value){if($.isNumeric(value)){me[property]=Math.round(value)}}}function DisplayController(element,options,tipController){var hoverTimer=null,myCloseDelay=null;function openTooltip(immediate,forceOpen){cancelTimer();if(!element.data(DATA_HASACTIVEHOVER)){if(!immediate){session.tipOpenImminent=true;hoverTimer=setTimeout(function intentDelay(){hoverTimer=null;checkForIntent()},options.intentPollInterval)}else{if(forceOpen){element.data(DATA_FORCEDOPEN,true)}closeAnyDelayed();tipController.showTip(element)}}else{cancelClose()}}function closeTooltip(disableDelay){if(myCloseDelay){myCloseDelay=session.closeDelayTimeout=clearTimeout(myCloseDelay);session.delayInProgress=false}cancelTimer();session.tipOpenImminent=false;if(element.data(DATA_HASACTIVEHOVER)){element.data(DATA_FORCEDOPEN,false);if(!disableDelay){session.delayInProgress=true;session.closeDelayTimeout=setTimeout(function closeDelay(){session.closeDelayTimeout=null;tipController.hideTip(element);session.delayInProgress=false;myCloseDelay=null},options.closeDelay);myCloseDelay=session.closeDelayTimeout}else{tipController.hideTip(element)}}}function checkForIntent(){var xDifference=Math.abs(session.previousX-session.currentX),yDifference=Math.abs(session.previousY-session.currentY),totalDifference=xDifference+yDifference;if(totalDifference",{id:options.popupId});if($body.length===0){$body=$("body")}$body.append(tipElement);session.tooltips=session.tooltips?session.tooltips.add(tipElement):tipElement}if(options.followMouse){if(!tipElement.data(DATA_HASMOUSEMOVE)){$document.on("mousemove"+EVENT_NAMESPACE,positionTipOnCursor);$window.on("scroll"+EVENT_NAMESPACE,positionTipOnCursor);tipElement.data(DATA_HASMOUSEMOVE,true)}}function beginShowTip(element){element.data(DATA_HASACTIVEHOVER,true);tipElement.queue(function queueTipInit(next){showTip(element);next()})}function showTip(element){var tipContent;if(!element.data(DATA_HASACTIVEHOVER)){return}if(session.isTipOpen){if(!session.isClosing){hideTip(session.activeHover)}tipElement.delay(100).queue(function queueTipAgain(next){showTip(element);next()});return}element.trigger("powerTipPreRender");tipContent=getTooltipContent(element);if(tipContent){tipElement.empty().append(tipContent)}else{return}element.trigger("powerTipRender");session.activeHover=element;session.isTipOpen=true;tipElement.data(DATA_MOUSEONTOTIP,options.mouseOnToPopup);tipElement.addClass(options.popupClass);if(!options.followMouse||element.data(DATA_FORCEDOPEN)){positionTipOnElement(element);session.isFixedTipOpen=true}else{positionTipOnCursor()}if(!element.data(DATA_FORCEDOPEN)&&!options.followMouse){$document.on("click"+EVENT_NAMESPACE,function documentClick(event){var target=event.target;if(target!==element[0]){if(options.mouseOnToPopup){if(target!==tipElement[0]&&!$.contains(tipElement[0],target)){$.powerTip.hide()}}else{$.powerTip.hide()}}})}if(options.mouseOnToPopup&&!options.manual){tipElement.on("mouseenter"+EVENT_NAMESPACE,function tipMouseEnter(){if(session.activeHover){session.activeHover.data(DATA_DISPLAYCONTROLLER).cancel()}});tipElement.on("mouseleave"+EVENT_NAMESPACE,function tipMouseLeave(){if(session.activeHover){session.activeHover.data(DATA_DISPLAYCONTROLLER).hide()}})}tipElement.fadeIn(options.fadeInTime,function fadeInCallback(){if(!session.desyncTimeout){session.desyncTimeout=setInterval(closeDesyncedTip,500)}element.trigger("powerTipOpen")})}function hideTip(element){session.isClosing=true;session.isTipOpen=false;session.desyncTimeout=clearInterval(session.desyncTimeout);element.data(DATA_HASACTIVEHOVER,false);element.data(DATA_FORCEDOPEN,false);$document.off("click"+EVENT_NAMESPACE);tipElement.off(EVENT_NAMESPACE);tipElement.fadeOut(options.fadeOutTime,function fadeOutCallback(){var coords=new CSSCoordinates;session.activeHover=null;session.isClosing=false;session.isFixedTipOpen=false;tipElement.removeClass();coords.set("top",session.currentY+options.offset);coords.set("left",session.currentX+options.offset);tipElement.css(coords);element.trigger("powerTipClose")})}function positionTipOnCursor(){var tipWidth,tipHeight,coords,collisions,collisionCount;if(!session.isFixedTipOpen&&(session.isTipOpen||session.tipOpenImminent&&tipElement.data(DATA_HASMOUSEMOVE))){tipWidth=tipElement.outerWidth();tipHeight=tipElement.outerHeight();coords=new CSSCoordinates;coords.set("top",session.currentY+options.offset);coords.set("left",session.currentX+options.offset);collisions=getViewportCollisions(coords,tipWidth,tipHeight);if(collisions!==Collision.none){collisionCount=countFlags(collisions);if(collisionCount===1){if(collisions===Collision.right){coords.set("left",session.scrollLeft+session.windowWidth-tipWidth)}else if(collisions===Collision.bottom){coords.set("top",session.scrollTop+session.windowHeight-tipHeight)}}else{coords.set("left",session.currentX-tipWidth-options.offset);coords.set("top",session.currentY-tipHeight-options.offset)}}tipElement.css(coords)}}function positionTipOnElement(element){var priorityList,finalPlacement;if(options.smartPlacement||options.followMouse&&element.data(DATA_FORCEDOPEN)){priorityList=$.fn.powerTip.smartPlacementLists[options.placement];$.each(priorityList,function(idx,pos){var collisions=getViewportCollisions(placeTooltip(element,pos),tipElement.outerWidth(),tipElement.outerHeight());finalPlacement=pos;return collisions!==Collision.none})}else{placeTooltip(element,options.placement);finalPlacement=options.placement}tipElement.removeClass("w nw sw e ne se n s w se-alt sw-alt ne-alt nw-alt");tipElement.addClass(finalPlacement)}function placeTooltip(element,placement){var iterationCount=0,tipWidth,tipHeight,coords=new CSSCoordinates;coords.set("top",0);coords.set("left",0);tipElement.css(coords);do{tipWidth=tipElement.outerWidth();tipHeight=tipElement.outerHeight();coords=placementCalculator.compute(element,placement,tipWidth,tipHeight,options.offset);tipElement.css(coords)}while(++iterationCount<=5&&(tipWidth!==tipElement.outerWidth()||tipHeight!==tipElement.outerHeight()));return coords}function closeDesyncedTip(){var isDesynced=false,hasDesyncableCloseEvent=$.grep(["mouseleave","mouseout","blur","focusout"],function(eventType){return $.inArray(eventType,options.closeEvents)!==-1}).length>0;if(session.isTipOpen&&!session.isClosing&&!session.delayInProgress&&hasDesyncableCloseEvent){if(session.activeHover.data(DATA_HASACTIVEHOVER)===false||session.activeHover.is(":disabled")){isDesynced=true}else if(!isMouseOver(session.activeHover)&&!session.activeHover.is(":focus")&&!session.activeHover.data(DATA_FORCEDOPEN)){if(tipElement.data(DATA_MOUSEONTOTIP)){if(!isMouseOver(tipElement)){isDesynced=true}}else{isDesynced=true}}if(isDesynced){hideTip(session.activeHover)}}}this.showTip=beginShowTip;this.hideTip=hideTip;this.resetPosition=positionTipOnElement}function isSvgElement(element){return Boolean(window.SVGElement&&element[0]instanceof SVGElement)}function isMouseEvent(event){return Boolean(event&&$.inArray(event.type,MOUSE_EVENTS)>-1&&typeof event.pageX==="number")}function initTracking(){if(!session.mouseTrackingActive){session.mouseTrackingActive=true;getViewportDimensions();$(getViewportDimensions);$document.on("mousemove"+EVENT_NAMESPACE,trackMouse);$window.on("resize"+EVENT_NAMESPACE,trackResize);$window.on("scroll"+EVENT_NAMESPACE,trackScroll)}}function getViewportDimensions(){session.scrollLeft=$window.scrollLeft();session.scrollTop=$window.scrollTop();session.windowWidth=$window.width();session.windowHeight=$window.height()}function trackResize(){session.windowWidth=$window.width();session.windowHeight=$window.height()}function trackScroll(){var x=$window.scrollLeft(),y=$window.scrollTop();if(x!==session.scrollLeft){session.currentX+=x-session.scrollLeft;session.scrollLeft=x}if(y!==session.scrollTop){session.currentY+=y-session.scrollTop;session.scrollTop=y}}function trackMouse(event){session.currentX=event.pageX;session.currentY=event.pageY}function isMouseOver(element){var elementPosition=element.offset(),elementBox=element[0].getBoundingClientRect(),elementWidth=elementBox.right-elementBox.left,elementHeight=elementBox.bottom-elementBox.top;return session.currentX>=elementPosition.left&&session.currentX<=elementPosition.left+elementWidth&&session.currentY>=elementPosition.top&&session.currentY<=elementPosition.top+elementHeight}function getTooltipContent(element){var tipText=element.data(DATA_POWERTIP),tipObject=element.data(DATA_POWERTIPJQ),tipTarget=element.data(DATA_POWERTIPTARGET),targetElement,content;if(tipText){if($.isFunction(tipText)){tipText=tipText.call(element[0])}content=tipText}else if(tipObject){if($.isFunction(tipObject)){tipObject=tipObject.call(element[0])}if(tipObject.length>0){content=tipObject.clone(true,true)}}else if(tipTarget){targetElement=$("#"+tipTarget);if(targetElement.length>0){content=targetElement.html()}}return content}function getViewportCollisions(coords,elementWidth,elementHeight){var viewportTop=session.scrollTop,viewportLeft=session.scrollLeft,viewportBottom=viewportTop+session.windowHeight,viewportRight=viewportLeft+session.windowWidth,collisions=Collision.none;if(coords.topviewportBottom||Math.abs(coords.bottom-session.windowHeight)>viewportBottom){collisions|=Collision.bottom}if(coords.leftviewportRight){collisions|=Collision.left}if(coords.left+elementWidth>viewportRight||coords.right1)){a.preventDefault();var c=a.originalEvent.changedTouches[0],d=document.createEvent("MouseEvents");d.initMouseEvent(b,!0,!0,window,1,c.screenX,c.screenY,c.clientX,c.clientY,!1,!1,!1,!1,0,null),a.target.dispatchEvent(d)}}if(a.support.touch="ontouchend"in document,a.support.touch){var e,b=a.ui.mouse.prototype,c=b._mouseInit,d=b._mouseDestroy;b._touchStart=function(a){var b=this;!e&&b._mouseCapture(a.originalEvent.changedTouches[0])&&(e=!0,b._touchMoved=!1,f(a,"mouseover"),f(a,"mousemove"),f(a,"mousedown"))},b._touchMove=function(a){e&&(this._touchMoved=!0,f(a,"mousemove"))},b._touchEnd=function(a){e&&(f(a,"mouseup"),f(a,"mouseout"),this._touchMoved||f(a,"click"),e=!1)},b._mouseInit=function(){var b=this;b.element.bind({touchstart:a.proxy(b,"_touchStart"),touchmove:a.proxy(b,"_touchMove"),touchend:a.proxy(b,"_touchEnd")}),c.call(b)},b._mouseDestroy=function(){var b=this;b.element.unbind({touchstart:a.proxy(b,"_touchStart"),touchmove:a.proxy(b,"_touchMove"),touchend:a.proxy(b,"_touchEnd")}),d.call(b)}}}(jQuery);/*! SmartMenus jQuery Plugin - v1.1.0 - September 17, 2017 - * http://www.smartmenus.org/ - * Copyright Vasil Dinkov, Vadikom Web Ltd. http://vadikom.com; Licensed MIT */(function(t){"function"==typeof define&&define.amd?define(["jquery"],t):"object"==typeof module&&"object"==typeof module.exports?module.exports=t(require("jquery")):t(jQuery)})(function($){function initMouseDetection(t){var e=".smartmenus_mouse";if(mouseDetectionEnabled||t)mouseDetectionEnabled&&t&&($(document).off(e),mouseDetectionEnabled=!1);else{var i=!0,s=null,o={mousemove:function(t){var e={x:t.pageX,y:t.pageY,timeStamp:(new Date).getTime()};if(s){var o=Math.abs(s.x-e.x),a=Math.abs(s.y-e.y);if((o>0||a>0)&&2>=o&&2>=a&&300>=e.timeStamp-s.timeStamp&&(mouse=!0,i)){var n=$(t.target).closest("a");n.is("a")&&$.each(menuTrees,function(){return $.contains(this.$root[0],n[0])?(this.itemEnter({currentTarget:n[0]}),!1):void 0}),i=!1}}s=e}};o[touchEvents?"touchstart":"pointerover pointermove pointerout MSPointerOver MSPointerMove MSPointerOut"]=function(t){isTouchEvent(t.originalEvent)&&(mouse=!1)},$(document).on(getEventsNS(o,e)),mouseDetectionEnabled=!0}}function isTouchEvent(t){return!/^(4|mouse)$/.test(t.pointerType)}function getEventsNS(t,e){e||(e="");var i={};for(var s in t)i[s.split(" ").join(e+" ")+e]=t[s];return i}var menuTrees=[],mouse=!1,touchEvents="ontouchstart"in window,mouseDetectionEnabled=!1,requestAnimationFrame=window.requestAnimationFrame||function(t){return setTimeout(t,1e3/60)},cancelAnimationFrame=window.cancelAnimationFrame||function(t){clearTimeout(t)},canAnimate=!!$.fn.animate;return $.SmartMenus=function(t,e){this.$root=$(t),this.opts=e,this.rootId="",this.accessIdPrefix="",this.$subArrow=null,this.activatedItems=[],this.visibleSubMenus=[],this.showTimeout=0,this.hideTimeout=0,this.scrollTimeout=0,this.clickActivated=!1,this.focusActivated=!1,this.zIndexInc=0,this.idInc=0,this.$firstLink=null,this.$firstSub=null,this.disabled=!1,this.$disableOverlay=null,this.$touchScrollingSub=null,this.cssTransforms3d="perspective"in t.style||"webkitPerspective"in t.style,this.wasCollapsible=!1,this.init()},$.extend($.SmartMenus,{hideAll:function(){$.each(menuTrees,function(){this.menuHideAll()})},destroy:function(){for(;menuTrees.length;)menuTrees[0].destroy();initMouseDetection(!0)},prototype:{init:function(t){var e=this;if(!t){menuTrees.push(this),this.rootId=((new Date).getTime()+Math.random()+"").replace(/\D/g,""),this.accessIdPrefix="sm-"+this.rootId+"-",this.$root.hasClass("sm-rtl")&&(this.opts.rightToLeftSubMenus=!0);var i=".smartmenus";this.$root.data("smartmenus",this).attr("data-smartmenus-id",this.rootId).dataSM("level",1).on(getEventsNS({"mouseover focusin":$.proxy(this.rootOver,this),"mouseout focusout":$.proxy(this.rootOut,this),keydown:$.proxy(this.rootKeyDown,this)},i)).on(getEventsNS({mouseenter:$.proxy(this.itemEnter,this),mouseleave:$.proxy(this.itemLeave,this),mousedown:$.proxy(this.itemDown,this),focus:$.proxy(this.itemFocus,this),blur:$.proxy(this.itemBlur,this),click:$.proxy(this.itemClick,this)},i),"a"),i+=this.rootId,this.opts.hideOnClick&&$(document).on(getEventsNS({touchstart:$.proxy(this.docTouchStart,this),touchmove:$.proxy(this.docTouchMove,this),touchend:$.proxy(this.docTouchEnd,this),click:$.proxy(this.docClick,this)},i)),$(window).on(getEventsNS({"resize orientationchange":$.proxy(this.winResize,this)},i)),this.opts.subIndicators&&(this.$subArrow=$("").addClass("sub-arrow"),this.opts.subIndicatorsText&&this.$subArrow.html(this.opts.subIndicatorsText)),initMouseDetection()}if(this.$firstSub=this.$root.find("ul").each(function(){e.menuInit($(this))}).eq(0),this.$firstLink=this.$root.find("a").eq(0),this.opts.markCurrentItem){var s=/(index|default)\.[^#\?\/]*/i,o=/#.*/,a=window.location.href.replace(s,""),n=a.replace(o,"");this.$root.find("a").each(function(){var t=this.href.replace(s,""),i=$(this);(t==a||t==n)&&(i.addClass("current"),e.opts.markCurrentTree&&i.parentsUntil("[data-smartmenus-id]","ul").each(function(){$(this).dataSM("parent-a").addClass("current")}))})}this.wasCollapsible=this.isCollapsible()},destroy:function(t){if(!t){var e=".smartmenus";this.$root.removeData("smartmenus").removeAttr("data-smartmenus-id").removeDataSM("level").off(e),e+=this.rootId,$(document).off(e),$(window).off(e),this.opts.subIndicators&&(this.$subArrow=null)}this.menuHideAll();var i=this;this.$root.find("ul").each(function(){var t=$(this);t.dataSM("scroll-arrows")&&t.dataSM("scroll-arrows").remove(),t.dataSM("shown-before")&&((i.opts.subMenusMinWidth||i.opts.subMenusMaxWidth)&&t.css({width:"",minWidth:"",maxWidth:""}).removeClass("sm-nowrap"),t.dataSM("scroll-arrows")&&t.dataSM("scroll-arrows").remove(),t.css({zIndex:"",top:"",left:"",marginLeft:"",marginTop:"",display:""})),0==(t.attr("id")||"").indexOf(i.accessIdPrefix)&&t.removeAttr("id")}).removeDataSM("in-mega").removeDataSM("shown-before").removeDataSM("scroll-arrows").removeDataSM("parent-a").removeDataSM("level").removeDataSM("beforefirstshowfired").removeAttr("role").removeAttr("aria-hidden").removeAttr("aria-labelledby").removeAttr("aria-expanded"),this.$root.find("a.has-submenu").each(function(){var t=$(this);0==t.attr("id").indexOf(i.accessIdPrefix)&&t.removeAttr("id")}).removeClass("has-submenu").removeDataSM("sub").removeAttr("aria-haspopup").removeAttr("aria-controls").removeAttr("aria-expanded").closest("li").removeDataSM("sub"),this.opts.subIndicators&&this.$root.find("span.sub-arrow").remove(),this.opts.markCurrentItem&&this.$root.find("a.current").removeClass("current"),t||(this.$root=null,this.$firstLink=null,this.$firstSub=null,this.$disableOverlay&&(this.$disableOverlay.remove(),this.$disableOverlay=null),menuTrees.splice($.inArray(this,menuTrees),1))},disable:function(t){if(!this.disabled){if(this.menuHideAll(),!t&&!this.opts.isPopup&&this.$root.is(":visible")){var e=this.$root.offset();this.$disableOverlay=$('
').css({position:"absolute",top:e.top,left:e.left,width:this.$root.outerWidth(),height:this.$root.outerHeight(),zIndex:this.getStartZIndex(!0),opacity:0}).appendTo(document.body)}this.disabled=!0}},docClick:function(t){return this.$touchScrollingSub?(this.$touchScrollingSub=null,void 0):((this.visibleSubMenus.length&&!$.contains(this.$root[0],t.target)||$(t.target).closest("a").length)&&this.menuHideAll(),void 0)},docTouchEnd:function(){if(this.lastTouch){if(!(!this.visibleSubMenus.length||void 0!==this.lastTouch.x2&&this.lastTouch.x1!=this.lastTouch.x2||void 0!==this.lastTouch.y2&&this.lastTouch.y1!=this.lastTouch.y2||this.lastTouch.target&&$.contains(this.$root[0],this.lastTouch.target))){this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0);var t=this;this.hideTimeout=setTimeout(function(){t.menuHideAll()},350)}this.lastTouch=null}},docTouchMove:function(t){if(this.lastTouch){var e=t.originalEvent.touches[0];this.lastTouch.x2=e.pageX,this.lastTouch.y2=e.pageY}},docTouchStart:function(t){var e=t.originalEvent.touches[0];this.lastTouch={x1:e.pageX,y1:e.pageY,target:e.target}},enable:function(){this.disabled&&(this.$disableOverlay&&(this.$disableOverlay.remove(),this.$disableOverlay=null),this.disabled=!1)},getClosestMenu:function(t){for(var e=$(t).closest("ul");e.dataSM("in-mega");)e=e.parent().closest("ul");return e[0]||null},getHeight:function(t){return this.getOffset(t,!0)},getOffset:function(t,e){var i;"none"==t.css("display")&&(i={position:t[0].style.position,visibility:t[0].style.visibility},t.css({position:"absolute",visibility:"hidden"}).show());var s=t[0].getBoundingClientRect&&t[0].getBoundingClientRect(),o=s&&(e?s.height||s.bottom-s.top:s.width||s.right-s.left);return o||0===o||(o=e?t[0].offsetHeight:t[0].offsetWidth),i&&t.hide().css(i),o},getStartZIndex:function(t){var e=parseInt(this[t?"$root":"$firstSub"].css("z-index"));return!t&&isNaN(e)&&(e=parseInt(this.$root.css("z-index"))),isNaN(e)?1:e},getTouchPoint:function(t){return t.touches&&t.touches[0]||t.changedTouches&&t.changedTouches[0]||t},getViewport:function(t){var e=t?"Height":"Width",i=document.documentElement["client"+e],s=window["inner"+e];return s&&(i=Math.min(i,s)),i},getViewportHeight:function(){return this.getViewport(!0)},getViewportWidth:function(){return this.getViewport()},getWidth:function(t){return this.getOffset(t)},handleEvents:function(){return!this.disabled&&this.isCSSOn()},handleItemEvents:function(t){return this.handleEvents()&&!this.isLinkInMegaMenu(t)},isCollapsible:function(){return"static"==this.$firstSub.css("position")},isCSSOn:function(){return"inline"!=this.$firstLink.css("display")},isFixed:function(){var t="fixed"==this.$root.css("position");return t||this.$root.parentsUntil("body").each(function(){return"fixed"==$(this).css("position")?(t=!0,!1):void 0}),t},isLinkInMegaMenu:function(t){return $(this.getClosestMenu(t[0])).hasClass("mega-menu")},isTouchMode:function(){return!mouse||this.opts.noMouseOver||this.isCollapsible()},itemActivate:function(t,e){var i=t.closest("ul"),s=i.dataSM("level");if(s>1&&(!this.activatedItems[s-2]||this.activatedItems[s-2][0]!=i.dataSM("parent-a")[0])){var o=this;$(i.parentsUntil("[data-smartmenus-id]","ul").get().reverse()).add(i).each(function(){o.itemActivate($(this).dataSM("parent-a"))})}if((!this.isCollapsible()||e)&&this.menuHideSubMenus(this.activatedItems[s-1]&&this.activatedItems[s-1][0]==t[0]?s:s-1),this.activatedItems[s-1]=t,this.$root.triggerHandler("activate.smapi",t[0])!==!1){var a=t.dataSM("sub");a&&(this.isTouchMode()||!this.opts.showOnClick||this.clickActivated)&&this.menuShow(a)}},itemBlur:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&this.$root.triggerHandler("blur.smapi",e[0])},itemClick:function(t){var e=$(t.currentTarget);if(this.handleItemEvents(e)){if(this.$touchScrollingSub&&this.$touchScrollingSub[0]==e.closest("ul")[0])return this.$touchScrollingSub=null,t.stopPropagation(),!1;if(this.$root.triggerHandler("click.smapi",e[0])===!1)return!1;var i=$(t.target).is(".sub-arrow"),s=e.dataSM("sub"),o=s?2==s.dataSM("level"):!1,a=this.isCollapsible(),n=/toggle$/.test(this.opts.collapsibleBehavior),r=/link$/.test(this.opts.collapsibleBehavior),h=/^accordion/.test(this.opts.collapsibleBehavior);if(s&&!s.is(":visible")){if((!r||!a||i)&&(this.opts.showOnClick&&o&&(this.clickActivated=!0),this.itemActivate(e,h),s.is(":visible")))return this.focusActivated=!0,!1}else if(a&&(n||i))return this.itemActivate(e,h),this.menuHide(s),n&&(this.focusActivated=!1),!1;return this.opts.showOnClick&&o||e.hasClass("disabled")||this.$root.triggerHandler("select.smapi",e[0])===!1?!1:void 0}},itemDown:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&e.dataSM("mousedown",!0)},itemEnter:function(t){var e=$(t.currentTarget);if(this.handleItemEvents(e)){if(!this.isTouchMode()){this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0);var i=this;this.showTimeout=setTimeout(function(){i.itemActivate(e)},this.opts.showOnClick&&1==e.closest("ul").dataSM("level")?1:this.opts.showTimeout)}this.$root.triggerHandler("mouseenter.smapi",e[0])}},itemFocus:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&(!this.focusActivated||this.isTouchMode()&&e.dataSM("mousedown")||this.activatedItems.length&&this.activatedItems[this.activatedItems.length-1][0]==e[0]||this.itemActivate(e,!0),this.$root.triggerHandler("focus.smapi",e[0]))},itemLeave:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&(this.isTouchMode()||(e[0].blur(),this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0)),e.removeDataSM("mousedown"),this.$root.triggerHandler("mouseleave.smapi",e[0]))},menuHide:function(t){if(this.$root.triggerHandler("beforehide.smapi",t[0])!==!1&&(canAnimate&&t.stop(!0,!0),"none"!=t.css("display"))){var e=function(){t.css("z-index","")};this.isCollapsible()?canAnimate&&this.opts.collapsibleHideFunction?this.opts.collapsibleHideFunction.call(this,t,e):t.hide(this.opts.collapsibleHideDuration,e):canAnimate&&this.opts.hideFunction?this.opts.hideFunction.call(this,t,e):t.hide(this.opts.hideDuration,e),t.dataSM("scroll")&&(this.menuScrollStop(t),t.css({"touch-action":"","-ms-touch-action":"","-webkit-transform":"",transform:""}).off(".smartmenus_scroll").removeDataSM("scroll").dataSM("scroll-arrows").hide()),t.dataSM("parent-a").removeClass("highlighted").attr("aria-expanded","false"),t.attr({"aria-expanded":"false","aria-hidden":"true"});var i=t.dataSM("level");this.activatedItems.splice(i-1,1),this.visibleSubMenus.splice($.inArray(t,this.visibleSubMenus),1),this.$root.triggerHandler("hide.smapi",t[0])}},menuHideAll:function(){this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0);for(var t=this.opts.isPopup?1:0,e=this.visibleSubMenus.length-1;e>=t;e--)this.menuHide(this.visibleSubMenus[e]);this.opts.isPopup&&(canAnimate&&this.$root.stop(!0,!0),this.$root.is(":visible")&&(canAnimate&&this.opts.hideFunction?this.opts.hideFunction.call(this,this.$root):this.$root.hide(this.opts.hideDuration))),this.activatedItems=[],this.visibleSubMenus=[],this.clickActivated=!1,this.focusActivated=!1,this.zIndexInc=0,this.$root.triggerHandler("hideAll.smapi")},menuHideSubMenus:function(t){for(var e=this.activatedItems.length-1;e>=t;e--){var i=this.activatedItems[e].dataSM("sub");i&&this.menuHide(i)}},menuInit:function(t){if(!t.dataSM("in-mega")){t.hasClass("mega-menu")&&t.find("ul").dataSM("in-mega",!0);for(var e=2,i=t[0];(i=i.parentNode.parentNode)!=this.$root[0];)e++;var s=t.prevAll("a").eq(-1);s.length||(s=t.prevAll().find("a").eq(-1)),s.addClass("has-submenu").dataSM("sub",t),t.dataSM("parent-a",s).dataSM("level",e).parent().dataSM("sub",t);var o=s.attr("id")||this.accessIdPrefix+ ++this.idInc,a=t.attr("id")||this.accessIdPrefix+ ++this.idInc;s.attr({id:o,"aria-haspopup":"true","aria-controls":a,"aria-expanded":"false"}),t.attr({id:a,role:"group","aria-hidden":"true","aria-labelledby":o,"aria-expanded":"false"}),this.opts.subIndicators&&s[this.opts.subIndicatorsPos](this.$subArrow.clone())}},menuPosition:function(t){var e,i,s=t.dataSM("parent-a"),o=s.closest("li"),a=o.parent(),n=t.dataSM("level"),r=this.getWidth(t),h=this.getHeight(t),u=s.offset(),l=u.left,c=u.top,d=this.getWidth(s),m=this.getHeight(s),p=$(window),f=p.scrollLeft(),v=p.scrollTop(),b=this.getViewportWidth(),S=this.getViewportHeight(),g=a.parent().is("[data-sm-horizontal-sub]")||2==n&&!a.hasClass("sm-vertical"),M=this.opts.rightToLeftSubMenus&&!o.is("[data-sm-reverse]")||!this.opts.rightToLeftSubMenus&&o.is("[data-sm-reverse]"),w=2==n?this.opts.mainMenuSubOffsetX:this.opts.subMenusSubOffsetX,T=2==n?this.opts.mainMenuSubOffsetY:this.opts.subMenusSubOffsetY;if(g?(e=M?d-r-w:w,i=this.opts.bottomToTopSubMenus?-h-T:m+T):(e=M?w-r:d-w,i=this.opts.bottomToTopSubMenus?m-T-h:T),this.opts.keepInViewport){var y=l+e,I=c+i;if(M&&f>y?e=g?f-y+e:d-w:!M&&y+r>f+b&&(e=g?f+b-r-y+e:w-r),g||(S>h&&I+h>v+S?i+=v+S-h-I:(h>=S||v>I)&&(i+=v-I)),g&&(I+h>v+S+.49||v>I)||!g&&h>S+.49){var x=this;t.dataSM("scroll-arrows")||t.dataSM("scroll-arrows",$([$('')[0],$('')[0]]).on({mouseenter:function(){t.dataSM("scroll").up=$(this).hasClass("scroll-up"),x.menuScroll(t)},mouseleave:function(e){x.menuScrollStop(t),x.menuScrollOut(t,e)},"mousewheel DOMMouseScroll":function(t){t.preventDefault()}}).insertAfter(t));var A=".smartmenus_scroll";if(t.dataSM("scroll",{y:this.cssTransforms3d?0:i-m,step:1,itemH:m,subH:h,arrowDownH:this.getHeight(t.dataSM("scroll-arrows").eq(1))}).on(getEventsNS({mouseover:function(e){x.menuScrollOver(t,e)},mouseout:function(e){x.menuScrollOut(t,e)},"mousewheel DOMMouseScroll":function(e){x.menuScrollMousewheel(t,e)}},A)).dataSM("scroll-arrows").css({top:"auto",left:"0",marginLeft:e+(parseInt(t.css("border-left-width"))||0),width:r-(parseInt(t.css("border-left-width"))||0)-(parseInt(t.css("border-right-width"))||0),zIndex:t.css("z-index")}).eq(g&&this.opts.bottomToTopSubMenus?0:1).show(),this.isFixed()){var C={};C[touchEvents?"touchstart touchmove touchend":"pointerdown pointermove pointerup MSPointerDown MSPointerMove MSPointerUp"]=function(e){x.menuScrollTouch(t,e)},t.css({"touch-action":"none","-ms-touch-action":"none"}).on(getEventsNS(C,A))}}}t.css({top:"auto",left:"0",marginLeft:e,marginTop:i-m})},menuScroll:function(t,e,i){var s,o=t.dataSM("scroll"),a=t.dataSM("scroll-arrows"),n=o.up?o.upEnd:o.downEnd;if(!e&&o.momentum){if(o.momentum*=.92,s=o.momentum,.5>s)return this.menuScrollStop(t),void 0}else s=i||(e||!this.opts.scrollAccelerate?this.opts.scrollStep:Math.floor(o.step));var r=t.dataSM("level");if(this.activatedItems[r-1]&&this.activatedItems[r-1].dataSM("sub")&&this.activatedItems[r-1].dataSM("sub").is(":visible")&&this.menuHideSubMenus(r-1),o.y=o.up&&o.y>=n||!o.up&&n>=o.y?o.y:Math.abs(n-o.y)>s?o.y+(o.up?s:-s):n,t.css(this.cssTransforms3d?{"-webkit-transform":"translate3d(0, "+o.y+"px, 0)",transform:"translate3d(0, "+o.y+"px, 0)"}:{marginTop:o.y}),mouse&&(o.up&&o.y>o.downEnd||!o.up&&o.y0;t.dataSM("scroll-arrows").eq(i?0:1).is(":visible")&&(t.dataSM("scroll").up=i,this.menuScroll(t,!0))}e.preventDefault()},menuScrollOut:function(t,e){mouse&&(/^scroll-(up|down)/.test((e.relatedTarget||"").className)||(t[0]==e.relatedTarget||$.contains(t[0],e.relatedTarget))&&this.getClosestMenu(e.relatedTarget)==t[0]||t.dataSM("scroll-arrows").css("visibility","hidden"))},menuScrollOver:function(t,e){if(mouse&&!/^scroll-(up|down)/.test(e.target.className)&&this.getClosestMenu(e.target)==t[0]){this.menuScrollRefreshData(t);var i=t.dataSM("scroll"),s=$(window).scrollTop()-t.dataSM("parent-a").offset().top-i.itemH;t.dataSM("scroll-arrows").eq(0).css("margin-top",s).end().eq(1).css("margin-top",s+this.getViewportHeight()-i.arrowDownH).end().css("visibility","visible")}},menuScrollRefreshData:function(t){var e=t.dataSM("scroll"),i=$(window).scrollTop()-t.dataSM("parent-a").offset().top-e.itemH;this.cssTransforms3d&&(i=-(parseFloat(t.css("margin-top"))-i)),$.extend(e,{upEnd:i,downEnd:i+this.getViewportHeight()-e.subH})},menuScrollStop:function(t){return this.scrollTimeout?(cancelAnimationFrame(this.scrollTimeout),this.scrollTimeout=0,t.dataSM("scroll").step=1,!0):void 0},menuScrollTouch:function(t,e){if(e=e.originalEvent,isTouchEvent(e)){var i=this.getTouchPoint(e);if(this.getClosestMenu(i.target)==t[0]){var s=t.dataSM("scroll");if(/(start|down)$/i.test(e.type))this.menuScrollStop(t)?(e.preventDefault(),this.$touchScrollingSub=t):this.$touchScrollingSub=null,this.menuScrollRefreshData(t),$.extend(s,{touchStartY:i.pageY,touchStartTime:e.timeStamp});else if(/move$/i.test(e.type)){var o=void 0!==s.touchY?s.touchY:s.touchStartY;if(void 0!==o&&o!=i.pageY){this.$touchScrollingSub=t;var a=i.pageY>o;void 0!==s.up&&s.up!=a&&$.extend(s,{touchStartY:i.pageY,touchStartTime:e.timeStamp}),$.extend(s,{up:a,touchY:i.pageY}),this.menuScroll(t,!0,Math.abs(i.pageY-o))}e.preventDefault()}else void 0!==s.touchY&&((s.momentum=15*Math.pow(Math.abs(i.pageY-s.touchStartY)/(e.timeStamp-s.touchStartTime),2))&&(this.menuScrollStop(t),this.menuScroll(t),e.preventDefault()),delete s.touchY)}}},menuShow:function(t){if((t.dataSM("beforefirstshowfired")||(t.dataSM("beforefirstshowfired",!0),this.$root.triggerHandler("beforefirstshow.smapi",t[0])!==!1))&&this.$root.triggerHandler("beforeshow.smapi",t[0])!==!1&&(t.dataSM("shown-before",!0),canAnimate&&t.stop(!0,!0),!t.is(":visible"))){var e=t.dataSM("parent-a"),i=this.isCollapsible();if((this.opts.keepHighlighted||i)&&e.addClass("highlighted"),i)t.removeClass("sm-nowrap").css({zIndex:"",width:"auto",minWidth:"",maxWidth:"",top:"",left:"",marginLeft:"",marginTop:""});else{if(t.css("z-index",this.zIndexInc=(this.zIndexInc||this.getStartZIndex())+1),(this.opts.subMenusMinWidth||this.opts.subMenusMaxWidth)&&(t.css({width:"auto",minWidth:"",maxWidth:""}).addClass("sm-nowrap"),this.opts.subMenusMinWidth&&t.css("min-width",this.opts.subMenusMinWidth),this.opts.subMenusMaxWidth)){var s=this.getWidth(t);t.css("max-width",this.opts.subMenusMaxWidth),s>this.getWidth(t)&&t.removeClass("sm-nowrap").css("width",this.opts.subMenusMaxWidth)}this.menuPosition(t)}var o=function(){t.css("overflow","")};i?canAnimate&&this.opts.collapsibleShowFunction?this.opts.collapsibleShowFunction.call(this,t,o):t.show(this.opts.collapsibleShowDuration,o):canAnimate&&this.opts.showFunction?this.opts.showFunction.call(this,t,o):t.show(this.opts.showDuration,o),e.attr("aria-expanded","true"),t.attr({"aria-expanded":"true","aria-hidden":"false"}),this.visibleSubMenus.push(t),this.$root.triggerHandler("show.smapi",t[0])}},popupHide:function(t){this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0);var e=this;this.hideTimeout=setTimeout(function(){e.menuHideAll()},t?1:this.opts.hideTimeout)},popupShow:function(t,e){if(!this.opts.isPopup)return alert('SmartMenus jQuery Error:\n\nIf you want to show this menu via the "popupShow" method, set the isPopup:true option.'),void 0;if(this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0),this.$root.dataSM("shown-before",!0),canAnimate&&this.$root.stop(!0,!0),!this.$root.is(":visible")){this.$root.css({left:t,top:e});var i=this,s=function(){i.$root.css("overflow","")};canAnimate&&this.opts.showFunction?this.opts.showFunction.call(this,this.$root,s):this.$root.show(this.opts.showDuration,s),this.visibleSubMenus[0]=this.$root}},refresh:function(){this.destroy(!0),this.init(!0)},rootKeyDown:function(t){if(this.handleEvents())switch(t.keyCode){case 27:var e=this.activatedItems[0];if(e){this.menuHideAll(),e[0].focus();var i=e.dataSM("sub");i&&this.menuHide(i)}break;case 32:var s=$(t.target);if(s.is("a")&&this.handleItemEvents(s)){var i=s.dataSM("sub");i&&!i.is(":visible")&&(this.itemClick({currentTarget:t.target}),t.preventDefault())}}},rootOut:function(t){if(this.handleEvents()&&!this.isTouchMode()&&t.target!=this.$root[0]&&(this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0),!this.opts.showOnClick||!this.opts.hideOnClick)){var e=this;this.hideTimeout=setTimeout(function(){e.menuHideAll()},this.opts.hideTimeout)}},rootOver:function(t){this.handleEvents()&&!this.isTouchMode()&&t.target!=this.$root[0]&&this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0)},winResize:function(t){if(this.handleEvents()){if(!("onorientationchange"in window)||"orientationchange"==t.type){var e=this.isCollapsible();this.wasCollapsible&&e||(this.activatedItems.length&&this.activatedItems[this.activatedItems.length-1][0].blur(),this.menuHideAll()),this.wasCollapsible=e}}else if(this.$disableOverlay){var i=this.$root.offset();this.$disableOverlay.css({top:i.top,left:i.left,width:this.$root.outerWidth(),height:this.$root.outerHeight()})}}}}),$.fn.dataSM=function(t,e){return e?this.data(t+"_smartmenus",e):this.data(t+"_smartmenus")},$.fn.removeDataSM=function(t){return this.removeData(t+"_smartmenus")},$.fn.smartmenus=function(options){if("string"==typeof options){var args=arguments,method=options;return Array.prototype.shift.call(args),this.each(function(){var t=$(this).data("smartmenus");t&&t[method]&&t[method].apply(t,args)})}return this.each(function(){var dataOpts=$(this).data("sm-options")||null;if(dataOpts)try{dataOpts=eval("("+dataOpts+")")}catch(e){dataOpts=null,alert('ERROR\n\nSmartMenus jQuery init:\nInvalid "data-sm-options" attribute value syntax.')}new $.SmartMenus(this,$.extend({},$.fn.smartmenus.defaults,options,dataOpts))})},$.fn.smartmenus.defaults={isPopup:!1,mainMenuSubOffsetX:0,mainMenuSubOffsetY:0,subMenusSubOffsetX:0,subMenusSubOffsetY:0,subMenusMinWidth:"10em",subMenusMaxWidth:"20em",subIndicators:!0,subIndicatorsPos:"append",subIndicatorsText:"",scrollStep:30,scrollAccelerate:!0,showTimeout:250,hideTimeout:500,showDuration:0,showFunction:null,hideDuration:0,hideFunction:function(t,e){t.fadeOut(200,e)},collapsibleShowDuration:0,collapsibleShowFunction:function(t,e){t.slideDown(200,e)},collapsibleHideDuration:0,collapsibleHideFunction:function(t,e){t.slideUp(200,e)},showOnClick:!1,hideOnClick:!0,noMouseOver:!1,keepInViewport:!0,keepHighlighted:!0,markCurrentItem:!1,markCurrentTree:!0,rightToLeftSubMenus:!1,bottomToTopSubMenus:!1,collapsibleBehavior:"default"},$}); \ No newline at end of file diff --git a/documentation/html/md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html b/documentation/html/md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html deleted file mode 100644 index 630eb97..0000000 --- a/documentation/html/md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html +++ /dev/null @@ -1,387 +0,0 @@ - - - - - - - -esp32_BNO08x: README - - - - - - - - - - - - - - - -
-
- - - - - - -
-
esp32_BNO08x 1.2 -
-
C++ BNO08x IMU driver component for esp-idf.
-
-
- - - - - - - -
-
- -
-
-
- -
- -
-
- - -
-
-
-
-
-
Loading...
-
Searching...
-
No Matches
-
-
-
-
- -
-
README
-
-
-

Table of Contents.

-

image

-
    -
  1. -About
  2. -
  3. -Getting Started -
  4. -
  5. -Unit Tests -
  6. -
  7. -Documentation
  8. -
  9. -Program Flowcharts
  10. -
  11. -Acknowledgements
  12. -
  13. -License
  14. -
  15. -Contact
  16. -
-

-About

-

esp32_BNO08x is a C++ component for esp-idf v5.x, serving as a driver for both BNO080 and BNO085 IMUs.
-

-

Originally based on the SparkFun BNO080 Arduino Library, it has since diverged significantly in implementation while retaining all original features and more, including callback functions enabled by its multi-tasked approach.

-

Currently, only SPI is supported. There are no plans to support I2C due to unpredictable behavior caused by an esp32 I2C driver silicon bug. UART support may be implemented in the future.

-

-Getting Started

-

(back to top)

-

-Wiring

-

The default wiring is depicted below, it can be changed at driver initialization (see example section).
-

-

If your ESP does not have the GPIO pin numbers depicted below, you must change the default GPIO settings in menuconfig. See the Menuconfig section.

-

image

-

(back to top)

-

-Adding to Project

-
    -
  1. Create a "components" directory in the root workspace directory of your esp-idf project if it does not exist already.
    -

    -

    In workspace directory:
    -

    mkdir components
    -
  2. -
  3. Cd into the components directory and clone the esp32_BNO08x repo.

    -
    cd components
    -
    git clone https://github.com/myles-parfeniuk/esp32_BNO08x.git
    -
  4. -
  5. Ensure you clean your esp-idf project before rebuilding.
    - Within esp-idf enabled terminal:
    idf.py fullclean
    -
  6. -
-

(back to top)

-

-Menuconfig

-

This library provides a menuconfig menu configured in Kconfig.projbuild. It contains settings to control the default GPIO and a few other things.
-

-

To access the menu:

-
    -
  1. Within esp-idf enabled terminal, execute the menuconfig command:
    idf.py menuconfig
    -
  2. -
  3. Scroll down to the esp_BNO08x menu and enter it, if you're using vsCode you may have to use the "j" and "k" keys instead of the arrow keys. image
  4. -
  5. Modify whatever settings you'd like from the sub menus. The GPIO Configuration menu allows for the default GPIO pins to be modified, the SPI Configuration menu allows for the default host peripheral, SCLK frequency, and queue size to be modified, the Logging menu allows for the enabling and disabling of log/print statements, and the Callbacks menu allows for the default size of the call-back execution task to be modified. image
  6. -
-

(back to top)

-

-Examples

-

There are two ways data returned from the BNO08x can be accessed with this library:

-
    -
  1. Polling Method with data_available() Function:
      -
    • Use the data_available() function to poll for new data, similar to the SparkFun library.
    • -
    • Behavior: It is a blocking function that returns true when new data is received or false if a timeout occurs.
    • -
    • See the Polling Example below.
    • -
    -
  2. -
  3. Callback Registration with register_cb() Function:
      -
    • Register callback functions that automatically execute upon receiving new data.
    • -
    • Behavior: The registered callback will be invoked whenever new data is available.
    • -
    • See the Call-Back Function Example below.
    • -
    -
  4. -
-

-Polling Example

-
#include <stdio.h>
-
#include "BNO08x.hpp"
-
-
extern "C" void app_main(void)
-
{
-
BNO08x imu; //create IMU object with default wiring scheme
-
float x, y, z = 0;
-
-
//if a custom wiring scheme is desired instead of default:
-
-
/*
-
bno08x_config_t imu_config; //create config struct
-
imu_config.io_mosi = GPIO_NUM_X; //assign pin
-
imu_config.io_miso = GPIO_NUM_X; //assign pin
-
//etc...
-
BNO08x imu(imu_config); //pass config to BNO08x constructor
-
*/
-
-
-
imu.initialize(); //initialize IMU
-
-
//enable gyro & game rotation vector
-
imu.enable_game_rotation_vector(100000UL); //100,000us == 100ms report interval
-
imu.enable_gyro(150000UL); //150,000us == 150ms report interval
-
-
while(1)
-
{
-
//print absolute heading in degrees and angular velocity in Rad/s
- -
{
-
x = imu.get_gyro_calibrated_velocity_X();
-
y = imu.get_gyro_calibrated_velocity_Y();
-
z = imu.get_gyro_calibrated_velocity_Z();
-
ESP_LOGW("Main", "Velocity: x: %.3f y: %.3f z: %.3f", x, y, z);
-
- - - -
ESP_LOGI("Main", "Euler Angle: x (roll): %.3f y (pitch): %.3f z (yaw): %.3f", x, y, z);
-
}
-
}
-
-
}
- -
BNO08x * imu
Definition CallbackTests.cpp:20
-
BNO08x IMU driver class.
Definition BNO08x.hpp:34
-
float get_roll_deg()
Get the reported rotation about x axis.
Definition BNO08x.cpp:2942
-
bool data_available(bool ignore_no_reports_enabled=false)
Checks if BNO08x has asserted interrupt and sent data.
Definition BNO08x.cpp:1469
-
void enable_game_rotation_vector(uint32_t time_between_reports)
Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19)
Definition BNO08x.cpp:2223
-
bool initialize()
Initializes BNO08x sensor.
Definition BNO08x.cpp:74
-
float get_pitch_deg()
Get the reported rotation about y axis.
Definition BNO08x.cpp:2952
-
float get_yaw_deg()
Get the reported rotation about z axis.
Definition BNO08x.cpp:2962
-

-Call-Back Function Example

-
#include <stdio.h>
-
#include "BNO08x.hpp"
-
-
extern "C" void app_main(void)
-
{
-
BNO08x imu; // create IMU object with default wiring scheme
-
-
// if a custom wiring scheme is desired instead of default:
-
-
/*
-
bno08x_config_t imu_config; //create config struct
-
imu_config.io_mosi = GPIO_NUM_X; //assign pin
-
imu_config.io_miso = GPIO_NUM_X; //assign pin
-
//etc...
-
BNO08x imu(imu_config); //pass config to BNO08x constructor
-
*/
-
-
imu.initialize(); // initialize IMU
-
-
// enable gyro & game rotation vector
-
imu.enable_game_rotation_vector(100000UL); // 100,000us == 100ms report interval
-
imu.enable_gyro(150000UL); // 150,000us == 150ms report interval
-
-
// register a callback function (in this case a lambda function, but it doesn't have to be)
- -
[&imu]()
-
{
-
// callback function contents, executed whenever new data is parsed
-
// print absolute heading in degrees and angular velocity in Rad/s
-
float x, y, z = 0;
-
x = imu.get_gyro_calibrated_velocity_X();
-
y = imu.get_gyro_calibrated_velocity_Y();
-
z = imu.get_gyro_calibrated_velocity_Z();
-
ESP_LOGW("Main", "Velocity: x: %.3f y: %.3f z: %.3f", x, y, z);
-
- - - -
ESP_LOGI("Main", "Euler Angle: x (roll): %.3f y (pitch): %.3f z (yaw): %.3f", x, y, z);
-
});
-
-
while (1)
-
{
-
vTaskDelay(300 / portTICK_PERIOD_MS); // delay here is irrelevant, we just don't want to trip cpu watchdog
-
}
-
}
-
void register_cb(std::function< void()> cb_fxn)
Registers a callback to execute when new data from a report is received.
Definition BNO08x.cpp:1493
-

(back to top)

-

-Unit Tests

-

A basic unit testing suite is included with this library, but it is very rudimentary.
- It can be used to verify some of the basic features of a BNO08x device and this library.

-

(back to top)

-

-Running Tests

-
    -
  1. Create a project and add the component as described in the getting started guide.
  2. -
  3. Open the outermost CMakeLists.txt file in the project root directory, as depicted below.
    -

    -

    image

    -
  4. -
  5. Modify the file by adding "set(TEST_COMPONENTS "esp32_BNO08x" CACHE STRING "Components to test.")" as depicted below:
    -

    -
    # For more information about build system see
    -
    # https://docs.espressif.com/projects/esp-idf/en/latest/api-guides/build-system.html
    -
    # The following five lines of boilerplate have to be in your project's
    -
    # CMakeLists in this exact order for cmake to work correctly
    -
    cmake_minimum_required(VERSION 3.16)
    -
    add_compile_definitions("ESP32C3_IMU_CONFIG")
    -
    set(TEST_COMPONENTS "esp32_BNO08x" CACHE STRING "Components to test.")
    -
    include($ENV{IDF_PATH}/tools/cmake/project.cmake)
    -
    project(bno08x_update)
    -
  6. -
  7. Include the test suite in your main file and launch into the test suite:
    -

    -
    #include <stdio.h>
    - -
    -
    extern "C" void app_main(void)
    -
    {
    - -
    }
    - -
    static void run_all_tests()
    Definition BNO08xTestSuite.hpp:35
    -
  8. -
  9. Ensure you run idf.py fullclean or delete your build directory before building for the first time after modifying the CMakeLists.txt file in step 3.
  10. -
-

(back to top)

-

-Adding Tests

-

Tests are implemented with the unity unit testing component.

-

To add a test, create a new .cpp file, or modify one of the existing ones in esp32_BNO08x/test/. Follow the existing test structure as an example, use the TEST_CASE(){} macro.
-

-

Any tests added will automatically be detected at build time.

-

(back to top)

-

-Documentation

-

API documentation generated with doxygen can be found in the documentation directory of the master branch.
-

-

(back to top)

-

-Program Flowcharts

-

The following charts illustrate the program flow this library implements for sending and receiving data from BNO08x.
- These are here to aid development for anyone looking to modify, fork, or contribute.
-

-

image

-

(back to top)

-

-Acknowledgements

-

Special thanks to the original creators of the sparkfun BNO080 library. Developing this without a reference would have been much more time consuming.
- https://github.com/sparkfun/SparkFun_BNO080_Arduino_Library
-

-

Special thanks to Anton Babiy, aka hwBirdy007 for helping with debugging SPI.
- https://github.com/hwBirdy007
-

-

(back to top)

-

-License

-

Distributed under the MIT License. See LICENSE.md for more information.

-

(back to top)

-

-Contact

-

Myles Parfeniuk - myles.nosp@m..par.nosp@m.fenyu.nosp@m.k@gm.nosp@m.ail.c.nosp@m.om

-

Project Link: https://github.com/myles-parfeniuk/esp32_BNO08x.git

-

(back to top)

-
-
-
- - - - diff --git a/documentation/html/menu.js b/documentation/html/menu.js deleted file mode 100644 index 717761d..0000000 --- a/documentation/html/menu.js +++ /dev/null @@ -1,134 +0,0 @@ -/* - @licstart The following is the entire license notice for the JavaScript code in this file. - - The MIT License (MIT) - - Copyright (C) 1997-2020 by Dimitri van Heesch - - Permission is hereby granted, free of charge, to any person obtaining a copy of this software - and associated documentation files (the "Software"), to deal in the Software without restriction, - including without limitation the rights to use, copy, modify, merge, publish, distribute, - sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in all copies or - substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - - @licend The above is the entire license notice for the JavaScript code in this file - */ -function initMenu(relPath,searchEnabled,serverSide,searchPage,search) { - function makeTree(data,relPath) { - let result=''; - if ('children' in data) { - result+='
    '; - for (let i in data.children) { - let url; - const link = data.children[i].url; - if (link.substring(0,1)=='^') { - url = link.substring(1); - } else { - url = relPath+link; - } - result+='
  • '+ - data.children[i].text+''+ - makeTree(data.children[i],relPath)+'
  • '; - } - result+='
'; - } - return result; - } - let searchBoxHtml; - if (searchEnabled) { - if (serverSide) { - searchBoxHtml='
'+ - '
'+ - '
 '+ - ''+ - '
'+ - '
'+ - '
'+ - '
'; - } else { - searchBoxHtml='
'+ - ''+ - ' '+ - ''+ - ''+ - ''+ - ''+ - ''+ - '
'; - } - } - - $('#main-nav').before('
'+ - ''+ - ''+ - '
'); - $('#main-nav').append(makeTree(menudata,relPath)); - $('#main-nav').children(':first').addClass('sm sm-dox').attr('id','main-menu'); - if (searchBoxHtml) { - $('#main-menu').append('
  • '); - } - const $mainMenuState = $('#main-menu-state'); - let prevWidth = 0; - if ($mainMenuState.length) { - const initResizableIfExists = function() { - if (typeof initResizable==='function') initResizable(); - } - // animate mobile menu - $mainMenuState.change(function() { - const $menu = $('#main-menu'); - let options = { duration: 250, step: initResizableIfExists }; - if (this.checked) { - options['complete'] = () => $menu.css('display', 'block'); - $menu.hide().slideDown(options); - } else { - options['complete'] = () => $menu.css('display', 'none'); - $menu.show().slideUp(options); - } - }); - // set default menu visibility - const resetState = function() { - const $menu = $('#main-menu'); - const newWidth = $(window).outerWidth(); - if (newWidth!=prevWidth) { - if ($(window).outerWidth()<768) { - $mainMenuState.prop('checked',false); $menu.hide(); - $('#searchBoxPos1').html(searchBoxHtml); - $('#searchBoxPos2').hide(); - } else { - $menu.show(); - $('#searchBoxPos1').empty(); - $('#searchBoxPos2').html(searchBoxHtml); - $('#searchBoxPos2').show(); - } - if (typeof searchBox!=='undefined') { - searchBox.CloseResultsWindow(); - } - prevWidth = newWidth; - } - } - $(window).ready(function() { resetState(); initResizableIfExists(); }); - $(window).resize(resetState); - } - $('#main-menu').smartmenus(); -} -/* @license-end */ diff --git a/documentation/html/menudata.js b/documentation/html/menudata.js deleted file mode 100644 index 8321059..0000000 --- a/documentation/html/menudata.js +++ /dev/null @@ -1,125 +0,0 @@ -/* - @licstart The following is the entire license notice for the JavaScript code in this file. - - The MIT License (MIT) - - Copyright (C) 1997-2020 by Dimitri van Heesch - - Permission is hereby granted, free of charge, to any person obtaining a copy of this software - and associated documentation files (the "Software"), to deal in the Software without restriction, - including without limitation the rights to use, copy, modify, merge, publish, distribute, - sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in all copies or - substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - - @licend The above is the entire license notice for the JavaScript code in this file -*/ -var menudata={children:[ -{text:"Main Page",url:"index.html"}, -{text:"Related Pages",url:"pages.html"}, -{text:"Classes",url:"annotated.html",children:[ -{text:"Class List",url:"annotated.html"}, -{text:"Class Index",url:"classes.html"}, -{text:"Class Members",url:"functions.html",children:[ -{text:"All",url:"functions.html",children:[ -{text:"a",url:"functions.html#index_a"}, -{text:"b",url:"functions_b.html#index_b"}, -{text:"c",url:"functions_c.html#index_c"}, -{text:"d",url:"functions_d.html#index_d"}, -{text:"e",url:"functions_e.html#index_e"}, -{text:"f",url:"functions_f.html#index_f"}, -{text:"g",url:"functions_g.html#index_g"}, -{text:"h",url:"functions_h.html#index_h"}, -{text:"i",url:"functions_i.html#index_i"}, -{text:"k",url:"functions_k.html#index_k"}, -{text:"l",url:"functions_l.html#index_l"}, -{text:"m",url:"functions_m.html#index_m"}, -{text:"p",url:"functions_p.html#index_p"}, -{text:"q",url:"functions_q.html#index_q"}, -{text:"r",url:"functions_r.html#index_r"}, -{text:"s",url:"functions_s.html#index_s"}, -{text:"t",url:"functions_t.html#index_t"}, -{text:"u",url:"functions_u.html#index_u"}, -{text:"w",url:"functions_w.html#index_w"}, -{text:"~",url:"functions_~.html#index__7E"}]}, -{text:"Functions",url:"functions_func.html",children:[ -{text:"a",url:"functions_func.html#index_a"}, -{text:"b",url:"functions_func_b.html#index_b"}, -{text:"c",url:"functions_func_c.html#index_c"}, -{text:"d",url:"functions_func_d.html#index_d"}, -{text:"e",url:"functions_func_e.html#index_e"}, -{text:"f",url:"functions_func_f.html#index_f"}, -{text:"g",url:"functions_func_g.html#index_g"}, -{text:"h",url:"functions_func_h.html#index_h"}, -{text:"i",url:"functions_func_i.html#index_i"}, -{text:"k",url:"functions_func_k.html#index_k"}, -{text:"l",url:"functions_func_l.html#index_l"}, -{text:"m",url:"functions_func_m.html#index_m"}, -{text:"p",url:"functions_func_p.html#index_p"}, -{text:"q",url:"functions_func_q.html#index_q"}, -{text:"r",url:"functions_func_r.html#index_r"}, -{text:"s",url:"functions_func_s.html#index_s"}, -{text:"t",url:"functions_func_t.html#index_t"}, -{text:"u",url:"functions_func_u.html#index_u"}, -{text:"w",url:"functions_func_w.html#index_w"}, -{text:"~",url:"functions_func_~.html#index__7E"}]}, -{text:"Variables",url:"functions_vars.html",children:[ -{text:"a",url:"functions_vars.html#index_a"}, -{text:"b",url:"functions_vars_b.html#index_b"}, -{text:"c",url:"functions_vars_c.html#index_c"}, -{text:"d",url:"functions_vars_d.html#index_d"}, -{text:"e",url:"functions_vars_e.html#index_e"}, -{text:"f",url:"functions_vars_f.html#index_f"}, -{text:"g",url:"functions_vars_g.html#index_g"}, -{text:"h",url:"functions_vars_h.html#index_h"}, -{text:"i",url:"functions_vars_i.html#index_i"}, -{text:"l",url:"functions_vars_l.html#index_l"}, -{text:"m",url:"functions_vars_m.html#index_m"}, -{text:"p",url:"functions_vars_p.html#index_p"}, -{text:"q",url:"functions_vars_q.html#index_q"}, -{text:"r",url:"functions_vars_r.html#index_r"}, -{text:"s",url:"functions_vars_s.html#index_s"}, -{text:"t",url:"functions_vars_t.html#index_t"}, -{text:"u",url:"functions_vars_u.html#index_u"}]}, -{text:"Typedefs",url:"functions_type.html"}, -{text:"Enumerations",url:"functions_enum.html"}, -{text:"Enumerator",url:"functions_eval.html"}, -{text:"Related Symbols",url:"functions_rela.html"}]}]}, -{text:"Files",url:"files.html",children:[ -{text:"File List",url:"files.html"}, -{text:"File Members",url:"globals.html",children:[ -{text:"All",url:"globals.html",children:[ -{text:"b",url:"globals.html#index_b"}, -{text:"c",url:"globals.html#index_c"}, -{text:"d",url:"globals.html#index_d"}, -{text:"e",url:"globals.html#index_e"}, -{text:"f",url:"globals.html#index_f"}, -{text:"i",url:"globals.html#index_i"}, -{text:"m",url:"globals.html#index_m"}, -{text:"n",url:"globals.html#index_n"}, -{text:"p",url:"globals.html#index_p"}, -{text:"r",url:"globals.html#index_r"}, -{text:"t",url:"globals.html#index_t"}, -{text:"u",url:"globals.html#index_u"}]}, -{text:"Functions",url:"globals_func.html",children:[ -{text:"d",url:"globals_func.html#index_d"}, -{text:"e",url:"globals_func.html#index_e"}, -{text:"f",url:"globals_func.html#index_f"}, -{text:"r",url:"globals_func.html#index_r"}, -{text:"t",url:"globals_func.html#index_t"}]}, -{text:"Variables",url:"globals_vars.html"}, -{text:"Typedefs",url:"globals_type.html"}, -{text:"Enumerations",url:"globals_enum.html"}, -{text:"Macros",url:"globals_defs.html",children:[ -{text:"c",url:"globals_defs.html#index_c"}, -{text:"i",url:"globals_defs.html#index_i"}, -{text:"p",url:"globals_defs.html#index_p"}, -{text:"u",url:"globals_defs.html#index_u"}]}]}]}]} diff --git a/documentation/html/minus.svg b/documentation/html/minus.svg deleted file mode 100644 index f70d0c1..0000000 --- a/documentation/html/minus.svg +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - - diff --git a/documentation/html/minusd.svg b/documentation/html/minusd.svg deleted file mode 100644 index 5f8e879..0000000 --- a/documentation/html/minusd.svg +++ /dev/null @@ -1,8 +0,0 @@ - - - - - - - - diff --git a/documentation/html/nav_f.png b/documentation/html/nav_f.png deleted file mode 100644 index 72a58a5..0000000 Binary files a/documentation/html/nav_f.png and /dev/null differ diff --git a/documentation/html/nav_fd.png b/documentation/html/nav_fd.png deleted file mode 100644 index 032fbdd..0000000 Binary files a/documentation/html/nav_fd.png and /dev/null differ diff --git a/documentation/html/nav_g.png b/documentation/html/nav_g.png deleted file mode 100644 index 2093a23..0000000 Binary files a/documentation/html/nav_g.png and /dev/null differ diff --git a/documentation/html/nav_h.png b/documentation/html/nav_h.png deleted file mode 100644 index 33389b1..0000000 Binary files a/documentation/html/nav_h.png and /dev/null differ diff --git a/documentation/html/nav_hd.png b/documentation/html/nav_hd.png deleted file mode 100644 index de80f18..0000000 Binary files a/documentation/html/nav_hd.png and /dev/null differ diff --git a/documentation/html/navtree.css b/documentation/html/navtree.css deleted file mode 100644 index 69211d4..0000000 --- a/documentation/html/navtree.css +++ /dev/null @@ -1,149 +0,0 @@ -#nav-tree .children_ul { - margin:0; - padding:4px; -} - -#nav-tree ul { - list-style:none outside none; - margin:0px; - padding:0px; -} - -#nav-tree li { - white-space:nowrap; - margin:0px; - padding:0px; -} - -#nav-tree .plus { - margin:0px; -} - -#nav-tree .selected { - background-image: url('tab_a.png'); - background-repeat:repeat-x; - color: var(--nav-text-active-color); - text-shadow: var(--nav-text-active-shadow); -} - -#nav-tree .selected .arrow { - color: var(--nav-arrow-selected-color); - text-shadow: none; -} - -#nav-tree img { - margin:0px; - padding:0px; - border:0px; - vertical-align: middle; -} - -#nav-tree a { - text-decoration:none; - padding:0px; - margin:0px; -} - -#nav-tree .label { - margin:0px; - padding:0px; - font: 12px var(--font-family-nav); -} - -#nav-tree .label a { - padding:2px; -} - -#nav-tree .selected a { - text-decoration:none; - color:var(--nav-text-active-color); -} - -#nav-tree .children_ul { - margin:0px; - padding:0px; -} - -#nav-tree .item { - margin:0px; - padding:0px; -} - -#nav-tree { - padding: 0px 0px; - font-size:14px; - overflow:auto; -} - -#doc-content { - overflow:auto; - display:block; - padding:0px; - margin:0px; - -webkit-overflow-scrolling : touch; /* iOS 5+ */ -} - -#side-nav { - padding:0 6px 0 0; - margin: 0px; - display:block; - position: absolute; - left: 0px; - width: $width; - overflow : hidden; -} - -.ui-resizable .ui-resizable-handle { - display:block; -} - -.ui-resizable-e { - background-image:var(--nav-splitbar-image); - background-size:100%; - background-repeat:repeat-y; - background-attachment: scroll; - cursor:ew-resize; - height:100%; - right:0; - top:0; - width:6px; -} - -.ui-resizable-handle { - display:none; - font-size:0.1px; - position:absolute; - z-index:1; -} - -#nav-tree-contents { - margin: 6px 0px 0px 0px; -} - -#nav-tree { - background-repeat:repeat-x; - background-color: var(--nav-background-color); - -webkit-overflow-scrolling : touch; /* iOS 5+ */ -} - -#nav-sync { - position:absolute; - top:5px; - right:24px; - z-index:0; -} - -#nav-sync img { - opacity:0.3; -} - -#nav-sync img:hover { - opacity:0.9; -} - -@media print -{ - #nav-tree { display: none; } - div.ui-resizable-handle { display: none; position: relative; } -} - diff --git a/documentation/html/navtree.js b/documentation/html/navtree.js deleted file mode 100644 index 884b79b..0000000 --- a/documentation/html/navtree.js +++ /dev/null @@ -1,482 +0,0 @@ -/* - @licstart The following is the entire license notice for the JavaScript code in this file. - - The MIT License (MIT) - - Copyright (C) 1997-2020 by Dimitri van Heesch - - Permission is hereby granted, free of charge, to any person obtaining a copy of this software - and associated documentation files (the "Software"), to deal in the Software without restriction, - including without limitation the rights to use, copy, modify, merge, publish, distribute, - sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in all copies or - substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - - @licend The above is the entire license notice for the JavaScript code in this file - */ - -function initNavTree(toroot,relpath) { - let navTreeSubIndices = []; - const ARROW_DOWN = '▼'; - const ARROW_RIGHT = '►'; - const NAVPATH_COOKIE_NAME = ''+'navpath'; - - const getData = function(varName) { - const i = varName.lastIndexOf('/'); - const n = i>=0 ? varName.substring(i+1) : varName; - return eval(n.replace(/-/g,'_')); - } - - const stripPath = function(uri) { - return uri.substring(uri.lastIndexOf('/')+1); - } - - const stripPath2 = function(uri) { - const i = uri.lastIndexOf('/'); - const s = uri.substring(i+1); - const m = uri.substring(0,i+1).match(/\/d\w\/d\w\w\/$/); - return m ? uri.substring(i-6) : s; - } - - const hashValue = function() { - return $(location).attr('hash').substring(1).replace(/[^\w-]/g,''); - } - - const hashUrl = function() { - return '#'+hashValue(); - } - - const pathName = function() { - return $(location).attr('pathname').replace(/[^-A-Za-z0-9+&@#/%?=~_|!:,.;()]/g, ''); - } - - const storeLink = function(link) { - if (!$("#nav-sync").hasClass('sync')) { - Cookie.writeSetting(NAVPATH_COOKIE_NAME,link,0); - } - } - - const deleteLink = function() { - Cookie.eraseSetting(NAVPATH_COOKIE_NAME); - } - - const cachedLink = function() { - return Cookie.readSetting(NAVPATH_COOKIE_NAME,''); - } - - const getScript = function(scriptName,func) { - const head = document.getElementsByTagName("head")[0]; - const script = document.createElement('script'); - script.id = scriptName; - script.type = 'text/javascript'; - script.onload = func; - script.src = scriptName+'.js'; - head.appendChild(script); - } - - const createIndent = function(o,domNode,node) { - let level=-1; - let n = node; - while (n.parentNode) { level++; n=n.parentNode; } - if (node.childrenData) { - const imgNode = document.createElement("span"); - imgNode.className = 'arrow'; - imgNode.style.paddingLeft=(16*level).toString()+'px'; - imgNode.innerHTML=ARROW_RIGHT; - node.plus_img = imgNode; - node.expandToggle = document.createElement("a"); - node.expandToggle.href = "javascript:void(0)"; - node.expandToggle.onclick = function() { - if (node.expanded) { - $(node.getChildrenUL()).slideUp("fast"); - node.plus_img.innerHTML=ARROW_RIGHT; - node.expanded = false; - } else { - expandNode(o, node, false, true); - } - } - node.expandToggle.appendChild(imgNode); - domNode.appendChild(node.expandToggle); - } else { - let span = document.createElement("span"); - span.className = 'arrow'; - span.style.width = 16*(level+1)+'px'; - span.innerHTML = ' '; - domNode.appendChild(span); - } - } - - let animationInProgress = false; - - const gotoAnchor = function(anchor,aname) { - let pos, docContent = $('#doc-content'); - let ancParent = $(anchor.parent()); - if (ancParent.hasClass('memItemLeft') || ancParent.hasClass('memtitle') || - ancParent.hasClass('fieldname') || ancParent.hasClass('fieldtype') || - ancParent.is(':header')) { - pos = ancParent.position().top; - } else if (anchor.position()) { - pos = anchor.position().top; - } - if (pos) { - const dcOffset = docContent.offset().top; - const dcHeight = docContent.height(); - const dcScrHeight = docContent[0].scrollHeight - const dcScrTop = docContent.scrollTop(); - let dist = Math.abs(Math.min(pos-dcOffset,dcScrHeight-dcHeight-dcScrTop)); - animationInProgress = true; - docContent.animate({ - scrollTop: pos + dcScrTop - dcOffset - },Math.max(50,Math.min(500,dist)),function() { - window.location.href=aname; - animationInProgress=false; - }); - } - } - - const newNode = function(o, po, text, link, childrenData, lastNode) { - const node = { - children : [], - childrenData : childrenData, - depth : po.depth + 1, - relpath : po.relpath, - isLast : lastNode, - li : document.createElement("li"), - parentNode : po, - itemDiv : document.createElement("div"), - labelSpan : document.createElement("span"), - label : document.createTextNode(text), - expanded : false, - childrenUL : null, - getChildrenUL : function() { - if (!this.childrenUL) { - this.childrenUL = document.createElement("ul"); - this.childrenUL.className = "children_ul"; - this.childrenUL.style.display = "none"; - this.li.appendChild(node.childrenUL); - } - return node.childrenUL; - }, - }; - - node.itemDiv.className = "item"; - node.labelSpan.className = "label"; - createIndent(o,node.itemDiv,node); - node.itemDiv.appendChild(node.labelSpan); - node.li.appendChild(node.itemDiv); - - const a = document.createElement("a"); - node.labelSpan.appendChild(a); - po.getChildrenUL().appendChild(node.li); - a.appendChild(node.label); - if (link) { - let url; - if (link.substring(0,1)=='^') { - url = link.substring(1); - link = url; - } else { - url = node.relpath+link; - } - a.className = stripPath(link.replace('#',':')); - if (link.indexOf('#')!=-1) { - const aname = '#'+link.split('#')[1]; - const srcPage = stripPath(pathName()); - const targetPage = stripPath(link.split('#')[0]); - a.href = srcPage!=targetPage ? url : aname; - a.onclick = function() { - storeLink(link); - aPPar = $(a).parent().parent(); - if (!aPPar.hasClass('selected')) { - $('.item').removeClass('selected'); - $('.item').removeAttr('id'); - aPPar.addClass('selected'); - aPPar.attr('id','selected'); - } - const anchor = $(aname); - gotoAnchor(anchor,aname); - }; - } else { - a.href = url; - a.onclick = () => storeLink(link); - } - } else if (childrenData != null) { - a.className = "nolink"; - a.href = "javascript:void(0)"; - a.onclick = node.expandToggle.onclick; - } - return node; - } - - const showRoot = function() { - const headerHeight = $("#top").height(); - const footerHeight = $("#nav-path").height(); - const windowHeight = $(window).height() - headerHeight - footerHeight; - (function() { // retry until we can scroll to the selected item - try { - const navtree=$('#nav-tree'); - navtree.scrollTo('#selected',100,{offset:-windowHeight/2}); - } catch (err) { - setTimeout(arguments.callee, 0); - } - })(); - } - - const expandNode = function(o, node, imm, setFocus) { - if (node.childrenData && !node.expanded) { - if (typeof(node.childrenData)==='string') { - const varName = node.childrenData; - getScript(node.relpath+varName,function() { - node.childrenData = getData(varName); - expandNode(o, node, imm, setFocus); - }); - } else { - if (!node.childrenVisited) { - getNode(o, node); - } - $(node.getChildrenUL()).slideDown("fast"); - node.plus_img.innerHTML = ARROW_DOWN; - node.expanded = true; - if (setFocus) { - $(node.expandToggle).focus(); - } - } - } - } - - const glowEffect = function(n,duration) { - n.addClass('glow').delay(duration).queue(function(next) { - $(this).removeClass('glow');next(); - }); - } - - const highlightAnchor = function() { - const aname = hashUrl(); - const anchor = $(aname); - if (anchor.parent().attr('class')=='memItemLeft') { - let rows = $('.memberdecls tr[class$="'+hashValue()+'"]'); - glowEffect(rows.children(),300); // member without details - } else if (anchor.parent().attr('class')=='fieldname') { - glowEffect(anchor.parent().parent(),1000); // enum value - } else if (anchor.parent().attr('class')=='fieldtype') { - glowEffect(anchor.parent().parent(),1000); // struct field - } else if (anchor.parent().is(":header")) { - glowEffect(anchor.parent(),1000); // section header - } else { - glowEffect(anchor.next(),1000); // normal member - } - gotoAnchor(anchor,aname); - } - - const selectAndHighlight = function(hash,n) { - let a; - if (hash) { - const link=stripPath(pathName())+':'+hash.substring(1); - a=$('.item a[class$="'+link+'"]'); - } - if (a && a.length) { - a.parent().parent().addClass('selected'); - a.parent().parent().attr('id','selected'); - highlightAnchor(); - } else if (n) { - $(n.itemDiv).addClass('selected'); - $(n.itemDiv).attr('id','selected'); - } - let topOffset=5; - if ($('#nav-tree-contents .item:first').hasClass('selected')) { - topOffset+=25; - } - $('#nav-sync').css('top',topOffset+'px'); - showRoot(); - } - - const showNode = function(o, node, index, hash) { - if (node && node.childrenData) { - if (typeof(node.childrenData)==='string') { - const varName = node.childrenData; - getScript(node.relpath+varName,function() { - node.childrenData = getData(varName); - showNode(o,node,index,hash); - }); - } else { - if (!node.childrenVisited) { - getNode(o, node); - } - $(node.getChildrenUL()).css({'display':'block'}); - node.plus_img.innerHTML = ARROW_DOWN; - node.expanded = true; - const n = node.children[o.breadcrumbs[index]]; - if (index+11 ? '#'+parts[1].replace(/[^\w-]/g,'') : ''; - } - if (hash.match(/^#l\d+$/)) { - const anchor=$('a[name='+hash.substring(1)+']'); - glowEffect(anchor.parent(),1000); // line number - hash=''; // strip line number anchors - } - const url=root+hash; - let i=-1; - while (NAVTREEINDEX[i+1]<=url) i++; - if (i==-1) { i=0; root=NAVTREE[0][1]; } // fallback: show index - if (navTreeSubIndices[i]) { - gotoNode(o,i,root,hash,relpath) - } else { - getScript(relpath+'navtreeindex'+i,function() { - navTreeSubIndices[i] = eval('NAVTREEINDEX'+i); - if (navTreeSubIndices[i]) { - gotoNode(o,i,root,hash,relpath); - } - }); - } - } - - const showSyncOff = function(n,relpath) { - n.html(''); - } - - const showSyncOn = function(n,relpath) { - n.html(''); - } - - const o = { - toroot : toroot, - node : { - childrenData : NAVTREE, - children : [], - childrenUL : document.createElement("ul"), - getChildrenUL : function() { return this.childrenUL }, - li : document.getElementById("nav-tree-contents"), - depth : 0, - relpath : relpath, - expanded : false, - isLast : true, - plus_img : document.createElement("span"), - }, - }; - o.node.li.appendChild(o.node.childrenUL); - o.node.plus_img.className = 'arrow'; - o.node.plus_img.innerHTML = ARROW_RIGHT; - - const navSync = $('#nav-sync'); - if (cachedLink()) { - showSyncOff(navSync,relpath); - navSync.removeClass('sync'); - } else { - showSyncOn(navSync,relpath); - } - - navSync.click(() => { - const navSync = $('#nav-sync'); - if (navSync.hasClass('sync')) { - navSync.removeClass('sync'); - showSyncOff(navSync,relpath); - storeLink(stripPath2(pathName())+hashUrl()); - } else { - navSync.addClass('sync'); - showSyncOn(navSync,relpath); - deleteLink(); - } - }); - - navTo(o,toroot,hashUrl(),relpath); - showRoot(); - - $(window).bind('hashchange', () => { - if (window.location.hash && window.location.hash.length>1) { - let a; - if ($(location).attr('hash')) { - const clslink=stripPath(pathName())+':'+hashValue(); - a=$('.item a[class$="'+clslink.replace(/ - - - - - - -esp32_BNO08x: Related Pages - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    Related Pages
    -
    -
    -
    Here is a list of all related documentation pages:
    - - -
     READMETable of Contents
    -
    -
    -
    - - - - diff --git a/documentation/html/plus.svg b/documentation/html/plus.svg deleted file mode 100644 index 0752016..0000000 --- a/documentation/html/plus.svg +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/plusd.svg b/documentation/html/plusd.svg deleted file mode 100644 index 0c65bfe..0000000 --- a/documentation/html/plusd.svg +++ /dev/null @@ -1,9 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/resize.js b/documentation/html/resize.js deleted file mode 100644 index 6ad2ae8..0000000 --- a/documentation/html/resize.js +++ /dev/null @@ -1,109 +0,0 @@ -/* - @licstart The following is the entire license notice for the JavaScript code in this file. - - The MIT License (MIT) - - Copyright (C) 1997-2020 by Dimitri van Heesch - - Permission is hereby granted, free of charge, to any person obtaining a copy of this software - and associated documentation files (the "Software"), to deal in the Software without restriction, - including without limitation the rights to use, copy, modify, merge, publish, distribute, - sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in all copies or - substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - - @licend The above is the entire license notice for the JavaScript code in this file - */ - -function initResizable() { - let sidenav,navtree,content,header,footer,barWidth=6; - const RESIZE_COOKIE_NAME = ''+'width'; - - function resizeWidth() { - const sidenavWidth = $(sidenav).outerWidth(); - content.css({marginLeft:parseInt(sidenavWidth)+"px"}); - if (typeof page_layout!=='undefined' && page_layout==1) { - footer.css({marginLeft:parseInt(sidenavWidth)+"px"}); - } - Cookie.writeSetting(RESIZE_COOKIE_NAME,sidenavWidth-barWidth); - } - - function restoreWidth(navWidth) { - content.css({marginLeft:parseInt(navWidth)+barWidth+"px"}); - if (typeof page_layout!=='undefined' && page_layout==1) { - footer.css({marginLeft:parseInt(navWidth)+barWidth+"px"}); - } - sidenav.css({width:navWidth + "px"}); - } - - function resizeHeight() { - const headerHeight = header.outerHeight(); - const footerHeight = footer.outerHeight(); - const windowHeight = $(window).height(); - let contentHeight,navtreeHeight,sideNavHeight; - if (typeof page_layout==='undefined' || page_layout==0) { /* DISABLE_INDEX=NO */ - contentHeight = windowHeight - headerHeight - footerHeight; - navtreeHeight = contentHeight; - sideNavHeight = contentHeight; - } else if (page_layout==1) { /* DISABLE_INDEX=YES */ - contentHeight = windowHeight - footerHeight; - navtreeHeight = windowHeight - headerHeight; - sideNavHeight = windowHeight; - } - content.css({height:contentHeight + "px"}); - navtree.css({height:navtreeHeight + "px"}); - sidenav.css({height:sideNavHeight + "px"}); - if (location.hash.slice(1)) { - (document.getElementById(location.hash.slice(1))||document.body).scrollIntoView(); - } - } - - function collapseExpand() { - let newWidth; - if (sidenav.width()>0) { - newWidth=0; - } else { - const width = Cookie.readSetting(RESIZE_COOKIE_NAME,250); - newWidth = (width>250 && width<$(window).width()) ? width : 250; - } - restoreWidth(newWidth); - const sidenavWidth = $(sidenav).outerWidth(); - Cookie.writeSetting(RESIZE_COOKIE_NAME,sidenavWidth-barWidth); - } - - header = $("#top"); - sidenav = $("#side-nav"); - content = $("#doc-content"); - navtree = $("#nav-tree"); - footer = $("#nav-path"); - $(".side-nav-resizable").resizable({resize: () => resizeWidth() }); - $(sidenav).resizable({ minWidth: 0 }); - $(window).resize(() => resizeHeight()); - const device = navigator.userAgent.toLowerCase(); - const touch_device = device.match(/(iphone|ipod|ipad|android)/); - if (touch_device) { /* wider split bar for touch only devices */ - $(sidenav).css({ paddingRight:'20px' }); - $('.ui-resizable-e').css({ width:'20px' }); - $('#nav-sync').css({ right:'34px' }); - barWidth=20; - } - const width = Cookie.readSetting(RESIZE_COOKIE_NAME,250); - if (width) { restoreWidth(width); } else { resizeWidth(); } - resizeHeight(); - const url = location.href; - const i=url.indexOf("#"); - if (i>=0) window.location.hash=url.substr(i); - const _preventDefault = (evt) => evt.preventDefault(); - $("#splitbar").bind("dragstart", _preventDefault).bind("selectstart", _preventDefault); - $(".ui-resizable-handle").dblclick(collapseExpand); - $(window).on('load',resizeHeight); -} -/* @license-end */ diff --git a/documentation/html/search/all_0.js b/documentation/html/search/all_0.js deleted file mode 100644 index fee6fe5..0000000 --- a/documentation/html/search/all_0.js +++ /dev/null @@ -1,19 +0,0 @@ -var searchData= -[ - ['about_0',['About',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md0',1,'']]], - ['accel_5faccuracy_1',['accel_accuracy',['../class_b_n_o08x.html#a3365b7ebde01e284274e655c60343df9',1,'BNO08x::accel_accuracy'],['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac5d393de0f15176ba81bc63a80b49ca3',1,'BNO08xTestHelper::imu_report_data_t::accel_accuracy']]], - ['accel_5flin_5faccuracy_2',['accel_lin_accuracy',['../class_b_n_o08x.html#a35e1635ef5edde8fc8640f978c6f2e3c',1,'BNO08x']]], - ['accel_5fx_3',['accel_x',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5c01b349cc9e4e45c78c576882d633fd',1,'BNO08xTestHelper::imu_report_data_t']]], - ['accel_5fy_4',['accel_y',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e594d0a1e86fb575f72c6f330c8983c',1,'BNO08xTestHelper::imu_report_data_t']]], - ['accel_5fz_5',['accel_z',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af134cb789c29120033d81916e0c100d4',1,'BNO08xTestHelper::imu_report_data_t']]], - ['accelerometer_5fdata_5fis_5fnew_6',['accelerometer_data_is_new',['../class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea',1,'BNO08xTestHelper']]], - ['accelerometer_5fq1_7',['ACCELEROMETER_Q1',['../class_b_n_o08x.html#a0564aaf5b20dc42b54db4fb3115ac1c7',1,'BNO08x']]], - ['acknowledgements_8',['Acknowledgements',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md13',1,'']]], - ['activity_5fclassifier_9',['activity_classifier',['../class_b_n_o08x.html#a75cea49c1c08ca28d9fa7e5ed61c6e7b',1,'BNO08x::activity_classifier'],['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0455033deba9570f248e8059cf6a3ce1',1,'BNO08xTestHelper::imu_report_data_t::activity_classifier']]], - ['activity_5fclassifier_5fdata_5fis_5fnew_10',['activity_classifier_data_is_new',['../class_b_n_o08x_test_helper.html#afc6cc734ad843aca30a7cb76ad6dedb9',1,'BNO08xTestHelper']]], - ['activity_5fconfidences_11',['activity_confidences',['../class_b_n_o08x.html#af96e8cd070459f945ffbf01b98106e13',1,'BNO08x']]], - ['adding_20tests_12',['Adding Tests',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md10',1,'']]], - ['adding_20to_20project_13',['Adding to Project',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md3',1,'']]], - ['all_14',['ALL',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d',1,'BNO08x_global_types.hpp']]], - ['angular_5fvelocity_5fq1_15',['ANGULAR_VELOCITY_Q1',['../class_b_n_o08x.html#aafe117561fe9138800073a04a778b4ce',1,'BNO08x']]] -]; diff --git a/documentation/html/search/all_1.js b/documentation/html/search/all_1.js deleted file mode 100644 index 954b096..0000000 --- a/documentation/html/search/all_1.js +++ /dev/null @@ -1,28 +0,0 @@ -var searchData= -[ - ['back_20function_20example_0',['Call-Back Function Example',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md7',1,'']]], - ['bno08x_1',['BNO08x',['../class_b_n_o08x.html',1,'BNO08x'],['../class_b_n_o08x.html#ad12fb6cf310ad7a04a4e53809833bd61',1,'BNO08x::BNO08x()']]], - ['bno08x_2ecpp_2',['BNO08x.cpp',['../_b_n_o08x_8cpp.html',1,'']]], - ['bno08x_2ehpp_3',['BNO08x.hpp',['../_b_n_o08x_8hpp.html',1,'']]], - ['bno08x_5fconfig_5ft_4',['bno08x_config_t',['../structbno08x__config__t.html',1,'bno08x_config_t'],['../structbno08x__config__t.html#a68e051212415a62e64c23678e7b40552',1,'bno08x_config_t::bno08x_config_t(bool install_isr_service=true)'],['../structbno08x__config__t.html#a3a4ef8ef437403592278110a73cafe70',1,'bno08x_config_t::bno08x_config_t(spi_host_device_t spi_peripheral, gpio_num_t io_mosi, gpio_num_t io_miso, gpio_num_t io_sclk, gpio_num_t io_cs, gpio_num_t io_int, gpio_num_t io_rst, gpio_num_t io_wake, uint32_t sclk_speed, bool install_isr_service=true)'],['../_b_n_o08x__global__types_8hpp.html#a648bbdbf22731476890dd8da977d7503',1,'bno08x_config_t: BNO08x_global_types.hpp']]], - ['bno08x_5fglobal_5ftypes_2ehpp_5',['BNO08x_global_types.hpp',['../_b_n_o08x__global__types_8hpp.html',1,'']]], - ['bno08x_5finit_5fstatus_5ft_6',['bno08x_init_status_t',['../struct_b_n_o08x_1_1bno08x__init__status__t.html',1,'BNO08x::bno08x_init_status_t'],['../class_b_n_o08x.html#a200dfd32391bcaff73e8498674c7ec87',1,'BNO08x::bno08x_init_status_t'],['../struct_b_n_o08x_1_1bno08x__init__status__t.html#a26db0bb1cf4ad4272a363c9995cc6851',1,'BNO08x::bno08x_init_status_t::bno08x_init_status_t()']]], - ['bno08x_5fmacros_2ehpp_7',['BNO08x_macros.hpp',['../_b_n_o08x__macros_8hpp.html',1,'']]], - ['bno08x_5freport_5fperiod_5ftracker_5ft_8',['bno08x_report_period_tracker_t',['../struct_b_n_o08x_1_1bno08x__report__period__tracker__t.html',1,'BNO08x::bno08x_report_period_tracker_t'],['../class_b_n_o08x.html#ae87c0e3c6eb34e209855d8e5d48c624b',1,'BNO08x::bno08x_report_period_tracker_t']]], - ['bno08x_5frx_5fpacket_5ft_9',['bno08x_rx_packet_t',['../struct_b_n_o08x_1_1bno08x__rx__packet__t.html',1,'BNO08x::bno08x_rx_packet_t'],['../class_b_n_o08x.html#a407711b4a84223a52cc043a152aea8ba',1,'BNO08x::bno08x_rx_packet_t']]], - ['bno08x_5ftx_5fpacket_5ft_10',['bno08x_tx_packet_t',['../struct_b_n_o08x_1_1bno08x__tx__packet__t.html',1,'BNO08x::bno08x_tx_packet_t'],['../class_b_n_o08x.html#a3a1a869ac69e6ee850bd2a7f90dd8945',1,'BNO08x::bno08x_tx_packet_t']]], - ['bno08xaccuracy_11',['BNO08xAccuracy',['../_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0',1,'BNO08x_global_types.hpp']]], - ['bno08xaccuracy_5fto_5fstr_12',['BNO08xAccuracy_to_str',['../class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3',1,'BNO08xTestHelper']]], - ['bno08xactivity_13',['BNO08xActivity',['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187',1,'BNO08x_global_types.hpp']]], - ['bno08xactivity_5fto_5fstr_14',['BNO08xActivity_to_str',['../class_b_n_o08x_test_helper.html#ac95ba2892d54e6219123ad3ca0104750',1,'BNO08xTestHelper']]], - ['bno08xactivityenable_15',['BNO08xActivityEnable',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0f',1,'BNO08x_global_types.hpp']]], - ['bno08xresetreason_16',['BNO08xResetReason',['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147',1,'BNO08x_global_types.hpp']]], - ['bno08xstability_17',['BNO08xStability',['../_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5',1,'BNO08x_global_types.hpp']]], - ['bno08xstability_5fto_5fstr_18',['BNO08xStability_to_str',['../class_b_n_o08x_test_helper.html#ae922f36719ab085550ef270d5a149059',1,'BNO08xTestHelper']]], - ['bno08xtesthelper_19',['BNO08xTestHelper',['../class_b_n_o08x_test_helper.html',1,'BNO08xTestHelper'],['../class_b_n_o08x.html#a190775b71c35d8007faae7dd6a9f1030',1,'BNO08x::BNO08xTestHelper']]], - ['bno08xtesthelper_2ehpp_20',['BNO08xTestHelper.hpp',['../_b_n_o08x_test_helper_8hpp.html',1,'']]], - ['bno08xtestsuite_21',['BNO08xTestSuite',['../class_b_n_o08x_test_suite.html',1,'']]], - ['bno08xtestsuite_2ehpp_22',['BNO08xTestSuite.hpp',['../_b_n_o08x_test_suite_8hpp.html',1,'']]], - ['body_23',['body',['../struct_b_n_o08x_1_1bno08x__rx__packet__t.html#ab422d75e1fcd776ef412f4d623cc293e',1,'BNO08x::bno08x_rx_packet_t::body'],['../struct_b_n_o08x_1_1bno08x__tx__packet__t.html#a4478c6cd9e87907eacc56dd06ad4a69d',1,'BNO08x::bno08x_tx_packet_t::body']]], - ['bus_5fconfig_24',['bus_config',['../class_b_n_o08x.html#a982f065df42f00e53fd87c840efdb0f1',1,'BNO08x']]] -]; diff --git a/documentation/html/search/all_10.js b/documentation/html/search/all_10.js deleted file mode 100644 index 3350a5a..0000000 --- a/documentation/html/search/all_10.js +++ /dev/null @@ -1,57 +0,0 @@ -var searchData= -[ - ['raw_5faccel_5fx_0',['raw_accel_X',['../class_b_n_o08x.html#a75fb2f06c5bbe26e3f3c794934ef954c',1,'BNO08x']]], - ['raw_5faccel_5fy_1',['raw_accel_Y',['../class_b_n_o08x.html#ab56e2ba505fa293d03e955137625c562',1,'BNO08x']]], - ['raw_5faccel_5fz_2',['raw_accel_Z',['../class_b_n_o08x.html#af254d245b368027df6952b7d7522bd35',1,'BNO08x']]], - ['raw_5fbias_5fx_3',['raw_bias_X',['../class_b_n_o08x.html#a8a2667f668317cee0a9fc4ef0accc3f5',1,'BNO08x']]], - ['raw_5fbias_5fy_4',['raw_bias_Y',['../class_b_n_o08x.html#ac38ff5eb93d3c3db0af2504ba02fd93c',1,'BNO08x']]], - ['raw_5fbias_5fz_5',['raw_bias_Z',['../class_b_n_o08x.html#a0968eaed9b3d979a2caa1aba6e6b417a',1,'BNO08x']]], - ['raw_5fcalib_5fgyro_5fx_6',['raw_calib_gyro_X',['../class_b_n_o08x.html#a87faca2c8c71ff46bf2e6ad4ba271b3a',1,'BNO08x']]], - ['raw_5fcalib_5fgyro_5fy_7',['raw_calib_gyro_Y',['../class_b_n_o08x.html#a66c48af1d4162a9ec25c3a1c95660fe4',1,'BNO08x']]], - ['raw_5fcalib_5fgyro_5fz_8',['raw_calib_gyro_Z',['../class_b_n_o08x.html#af5450d1a9c20c2a5c62c960e3df11c0e',1,'BNO08x']]], - ['raw_5flin_5faccel_5fx_9',['raw_lin_accel_X',['../class_b_n_o08x.html#ae1f71a432cb15e75f522fa18f29f4d50',1,'BNO08x']]], - ['raw_5flin_5faccel_5fy_10',['raw_lin_accel_Y',['../class_b_n_o08x.html#aff3a5590471d1c9fc485a5610433915f',1,'BNO08x']]], - ['raw_5flin_5faccel_5fz_11',['raw_lin_accel_Z',['../class_b_n_o08x.html#abc8add47f1babc66c812a015614143d3',1,'BNO08x']]], - ['raw_5fmagf_5fx_12',['raw_magf_X',['../class_b_n_o08x.html#aa5bdf740161b7c37adcac0154a410118',1,'BNO08x']]], - ['raw_5fmagf_5fy_13',['raw_magf_Y',['../class_b_n_o08x.html#acd365418f24a6da61122c66d82086639',1,'BNO08x']]], - ['raw_5fmagf_5fz_14',['raw_magf_Z',['../class_b_n_o08x.html#ab4862de31d0874b44b6745678e1c905e',1,'BNO08x']]], - ['raw_5fmems_5fgyro_5fx_15',['raw_mems_gyro_x',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a94befe7132d3a6a6ce2a7890e96ec091',1,'BNO08xTestHelper::imu_report_data_t']]], - ['raw_5fmems_5fgyro_5fy_16',['raw_mems_gyro_y',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e9cd7e43d70932c5f84e3cfadf8bb47',1,'BNO08xTestHelper::imu_report_data_t']]], - ['raw_5fmems_5fgyro_5fz_17',['raw_mems_gyro_z',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a9df84179bd44a7febfa1058afe3dad6c',1,'BNO08xTestHelper::imu_report_data_t']]], - ['raw_5fquat_5fi_18',['raw_quat_I',['../class_b_n_o08x.html#a69dc7e97875060213085ba964b3bd987',1,'BNO08x']]], - ['raw_5fquat_5fj_19',['raw_quat_J',['../class_b_n_o08x.html#a61ae05dc5572b326541bf8099f0c2a54',1,'BNO08x']]], - ['raw_5fquat_5fk_20',['raw_quat_K',['../class_b_n_o08x.html#a7720c44ed1c0f1a0663d2adc5e1a1ea1',1,'BNO08x']]], - ['raw_5fquat_5fradian_5faccuracy_21',['raw_quat_radian_accuracy',['../class_b_n_o08x.html#a033d6cb1aa137743b69cc3e401df67b7',1,'BNO08x']]], - ['raw_5fquat_5freal_22',['raw_quat_real',['../class_b_n_o08x.html#a867354267253ae828be4fae15c062db3',1,'BNO08x']]], - ['raw_5funcalib_5fgyro_5fx_23',['raw_uncalib_gyro_X',['../class_b_n_o08x.html#afdc5cdb65bd0b36528b5b671b9d27053',1,'BNO08x']]], - ['raw_5funcalib_5fgyro_5fy_24',['raw_uncalib_gyro_Y',['../class_b_n_o08x.html#acc2c66e2985975266a286385ea855117',1,'BNO08x']]], - ['raw_5funcalib_5fgyro_5fz_25',['raw_uncalib_gyro_Z',['../class_b_n_o08x.html#afac9dd4161f4c0051255293680c9082b',1,'BNO08x']]], - ['readme_26',['README',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html',1,'']]], - ['readme_2emd_27',['README.md',['../_r_e_a_d_m_e_8md.html',1,'']]], - ['receive_5fpacket_28',['receive_packet',['../class_b_n_o08x.html#a8d9f28d8857279a3c4b1f62f6dabb638',1,'BNO08x']]], - ['receive_5fpacket_5fbody_29',['receive_packet_body',['../class_b_n_o08x.html#a9ee7e73f695af8965a9ede50136d5a8c',1,'BNO08x']]], - ['receive_5fpacket_5fheader_30',['receive_packet_header',['../class_b_n_o08x.html#acb246769719351e02bf2aff06d039475',1,'BNO08x']]], - ['register_5fcb_31',['register_cb',['../class_b_n_o08x.html#a06bb0c70305421b5357e64f31579fdc7',1,'BNO08x::register_cb()'],['../_callback_tests_8cpp.html#a6df8508e34beaeb28f34554ce0e20573',1,'register_cb([&imu, &new_data, &report_data, &prev_report_data, &msg_buff]() { static int cb_execution_cnt=0;cb_execution_cnt++;BNO08xTestHelper::update_report_data(&report_data);if(BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) { new_data=true;sprintf(msg_buff, "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " "%.2lf Accuracy %s", cb_execution_cnt, report_data.accel_x, report_data.accel_y, report_data.accel_z, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy));BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff);} }): CallbackTests.cpp'],['../_callback_tests_8cpp.html#a8dba989b01b464871f3232223050ec73',1,'register_cb([&imu, &new_data, &report_data, &prev_report_data, &msg_buff]() { static int cb_execution_cnt=0;cb_execution_cnt++;BNO08xTestHelper::update_report_data(&report_data);if(BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) { new_data[0]=true;sprintf(msg_buff, "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " "%.2lf Accuracy %s", cb_execution_cnt, report_data.accel_x, report_data.accel_y, report_data.accel_z, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy));BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff);} if(BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) { new_data[1]=true;sprintf(msg_buff, "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " "%.2lf Accuracy: %s",(cb_execution_cnt+1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy));BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff);} }): CallbackTests.cpp']]], - ['report_5fcnt_32',['REPORT_CNT',['../class_b_n_o08x.html#a9658c821658ab51fe6831a83d8903a53',1,'BNO08x']]], - ['report_5fdata_33',['report_data',['../_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9',1,'CallbackTests.cpp']]], - ['report_5fid_34',['report_ID',['../struct_b_n_o08x_1_1bno08x__report__period__tracker__t.html#a05dd1697e0b5fda59d112af2c396295c',1,'BNO08x::bno08x_report_period_tracker_t']]], - ['report_5fid_5fto_5freport_5fperiod_5ftracker_5fidx_35',['report_ID_to_report_period_tracker_idx',['../class_b_n_o08x.html#a27b5317d11a5b81028b87a73b7024bfa',1,'BNO08x']]], - ['report_5fperiod_36',['REPORT_PERIOD',['../_callback_tests_8cpp.html#a4b80e39a1f48d801615a1f7baa210071',1,'REPORT_PERIOD: CallbackTests.cpp'],['../_single_report_tests_8cpp.html#a4b80e39a1f48d801615a1f7baa210071',1,'REPORT_PERIOD: SingleReportTests.cpp']]], - ['report_5fperiod_5ftrackers_37',['report_period_trackers',['../class_b_n_o08x.html#ae3750acb4578ccdd7fcf20abcd8e0904',1,'BNO08x']]], - ['request_5fcalibration_5fstatus_38',['request_calibration_status',['../class_b_n_o08x.html#affaaa35abbb872da5299ebab6e2c9b11',1,'BNO08x']]], - ['reset_5fall_5fdata_5fto_5fdefaults_39',['reset_all_data_to_defaults',['../class_b_n_o08x.html#a453ec8a70646651d4e5b10bf0b2e4d61',1,'BNO08x']]], - ['reset_5fall_5fimu_5fdata_5fto_5ftest_5fdefaults_40',['reset_all_imu_data_to_test_defaults',['../class_b_n_o08x_test_helper.html#ade6be1fd8ef3a99e0edae4cbf25eb528',1,'BNO08xTestHelper']]], - ['rotation_5fvector_5faccuracy_5fq1_41',['ROTATION_VECTOR_ACCURACY_Q1',['../class_b_n_o08x.html#a923d65d8568cc31873ad56a3908e1939',1,'BNO08x']]], - ['rotation_5fvector_5fdata_5fis_5fnew_42',['rotation_vector_data_is_new',['../class_b_n_o08x_test_helper.html#aeb8cd985faf8e403f62b60fced9cb2fd',1,'BNO08xTestHelper']]], - ['rotation_5fvector_5fq1_43',['ROTATION_VECTOR_Q1',['../class_b_n_o08x.html#a0b19c8f2de2b2bfe033da7f93cdd2608',1,'BNO08x']]], - ['run_5fall_5ftests_44',['run_all_tests',['../class_b_n_o08x_test_suite.html#ac12545fe311a98e9c0ae6fea77da95fd',1,'BNO08xTestSuite']]], - ['run_5fcallback_5ftests_45',['run_callback_tests',['../class_b_n_o08x_test_suite.html#a8e294955bf512e2e88c086f04f6030a8',1,'BNO08xTestSuite']]], - ['run_5ffull_5fcalibration_5froutine_46',['run_full_calibration_routine',['../class_b_n_o08x.html#ae6e875a27ae74ebed806ee1a4576845a',1,'BNO08x']]], - ['run_5finit_5fdeinit_5ftests_47',['run_init_deinit_tests',['../class_b_n_o08x_test_suite.html#a53de9b0fe1b28c18e3a1ca4c68a06f16',1,'BNO08xTestSuite']]], - ['run_5fmulti_5freport_5ftests_48',['run_multi_report_tests',['../class_b_n_o08x_test_suite.html#a916cff374791381de61f1035f9935ac5',1,'BNO08xTestSuite']]], - ['run_5fsingle_5freport_5ftests_49',['run_single_report_tests',['../class_b_n_o08x_test_suite.html#a37899d7bf67fce5c3dd77dd5647f8ecb',1,'BNO08xTestSuite']]], - ['running_50',['RUNNING',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd',1,'RUNNING: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd',1,'RUNNING: BNO08x_global_types.hpp']]], - ['running_20tests_51',['Running Tests',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md9',1,'']]], - ['rx_5fdata_5flength_52',['RX_DATA_LENGTH',['../class_b_n_o08x.html#a1a037bda37493cde56732cc6fdc7884b',1,'BNO08x']]], - ['rx_5freport_5ftrial_5fcnt_53',['RX_REPORT_TRIAL_CNT',['../_callback_tests_8cpp.html#a20cd776c25ed6d39b2dcb95d155cfbda',1,'RX_REPORT_TRIAL_CNT: CallbackTests.cpp'],['../_single_report_tests_8cpp.html#a20cd776c25ed6d39b2dcb95d155cfbda',1,'RX_REPORT_TRIAL_CNT: SingleReportTests.cpp']]] -]; diff --git a/documentation/html/search/all_11.js b/documentation/html/search/all_11.js deleted file mode 100644 index eec76c4..0000000 --- a/documentation/html/search/all_11.js +++ /dev/null @@ -1,55 +0,0 @@ -var searchData= -[ - ['save_5fcalibration_0',['save_calibration',['../class_b_n_o08x.html#aa16609de88bfb7b389348859aa0cee54',1,'BNO08x']]], - ['save_5ftare_1',['save_tare',['../class_b_n_o08x.html#afb2ffc4e7ff0498917bc14a83af306e2',1,'BNO08x']]], - ['sclk_5fmax_5fspeed_2',['SCLK_MAX_SPEED',['../class_b_n_o08x.html#a031976dacd97917d9d72edccb607160c',1,'BNO08x']]], - ['sclk_5fspeed_3',['sclk_speed',['../structbno08x__config__t.html#a231614c3b20888360def2ce9db83f52a',1,'bno08x_config_t']]], - ['sem_5fkill_5ftasks_4',['sem_kill_tasks',['../class_b_n_o08x.html#aa92ff86d82a097a565ed2a2b9000b571',1,'BNO08x']]], - ['send_5fpacket_5',['send_packet',['../class_b_n_o08x.html#a2c359a44a2c8e83ecb258a340e2d0e1a',1,'BNO08x']]], - ['sensor_5freport_5fid_5faccelerometer_6',['SENSOR_REPORT_ID_ACCELEROMETER',['../class_b_n_o08x.html#a354eaff2218eb382a1851537a75badcc',1,'BNO08x']]], - ['sensor_5freport_5fid_5farvr_5fstabilized_5fgame_5frotation_5fvector_7',['SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR',['../class_b_n_o08x.html#aeb51ebb6c82158cd7e23bd682c08c4e0',1,'BNO08x']]], - ['sensor_5freport_5fid_5farvr_5fstabilized_5frotation_5fvector_8',['SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR',['../class_b_n_o08x.html#a8d4b91149cfc1a3cd615f60a4ad2275e',1,'BNO08x']]], - ['sensor_5freport_5fid_5fgame_5frotation_5fvector_9',['SENSOR_REPORT_ID_GAME_ROTATION_VECTOR',['../class_b_n_o08x.html#ada7dbda9f7a0bfb0894a787ce0ff9cef',1,'BNO08x']]], - ['sensor_5freport_5fid_5fgeomagnetic_5frotation_5fvector_10',['SENSOR_REPORT_ID_GEOMAGNETIC_ROTATION_VECTOR',['../class_b_n_o08x.html#abb6d0586a5a87b7b34f4c65ae52965a4',1,'BNO08x']]], - ['sensor_5freport_5fid_5fgravity_11',['SENSOR_REPORT_ID_GRAVITY',['../class_b_n_o08x.html#a6730acb92053d44decb690a7b7234032',1,'BNO08x']]], - ['sensor_5freport_5fid_5fgyro_5fintegrated_5frotation_5fvector_12',['SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR',['../class_b_n_o08x.html#acd0fc6ffa70dd2761cba0ac0b88c234f',1,'BNO08x']]], - ['sensor_5freport_5fid_5fgyroscope_13',['SENSOR_REPORT_ID_GYROSCOPE',['../class_b_n_o08x.html#a224fb8f833806dd530c5f16e7ab5bc7a',1,'BNO08x']]], - ['sensor_5freport_5fid_5flinear_5facceleration_14',['SENSOR_REPORT_ID_LINEAR_ACCELERATION',['../class_b_n_o08x.html#ace7720a02c9f4ef38e319849f6c36a0b',1,'BNO08x']]], - ['sensor_5freport_5fid_5fmagnetic_5ffield_15',['SENSOR_REPORT_ID_MAGNETIC_FIELD',['../class_b_n_o08x.html#a06058a84d6604054aa66ee008ac64aa9',1,'BNO08x']]], - ['sensor_5freport_5fid_5fpersonal_5factivity_5fclassifier_16',['SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER',['../class_b_n_o08x.html#a7274f6d3bda04da0bb304386b4e8d603',1,'BNO08x']]], - ['sensor_5freport_5fid_5fraw_5faccelerometer_17',['SENSOR_REPORT_ID_RAW_ACCELEROMETER',['../class_b_n_o08x.html#a80ea70c4787dea6c3eabb48f583f1916',1,'BNO08x']]], - ['sensor_5freport_5fid_5fraw_5fgyroscope_18',['SENSOR_REPORT_ID_RAW_GYROSCOPE',['../class_b_n_o08x.html#a03b3000424e6d966b80655443ec546bc',1,'BNO08x']]], - ['sensor_5freport_5fid_5fraw_5fmagnetometer_19',['SENSOR_REPORT_ID_RAW_MAGNETOMETER',['../class_b_n_o08x.html#a9e9a7578b7584e7eb2ad562b29565fa7',1,'BNO08x']]], - ['sensor_5freport_5fid_5frotation_5fvector_20',['SENSOR_REPORT_ID_ROTATION_VECTOR',['../class_b_n_o08x.html#a37c91f995c385556486df5fbbce8a3d5',1,'BNO08x']]], - ['sensor_5freport_5fid_5fstability_5fclassifier_21',['SENSOR_REPORT_ID_STABILITY_CLASSIFIER',['../class_b_n_o08x.html#ab5c29f31714b4755c0edbce7156652f7',1,'BNO08x']]], - ['sensor_5freport_5fid_5fstep_5fcounter_22',['SENSOR_REPORT_ID_STEP_COUNTER',['../class_b_n_o08x.html#a2a10161bb564067a07f3fcf4021e00bb',1,'BNO08x']]], - ['sensor_5freport_5fid_5ftap_5fdetector_23',['SENSOR_REPORT_ID_TAP_DETECTOR',['../class_b_n_o08x.html#a8114460c50e84b0ac750293ab72868c8',1,'BNO08x']]], - ['sensor_5freport_5fid_5funcalibrated_5fgyro_24',['SENSOR_REPORT_ID_UNCALIBRATED_GYRO',['../class_b_n_o08x.html#acb8e83fbb0645d4e98a96120ce9f431c',1,'BNO08x']]], - ['set_5ftest_5fimu_5fcfg_25',['set_test_imu_cfg',['../class_b_n_o08x_test_helper.html#a9e2f9bf13f28f1a6ba87e86bc5947cf1',1,'BNO08xTestHelper']]], - ['shtp_5freport_5fbase_5ftimestamp_26',['SHTP_REPORT_BASE_TIMESTAMP',['../class_b_n_o08x.html#ae37d6f8431c8c465bfb0c662772b5cb9',1,'BNO08x']]], - ['shtp_5freport_5fcommand_5frequest_27',['SHTP_REPORT_COMMAND_REQUEST',['../class_b_n_o08x.html#ab04695dd189412092254e52bd6e5a75a',1,'BNO08x']]], - ['shtp_5freport_5fcommand_5fresponse_28',['SHTP_REPORT_COMMAND_RESPONSE',['../class_b_n_o08x.html#a1e5b64caa514b7e4fe64ab214758b875',1,'BNO08x']]], - ['shtp_5freport_5ffrs_5fread_5frequest_29',['SHTP_REPORT_FRS_READ_REQUEST',['../class_b_n_o08x.html#a74af7eacc35cc825940b647c2de0d368',1,'BNO08x']]], - ['shtp_5freport_5ffrs_5fread_5fresponse_30',['SHTP_REPORT_FRS_READ_RESPONSE',['../class_b_n_o08x.html#aeb760b095dcf808a413ef696f2608e43',1,'BNO08x']]], - ['shtp_5freport_5fget_5ffeature_5fresponse_31',['SHTP_REPORT_GET_FEATURE_RESPONSE',['../class_b_n_o08x.html#ad09312802cf5b8b5115362c86b53858b',1,'BNO08x']]], - ['shtp_5freport_5fproduct_5fid_5frequest_32',['SHTP_REPORT_PRODUCT_ID_REQUEST',['../class_b_n_o08x.html#a542405639c28bd56bc4361b922763c95',1,'BNO08x']]], - ['shtp_5freport_5fproduct_5fid_5fresponse_33',['SHTP_REPORT_PRODUCT_ID_RESPONSE',['../class_b_n_o08x.html#a0177134162e116501bc9483c6e4b76c3',1,'BNO08x']]], - ['shtp_5freport_5fset_5ffeature_5fcommand_34',['SHTP_REPORT_SET_FEATURE_COMMAND',['../class_b_n_o08x.html#a1d3bff4e20c2c3d47db322c9e34ef338',1,'BNO08x']]], - ['singlereporttests_2ecpp_35',['SingleReportTests.cpp',['../_single_report_tests_8cpp.html',1,'']]], - ['soft_5freset_36',['soft_reset',['../class_b_n_o08x.html#a973a1b1785f3302ee1b2702c6a27646e',1,'BNO08x']]], - ['spi_5fbus_37',['spi_bus',['../struct_b_n_o08x_1_1bno08x__init__status__t.html#a9855844dee2cd51e734693294d5cc438',1,'BNO08x::bno08x_init_status_t']]], - ['spi_5fdevice_38',['spi_device',['../struct_b_n_o08x_1_1bno08x__init__status__t.html#aa7c583b48551710dd4f71bb5a72c029a',1,'BNO08x::bno08x_init_status_t']]], - ['spi_5fhdl_39',['spi_hdl',['../class_b_n_o08x.html#acc0ea091465fc9a5736f5e0c6a0ce8ef',1,'BNO08x']]], - ['spi_5fperipheral_40',['spi_peripheral',['../structbno08x__config__t.html#a020d2343750bb7debc2a108ae038c9ec',1,'bno08x_config_t']]], - ['spi_5ftask_41',['spi_task',['../struct_b_n_o08x_1_1bno08x__init__status__t.html#a92f78cc3fd3161bbc1fcad08b9c6bcb5',1,'BNO08x::bno08x_init_status_t::spi_task'],['../class_b_n_o08x.html#a2ecd4ed60f82730ae230c61687ec92bf',1,'BNO08x::spi_task()']]], - ['spi_5ftask_5fhdl_42',['spi_task_hdl',['../class_b_n_o08x.html#a615090aae15f1b0410a7e5ecb94957b5',1,'BNO08x']]], - ['spi_5ftask_5ftrampoline_43',['spi_task_trampoline',['../class_b_n_o08x.html#a0ce6d9db873555f1ebe7e095251eab74',1,'BNO08x']]], - ['spi_5ftransaction_44',['spi_transaction',['../class_b_n_o08x.html#ac16adc5f00b0039c98a4921f13895026',1,'BNO08x']]], - ['stability_5fclassifier_45',['stability_classifier',['../class_b_n_o08x.html#a1b12471e92536a79d0c425d77676f2e1',1,'BNO08x::stability_classifier'],['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a86473c2bd8cbe2c76276393ee20d568b',1,'BNO08xTestHelper::imu_report_data_t::stability_classifier']]], - ['stability_5fclassifier_5fdata_5fis_5fnew_46',['stability_classifier_data_is_new',['../class_b_n_o08x_test_helper.html#a95ed21657224358877a66d010eeefad3',1,'BNO08xTestHelper']]], - ['started_47',['Getting Started',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md1',1,'']]], - ['stationary_48',['STATIONARY',['../_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146',1,'BNO08x_global_types.hpp']]], - ['step_5fcount_49',['step_count',['../class_b_n_o08x.html#ad80a77973371b12d722ea39063c648be',1,'BNO08x::step_count'],['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae8435a931eac7f4376a94acfcbf6a784',1,'BNO08xTestHelper::imu_report_data_t::step_count']]], - ['step_5fcounter_5fdata_5fis_5fnew_50',['step_counter_data_is_new',['../class_b_n_o08x_test_helper.html#aa7eb152d4192c3949bb3443ef6221782',1,'BNO08xTestHelper']]], - ['still_51',['STILL',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6',1,'STILL: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6',1,'STILL: BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/all_12.js b/documentation/html/search/all_12.js deleted file mode 100644 index b3cced1..0000000 --- a/documentation/html/search/all_12.js +++ /dev/null @@ -1,26 +0,0 @@ -var searchData= -[ - ['tag_0',['TAG',['../class_b_n_o08x.html#a2c98d5f2c406a3efd0b48c5666fa8c46',1,'BNO08x::TAG'],['../class_b_n_o08x_test_helper.html#aa09d388a5da3a925ac25125b9c5c3a90',1,'BNO08xTestHelper::TAG']]], - ['tap_5fdetector_1',['tap_detector',['../class_b_n_o08x.html#a1171a5738a4e6831ec7fa32a29f15554',1,'BNO08x']]], - ['tare_5farvr_5fstabilized_5fgame_5frotation_5fvector_2',['TARE_ARVR_STABILIZED_GAME_ROTATION_VECTOR',['../class_b_n_o08x.html#a68aaaab144adbe5af00597408f044d9d',1,'BNO08x']]], - ['tare_5farvr_5fstabilized_5frotation_5fvector_3',['TARE_ARVR_STABILIZED_ROTATION_VECTOR',['../class_b_n_o08x.html#abff9abe904bcdde951cf88c378284b45',1,'BNO08x']]], - ['tare_5faxis_5fall_4',['TARE_AXIS_ALL',['../class_b_n_o08x.html#a1ef13f6f330810934416ad5fe0ee55b2',1,'BNO08x']]], - ['tare_5faxis_5fz_5',['TARE_AXIS_Z',['../class_b_n_o08x.html#aecb3e11c1ca5769fd60f42c17a105731',1,'BNO08x']]], - ['tare_5fgame_5frotation_5fvector_6',['TARE_GAME_ROTATION_VECTOR',['../class_b_n_o08x.html#abaf1ec8bb197db1998a9ed3cec6180d5',1,'BNO08x']]], - ['tare_5fgeomagnetic_5frotation_5fvector_7',['TARE_GEOMAGNETIC_ROTATION_VECTOR',['../class_b_n_o08x.html#a225397a04d849e5647992ca80d68febb',1,'BNO08x']]], - ['tare_5fgyro_5fintegrated_5frotation_5fvector_8',['TARE_GYRO_INTEGRATED_ROTATION_VECTOR',['../class_b_n_o08x.html#a9ec354d75249f06f13599abf7bedfde0',1,'BNO08x']]], - ['tare_5fnow_9',['TARE_NOW',['../class_b_n_o08x.html#a27df630f3e52b35552d2c1f2cf3496b0',1,'BNO08x']]], - ['tare_5fnow_10',['tare_now',['../class_b_n_o08x.html#a4549bbef48208bd9c745fc755b93012f',1,'BNO08x']]], - ['tare_5fpersist_11',['TARE_PERSIST',['../class_b_n_o08x.html#a115aef7b38ec0dec2085f6917d832912',1,'BNO08x']]], - ['tare_5frotation_5fvector_12',['TARE_ROTATION_VECTOR',['../class_b_n_o08x.html#a8e2cfc25d0e34ae53a762b88cc3ac3c8',1,'BNO08x']]], - ['tare_5fset_5freorientation_13',['TARE_SET_REORIENTATION',['../class_b_n_o08x.html#a59cde7dd301c94a20b84735c5d49008e',1,'BNO08x']]], - ['task_5fcnt_14',['TASK_CNT',['../class_b_n_o08x.html#a5448bffec9a90f5c388b3c22928463ae',1,'BNO08x']]], - ['task_5fcount_15',['task_count',['../struct_b_n_o08x_1_1bno08x__init__status__t.html#a6b2d0002d0e817d6384a1064453eb84d',1,'BNO08x::bno08x_init_status_t']]], - ['test_5fassert_5fequal_16',['TEST_ASSERT_EQUAL',['../_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3',1,'TEST_ASSERT_EQUAL(true, new_data[0]): CallbackTests.cpp'],['../_callback_tests_8cpp.html#aa6754207db4cfba956441680c7a6a97d',1,'TEST_ASSERT_EQUAL(true, new_data[1]): CallbackTests.cpp']]], - ['test_5fcase_17',['TEST_CASE',['../_callback_tests_8cpp.html#ac18b9cb122499f587331d82a538f23aa',1,'TEST_CASE("BNO08x Driver Creation for [CallbackTests] Tests", "[CallbackTests]"): CallbackTests.cpp'],['../_callback_tests_8cpp.html#a574f179a8295301510bc8b5475f02ba8',1,'TEST_CASE("BNO08x Driver Cleanup for [CallbackTests] Tests", "[CallbackTests]"): CallbackTests.cpp'],['../_init_deinit_tests_8cpp.html#a6ed5310154fb7e7f290e619e6fbed708',1,'TEST_CASE("Init Config Args", "[InitComprehensive]"): InitDeinitTests.cpp'],['../_init_deinit_tests_8cpp.html#a96d79e5c8f3096a207d806be926af15b',1,'TEST_CASE("Init GPIO", "[InitComprehensive]"): InitDeinitTests.cpp'],['../_init_deinit_tests_8cpp.html#ab8015ecd4179bc39223921d6eef1165a',1,'TEST_CASE("Init HINT ISR", "[InitComprehensive]"): InitDeinitTests.cpp'],['../_init_deinit_tests_8cpp.html#ad71fea7e4a2e587d48d2bf7fadd711cc',1,'TEST_CASE("Init SPI", "[InitComprehensive]"): InitDeinitTests.cpp'],['../_init_deinit_tests_8cpp.html#a9f7d58c894a252a5d5f4926f43c1da05',1,'TEST_CASE("InitComprehensive Tasks", "[InitComprehensive]"): InitDeinitTests.cpp'],['../_init_deinit_tests_8cpp.html#a69680e2934e7ec3c6a1771270dc59f05',1,'TEST_CASE("Finish Init", "[InitComprehensive]"): InitDeinitTests.cpp'],['../_init_deinit_tests_8cpp.html#ac4fb371054271d54830b58cc164dc0f6',1,'TEST_CASE("Init & Deinit", "[InitDenit]"): InitDeinitTests.cpp'],['../_multi_report_tests_8cpp.html#a1fd7b6a0d4dbb7f91fd5691b5b054bda',1,'TEST_CASE("BNO08x Driver Creation for [MultiReportEnableDisable] Tests", "[MultiReportEnableDisable]"): MultiReportTests.cpp'],['../_multi_report_tests_8cpp.html#aa9e0389fa75046b52d13286af2c3b2a7',1,'TEST_CASE("Dual Report Enable/Disable", "[MultiReportEnableDisable]"): MultiReportTests.cpp'],['../_multi_report_tests_8cpp.html#a915d6c272bf95057a8bb22abfb307882',1,'TEST_CASE("Tri Report Enable/Disable", "[MultiReportEnableDisable]"): MultiReportTests.cpp'],['../_multi_report_tests_8cpp.html#a1438f6b8587b635b6096dda2927fa9a1',1,'TEST_CASE("Quad Report Enable/Disable", "[MultiReportEnableDisable]"): MultiReportTests.cpp'],['../_multi_report_tests_8cpp.html#ad96cfd7c30e8693897688ce24bb53996',1,'TEST_CASE("Hex Report Enable", "[MultiReportEnableDisable]"): MultiReportTests.cpp'],['../_multi_report_tests_8cpp.html#ac92ec06fe64f7bedbbe37dee3e64c090',1,'TEST_CASE("BNO08x Driver Cleanup for [MultiReportEnableDisable] Tests", "[MultiReportEnableDisable]"): MultiReportTests.cpp'],['../_single_report_tests_8cpp.html#aac644123799c1f836d379c9789a064ab',1,'TEST_CASE("BNO08x Driver Creation for [SingleReportEnableDisable] Tests", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#af30c5c1549bda77b45a1e6fb5f76844a',1,'TEST_CASE("Enable Incorrect Report", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#ae436161f7f0085f01ce63d9373944ae8',1,'TEST_CASE("Enable/Disable Rotation Vector", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a90980a9fc26b3a692ab2529c9f8e4747',1,'TEST_CASE("Enable/Disable Game Rotation Vector", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#af9d07441bd8651bc21743664b7f99bb8',1,'TEST_CASE("Enable/Disable ARVR Stabilized Rotation Vector", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a35b0417a053d9fbf61a91a2110c3495c',1,'TEST_CASE("Enable/Disable ARVR Stabilized Game Rotation Vector", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a713376354af2a970230882e2a487050e',1,'TEST_CASE("Enable/Disable Gyro Integrated Rotation Vector", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a3cce613b379b768244a176a32b37667c',1,'TEST_CASE("Enable/Disable Uncalibrated Gyro", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#ace1544ccc126d0b9eadd433f9cb41486',1,'TEST_CASE("Enable/Disable Calibrated Gyro", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#aaefa1a1d4b3c190b7f46bb7f42512949',1,'TEST_CASE("Enable/Disable Accelerometer", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#ae4d70e11995e36808b6390b171aba0e8',1,'TEST_CASE("Enable/Disable Linear Accelerometer", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#ab9b4ae43e33572d90c4c889452cd91ee',1,'TEST_CASE("Enable/Disable Gravity", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a429f6e7897a9609ddd093d66b6f7b1ff',1,'TEST_CASE("Enable/Disable Magnetometer", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a9f2e049a5b61721869c5f4757e313502',1,'TEST_CASE("Enable/Disable Step Counter", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#acf249e215fca056266de6e833875925e',1,'TEST_CASE("Enable/Disable Stability Classifier", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a098111e0f361615318674b5b1b05ece4',1,'TEST_CASE("Enable/Disable Activity Classifier", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a697ac897c8756d7553854e52229d36f5',1,'TEST_CASE("BNO08x Driver Cleanup for [SingleReportEnableDisable] Tests", "[SingleReportEnableDisable]"): SingleReportTests.cpp']]], - ['test_5fimu_18',['test_imu',['../class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243',1,'BNO08xTestHelper']]], - ['tests_19',['Tests',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md10',1,'Adding Tests'],['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md9',1,'Running Tests'],['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md8',1,'Unit Tests']]], - ['tilting_20',['TILTING',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c',1,'TILTING: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c',1,'TILTING: BNO08x_global_types.hpp']]], - ['time_5fstamp_21',['time_stamp',['../class_b_n_o08x.html#abc972db20affbd0040b4e6c4892dd57b',1,'BNO08x::time_stamp'],['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae5e8705ad014ed3f70e5de527cb2cb66',1,'BNO08xTestHelper::imu_report_data_t::time_stamp']]], - ['to_20project_22',['Adding to Project',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md3',1,'']]] -]; diff --git a/documentation/html/search/all_13.js b/documentation/html/search/all_13.js deleted file mode 100644 index 395be99..0000000 --- a/documentation/html/search/all_13.js +++ /dev/null @@ -1,35 +0,0 @@ -var searchData= -[ - ['uint16_5fclr_5flsb_0',['UINT16_CLR_LSB',['../_b_n_o08x__macros_8hpp.html#ac89a0ae0c3d3067f02e9fa275521606b',1,'BNO08x_macros.hpp']]], - ['uint16_5fclr_5fmsb_1',['UINT16_CLR_MSB',['../_b_n_o08x__macros_8hpp.html#ad98f2fa811436866ff297a8288e34f40',1,'BNO08x_macros.hpp']]], - ['uint32_5fclr_5fbyte_2',['UINT32_CLR_BYTE',['../_b_n_o08x__macros_8hpp.html#a7de5c0b84ba545981105e1216925d8e9',1,'BNO08x_macros.hpp']]], - ['uint32_5fmsk_5fbyte_3',['UINT32_MSK_BYTE',['../_b_n_o08x__macros_8hpp.html#a6f459cc2cce1722c63d22a9556f06bc8',1,'BNO08x_macros.hpp']]], - ['uncalib_5fgyro_5fdrift_5fx_4',['uncalib_gyro_drift_x',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac70a65027c3e740eca2b1f172b7cefa3',1,'BNO08xTestHelper::imu_report_data_t']]], - ['uncalib_5fgyro_5fdrift_5fy_5',['uncalib_gyro_drift_y',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a29d5ae3e0ed3463cb9297f9cdc0e8472',1,'BNO08xTestHelper::imu_report_data_t']]], - ['uncalib_5fgyro_5fdrift_5fz_6',['uncalib_gyro_drift_z',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a27b52e2d96cb948c4257de4553053f72',1,'BNO08xTestHelper::imu_report_data_t']]], - ['uncalib_5fgyro_5fvel_5fx_7',['uncalib_gyro_vel_x',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a292b1c36fed6a9c9742edf730299c4f4',1,'BNO08xTestHelper::imu_report_data_t']]], - ['uncalib_5fgyro_5fvel_5fy_8',['uncalib_gyro_vel_y',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#adfd6bf2e2264cf25bd02814446600ab4',1,'BNO08xTestHelper::imu_report_data_t']]], - ['uncalib_5fgyro_5fvel_5fz_9',['uncalib_gyro_vel_z',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ab39fd6f409288bb35fb1542ff4b9cbe4',1,'BNO08xTestHelper::imu_report_data_t']]], - ['uncalibrated_5fgyro_5fdata_5fis_5fnew_10',['uncalibrated_gyro_data_is_new',['../class_b_n_o08x_test_helper.html#adb5952b2b96b553024b6a841e30adad2',1,'BNO08xTestHelper']]], - ['undefined_11',['UNDEFINED',['../_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3',1,'UNDEFINED: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a0db45d2a4141101bdfe48e3314cfbca3',1,'UNDEFINED: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3',1,'UNDEFINED: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3',1,'UNDEFINED: BNO08x_global_types.hpp']]], - ['unit_20tests_12',['Unit Tests',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md8',1,'']]], - ['unknown_13',['UNKNOWN',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3',1,'UNKNOWN: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3',1,'UNKNOWN: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3',1,'UNKNOWN: BNO08x_global_types.hpp']]], - ['update_5faccelerometer_5fdata_14',['update_accelerometer_data',['../class_b_n_o08x.html#afe588fbd0055193d3bc08984d7732354',1,'BNO08x']]], - ['update_5fcalibrated_5fgyro_5fdata_15',['update_calibrated_gyro_data',['../class_b_n_o08x.html#a962b695ef4733d558c6f9684da0931ab',1,'BNO08x']]], - ['update_5fcommand_5fdata_16',['update_command_data',['../class_b_n_o08x.html#af971d82426740e62c1f05adcd2c9ce7c',1,'BNO08x']]], - ['update_5fgravity_5fdata_17',['update_gravity_data',['../class_b_n_o08x.html#ad7de3999d4df19038e27c01f9b02010e',1,'BNO08x']]], - ['update_5fintegrated_5fgyro_5frotation_5fvector_5fdata_18',['update_integrated_gyro_rotation_vector_data',['../class_b_n_o08x.html#ab02386f13caa446bab5921c1a71f92ab',1,'BNO08x']]], - ['update_5flin_5faccelerometer_5fdata_19',['update_lin_accelerometer_data',['../class_b_n_o08x.html#a7416d844f6188c8d16f181d6d4431708',1,'BNO08x']]], - ['update_5fmagf_5fdata_20',['update_magf_data',['../class_b_n_o08x.html#a3abf4a199bc7a03ac7447c2781673d88',1,'BNO08x']]], - ['update_5fpersonal_5factivity_5fclassifier_5fdata_21',['update_personal_activity_classifier_data',['../class_b_n_o08x.html#a04489cf9a125495c7cf07c6ba5e9f6c0',1,'BNO08x']]], - ['update_5fraw_5faccelerometer_5fdata_22',['update_raw_accelerometer_data',['../class_b_n_o08x.html#a83fed63c67957ec4338afd43087d6e22',1,'BNO08x']]], - ['update_5fraw_5fgyro_5fdata_23',['update_raw_gyro_data',['../class_b_n_o08x.html#ad0f0fec4e53029b4ba907414a36ac5ea',1,'BNO08x']]], - ['update_5fraw_5fmagf_5fdata_24',['update_raw_magf_data',['../class_b_n_o08x.html#a6ddc9600c53a4248d1affcab36f6f245',1,'BNO08x']]], - ['update_5freport_5fdata_25',['update_report_data',['../class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2',1,'BNO08xTestHelper']]], - ['update_5freport_5fperiod_5ftrackers_26',['update_report_period_trackers',['../class_b_n_o08x.html#a0ec9b1a10bbf25a057273605575f0d64',1,'BNO08x']]], - ['update_5frotation_5fvector_5fdata_27',['update_rotation_vector_data',['../class_b_n_o08x.html#aa309152750686fbf8ebf7d6de1f1254b',1,'BNO08x']]], - ['update_5fstability_5fclassifier_5fdata_28',['update_stability_classifier_data',['../class_b_n_o08x.html#a358316b883928c50dd381f024e6b0645',1,'BNO08x']]], - ['update_5fstep_5fcounter_5fdata_29',['update_step_counter_data',['../class_b_n_o08x.html#aa390bf840246e3233e07f6a424efcb6f',1,'BNO08x']]], - ['update_5ftap_5fdetector_5fdata_30',['update_tap_detector_data',['../class_b_n_o08x.html#ac75b7fb1a1b407d0888ea07d708831b1',1,'BNO08x']]], - ['update_5funcalibrated_5fgyro_5fdata_31',['update_uncalibrated_gyro_data',['../class_b_n_o08x.html#a8de12c9c47549502147bd85dbb7e364e',1,'BNO08x']]] -]; diff --git a/documentation/html/search/all_14.js b/documentation/html/search/all_14.js deleted file mode 100644 index ff7b084..0000000 --- a/documentation/html/search/all_14.js +++ /dev/null @@ -1,9 +0,0 @@ -var searchData= -[ - ['wait_5ffor_5fdata_0',['wait_for_data',['../class_b_n_o08x.html#a4f12de628073f44b2a3fab2688cf1caf',1,'BNO08x']]], - ['wait_5ffor_5frx_5fdone_1',['wait_for_rx_done',['../class_b_n_o08x.html#a2897a178bf2c53cd99df0d4570edf72e',1,'BNO08x']]], - ['wait_5ffor_5ftx_5fdone_2',['wait_for_tx_done',['../class_b_n_o08x.html#a7cdeb849e728487de961cdfd4030c773',1,'BNO08x']]], - ['walking_3',['WALKING',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3',1,'WALKING: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3',1,'WALKING: BNO08x_global_types.hpp']]], - ['wiring_4',['Wiring',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md2',1,'']]], - ['wtd_5',['WTD',['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/all_15.js b/documentation/html/search/all_15.js deleted file mode 100644 index 0c734b6..0000000 --- a/documentation/html/search/all_15.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['_7ebno08x_0',['~BNO08x',['../class_b_n_o08x.html#a687eee44d68e1bcabce04780d7eb5fb9',1,'BNO08x']]] -]; diff --git a/documentation/html/search/all_2.js b/documentation/html/search/all_2.js deleted file mode 100644 index ba612b7..0000000 --- a/documentation/html/search/all_2.js +++ /dev/null @@ -1,50 +0,0 @@ -var searchData= -[ - ['calib_5fgyro_5fvel_5fx_0',['calib_gyro_vel_x',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a89b427579a281440ab94a340c0ec8443',1,'BNO08xTestHelper::imu_report_data_t']]], - ['calib_5fgyro_5fvel_5fy_1',['calib_gyro_vel_y',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af9e11fd749123f5723b2e281c8d2fd16',1,'BNO08xTestHelper::imu_report_data_t']]], - ['calib_5fgyro_5fvel_5fz_2',['calib_gyro_vel_z',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a769ddae74a6c89a2d319c28f95ed6479',1,'BNO08xTestHelper::imu_report_data_t']]], - ['calibrate_5faccel_3',['CALIBRATE_ACCEL',['../class_b_n_o08x.html#acd5b44d705af1f9aaa271a59a9d2d595',1,'BNO08x']]], - ['calibrate_5faccel_5fgyro_5fmag_4',['CALIBRATE_ACCEL_GYRO_MAG',['../class_b_n_o08x.html#af53d9e99f163d97ef92fe989b1dd25cc',1,'BNO08x']]], - ['calibrate_5faccelerometer_5',['calibrate_accelerometer',['../class_b_n_o08x.html#aeffce374f558a167d5b5f19ad627e7cc',1,'BNO08x']]], - ['calibrate_5fall_6',['calibrate_all',['../class_b_n_o08x.html#afd0ca5f9b9741935543d143a5a43d128',1,'BNO08x']]], - ['calibrate_5fgyro_7',['CALIBRATE_GYRO',['../class_b_n_o08x.html#aeac84719a1cc0f9c8d5a9a749391d4db',1,'BNO08x']]], - ['calibrate_5fgyro_8',['calibrate_gyro',['../class_b_n_o08x.html#a9ada90f8ab6dd33fa2d7c168d9234af1',1,'BNO08x']]], - ['calibrate_5fmag_9',['CALIBRATE_MAG',['../class_b_n_o08x.html#ac00e8b59ae8d710cf79956eaafa97ddb',1,'BNO08x']]], - ['calibrate_5fmagnetometer_10',['calibrate_magnetometer',['../class_b_n_o08x.html#ac26350b55095a346d72598ab8aa74b4a',1,'BNO08x']]], - ['calibrate_5fplanar_5faccel_11',['CALIBRATE_PLANAR_ACCEL',['../class_b_n_o08x.html#a955dcb60da150490e17367a871b3a3d2',1,'BNO08x']]], - ['calibrate_5fplanar_5faccelerometer_12',['calibrate_planar_accelerometer',['../class_b_n_o08x.html#a1c6c49c97bc098db89db1aaa37e18f26',1,'BNO08x']]], - ['calibrate_5fstop_13',['CALIBRATE_STOP',['../class_b_n_o08x.html#a584bfa04a39feb93279ee673c340db54',1,'BNO08x']]], - ['calibrated_5fgyro_5fdata_5fis_5fnew_14',['calibrated_gyro_data_is_new',['../class_b_n_o08x_test_helper.html#a084e65ff5c0e2f429b39ebb53b0e03c9',1,'BNO08xTestHelper']]], - ['calibration_5fcomplete_15',['calibration_complete',['../class_b_n_o08x.html#a71ca35f78b98d93d31eb0c187dc8543b',1,'BNO08x']]], - ['calibration_5fstatus_16',['calibration_status',['../class_b_n_o08x.html#ad212b5028a31e857e76d251ced2724e1',1,'BNO08x']]], - ['call_20back_20function_20example_17',['Call-Back Function Example',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md7',1,'']]], - ['call_5finit_5fconfig_5fargs_18',['call_init_config_args',['../class_b_n_o08x_test_helper.html#a71d9fd7d459a98a7e9089a8587a21f8d',1,'BNO08xTestHelper']]], - ['call_5finit_5fgpio_19',['call_init_gpio',['../class_b_n_o08x_test_helper.html#a504749533ccd91890d73440809d38161',1,'BNO08xTestHelper']]], - ['call_5finit_5fhint_5fisr_20',['call_init_hint_isr',['../class_b_n_o08x_test_helper.html#a836c928981ac85d34668c9b97af17a15',1,'BNO08xTestHelper']]], - ['call_5finit_5fspi_21',['call_init_spi',['../class_b_n_o08x_test_helper.html#a7d2d784da1e850dab41154b35d7cdab5',1,'BNO08xTestHelper']]], - ['call_5flaunch_5ftasks_22',['call_launch_tasks',['../class_b_n_o08x_test_helper.html#adf2488d1f7e3dec21a0d0c99417c181a',1,'BNO08xTestHelper']]], - ['callbacktests_2ecpp_23',['CallbackTests.cpp',['../_callback_tests_8cpp.html',1,'']]], - ['cb_5flist_24',['cb_list',['../class_b_n_o08x.html#a6a15e3a64dd71ea61f0448afcce96409',1,'BNO08x']]], - ['channel_5fcommand_25',['CHANNEL_COMMAND',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fad116268ebf7fb5e5cb4795ccc27867ed',1,'BNO08x']]], - ['channel_5fcontrol_26',['CHANNEL_CONTROL',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fa5b5d133bf4a91e14741fdd8e635e897e',1,'BNO08x']]], - ['channel_5fexecutable_27',['CHANNEL_EXECUTABLE',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fab1f28434b161c7ffa7b1a5c5f1a8a95b',1,'BNO08x']]], - ['channel_5fgyro_28',['CHANNEL_GYRO',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fadd3caa696e525dd901de7a8e3dbf0731',1,'BNO08x']]], - ['channel_5freports_29',['CHANNEL_REPORTS',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fabeb0a4983bc57ad2ce9f98360742e03e',1,'BNO08x']]], - ['channel_5fwake_5freports_30',['CHANNEL_WAKE_REPORTS',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638faefb874de7f2f90fb99b42bedf9623d21',1,'BNO08x']]], - ['channels_5ft_31',['channels_t',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638f',1,'BNO08x']]], - ['check_5ftasks_5frunning_32',['CHECK_TASKS_RUNNING',['../_b_n_o08x__macros_8hpp.html#a59dd17f0673fdd60f6a65bba104a6f80',1,'BNO08x_macros.hpp']]], - ['clear_5ftare_33',['clear_tare',['../class_b_n_o08x.html#afe39bfdede7b9a2b273983cb29a27d6e',1,'BNO08x']]], - ['cmd_5fexecution_5fdelay_5fms_34',['CMD_EXECUTION_DELAY_MS',['../class_b_n_o08x.html#a38e31bdb22afdfe05372ffcd5eabfdd2',1,'BNO08x']]], - ['command_5fclear_5fdcd_35',['COMMAND_CLEAR_DCD',['../class_b_n_o08x.html#a4f580b3cb232a762ea7019ee7b04d419',1,'BNO08x']]], - ['command_5fcounter_36',['COMMAND_COUNTER',['../class_b_n_o08x.html#a93dd073c0cc1f3ccfde552649f6ebccc',1,'BNO08x']]], - ['command_5fdcd_37',['COMMAND_DCD',['../class_b_n_o08x.html#af124a6c1d8b871f3181b6c85f1099cb2',1,'BNO08x']]], - ['command_5fdcd_5fperiod_5fsave_38',['COMMAND_DCD_PERIOD_SAVE',['../class_b_n_o08x.html#a7a246989c94cd87f68166b20b7ad4c8b',1,'BNO08x']]], - ['command_5ferrors_39',['COMMAND_ERRORS',['../class_b_n_o08x.html#a384a1efc9857ad938be3bb44f871539b',1,'BNO08x']]], - ['command_5finitialize_40',['COMMAND_INITIALIZE',['../class_b_n_o08x.html#a30eb6d305a187d4d36546841e12176b9',1,'BNO08x']]], - ['command_5fme_5fcalibrate_41',['COMMAND_ME_CALIBRATE',['../class_b_n_o08x.html#a8381dfe403ddff522f172cb16780731a',1,'BNO08x']]], - ['command_5foscillator_42',['COMMAND_OSCILLATOR',['../class_b_n_o08x.html#a308c8b5307d93a67b5b9066d44494aa5',1,'BNO08x']]], - ['command_5ftare_43',['COMMAND_TARE',['../class_b_n_o08x.html#a0a1756bc16ba3eac45f4229b1e350107',1,'BNO08x']]], - ['contact_44',['Contact',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md15',1,'']]], - ['create_5ftest_5fimu_45',['create_test_imu',['../class_b_n_o08x_test_helper.html#a6bd040c7d670a9713f2ab8a8a3913518',1,'BNO08xTestHelper']]], - ['current_5fslowest_5freport_5fid_46',['current_slowest_report_ID',['../class_b_n_o08x.html#ae2e8382b5ff8d0ca3375a10b6e273f0c',1,'BNO08x']]] -]; diff --git a/documentation/html/search/all_3.js b/documentation/html/search/all_3.js deleted file mode 100644 index ef7bae1..0000000 --- a/documentation/html/search/all_3.js +++ /dev/null @@ -1,33 +0,0 @@ -var searchData= -[ - ['data_5favailable_0',['data_available',['../class_b_n_o08x.html#ab56b185d6c9e972a2b28c2621387bb86',1,'BNO08x']]], - ['data_5fproc_5ftask_1',['data_proc_task',['../struct_b_n_o08x_1_1bno08x__init__status__t.html#a04ef18c7f80f305a621b6cc3e5b6107d',1,'BNO08x::bno08x_init_status_t::data_proc_task'],['../class_b_n_o08x.html#ab4373e9b87837ea9fcbc0b536338c7b8',1,'BNO08x::data_proc_task()']]], - ['data_5fproc_5ftask_5fhdl_2',['data_proc_task_hdl',['../class_b_n_o08x.html#af9b6fbf35e7cd55d517d30c6429a21a4',1,'BNO08x']]], - ['data_5fproc_5ftask_5ftrampoline_3',['data_proc_task_trampoline',['../class_b_n_o08x.html#a0ae135d7bf7a5f047a1d1aa5cc07e520',1,'BNO08x']]], - ['deinit_5fgpio_4',['deinit_gpio',['../class_b_n_o08x.html#a4f007dd431f10e741414d197bb4926c3',1,'BNO08x']]], - ['deinit_5fgpio_5finputs_5',['deinit_gpio_inputs',['../class_b_n_o08x.html#a1f0f4cd8dc7d38448e2198ea47d0018c',1,'BNO08x']]], - ['deinit_5fgpio_5foutputs_6',['deinit_gpio_outputs',['../class_b_n_o08x.html#ab132a061bd437fd109225446aa1f6010',1,'BNO08x']]], - ['deinit_5fhint_5fisr_7',['deinit_hint_isr',['../class_b_n_o08x.html#a9d96108b0f5b1e1e1ac431bc993ca758',1,'BNO08x']]], - ['deinit_5fspi_8',['deinit_spi',['../class_b_n_o08x.html#a233920ce97f685fbdabecccacf471d85',1,'BNO08x']]], - ['destroy_5ftest_5fimu_9',['destroy_test_imu',['../class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40',1,'BNO08xTestHelper']]], - ['disable_5faccelerometer_10',['disable_accelerometer',['../class_b_n_o08x.html#ad5c991150895b80bee68c933059a4058',1,'BNO08x::disable_accelerometer()'],['../_callback_tests_8cpp.html#a79547a2396efd083faeba3e54d94360d',1,'disable_accelerometer(): CallbackTests.cpp']]], - ['disable_5factivity_5fclassifier_11',['disable_activity_classifier',['../class_b_n_o08x.html#a4fdc39294922a9553d84cd96bdae4376',1,'BNO08x']]], - ['disable_5farvr_5fstabilized_5fgame_5frotation_5fvector_12',['disable_ARVR_stabilized_game_rotation_vector',['../class_b_n_o08x.html#ab187fe50fcfbb04bec9e80eb0fccf61c',1,'BNO08x']]], - ['disable_5farvr_5fstabilized_5frotation_5fvector_13',['disable_ARVR_stabilized_rotation_vector',['../class_b_n_o08x.html#aa59e3d8953c96dc1cc5958a1ac628df4',1,'BNO08x']]], - ['disable_5fcalibrated_5fgyro_14',['disable_calibrated_gyro',['../class_b_n_o08x.html#a4d6832a3c0b2b4014e28145e6ffe9c2c',1,'BNO08x']]], - ['disable_5fgame_5frotation_5fvector_15',['disable_game_rotation_vector',['../class_b_n_o08x.html#a7665cce95e791c89161ec863f49c0392',1,'BNO08x']]], - ['disable_5fgravity_16',['disable_gravity',['../class_b_n_o08x.html#a5e63a9e68dbe2968b37dcb6dae04de6f',1,'BNO08x']]], - ['disable_5fgyro_5fintegrated_5frotation_5fvector_17',['disable_gyro_integrated_rotation_vector',['../class_b_n_o08x.html#aac0a00bed7825d8a2c357a48c3626931',1,'BNO08x']]], - ['disable_5flinear_5faccelerometer_18',['disable_linear_accelerometer',['../class_b_n_o08x.html#afbd2b02d5abe7084ce9de49ee2c9142f',1,'BNO08x::disable_linear_accelerometer()'],['../_callback_tests_8cpp.html#a5cc5f7e6658e3b1634d99b73dbfd06ab',1,'disable_linear_accelerometer(): CallbackTests.cpp']]], - ['disable_5fmagnetometer_19',['disable_magnetometer',['../class_b_n_o08x.html#a6671b082d20dda8bf5c53cb47db0c338',1,'BNO08x']]], - ['disable_5fraw_5fmems_5faccelerometer_20',['disable_raw_mems_accelerometer',['../class_b_n_o08x.html#a6cd96063eeac75af5f292bdcd31972ce',1,'BNO08x']]], - ['disable_5fraw_5fmems_5fgyro_21',['disable_raw_mems_gyro',['../class_b_n_o08x.html#a5d3ed8a44a34553cf5239cdd4032e725',1,'BNO08x']]], - ['disable_5fraw_5fmems_5fmagnetometer_22',['disable_raw_mems_magnetometer',['../class_b_n_o08x.html#a62d634fc9bced0197103f2973f27bae2',1,'BNO08x']]], - ['disable_5freport_23',['disable_report',['../class_b_n_o08x.html#a00ec3857cb06ae885e32059ef1cab693',1,'BNO08x']]], - ['disable_5frotation_5fvector_24',['disable_rotation_vector',['../class_b_n_o08x.html#a1ebd456d2a67a22b5ba0911a95915921',1,'BNO08x']]], - ['disable_5fstability_5fclassifier_25',['disable_stability_classifier',['../class_b_n_o08x.html#ab307ed3352e04c9e998ab4dd066f8932',1,'BNO08x']]], - ['disable_5fstep_5fcounter_26',['disable_step_counter',['../class_b_n_o08x.html#a427550a4ba25252912436b899124e157',1,'BNO08x']]], - ['disable_5ftap_5fdetector_27',['disable_tap_detector',['../class_b_n_o08x.html#a16f83d1e85576a51abf2c65e5de58cd2',1,'BNO08x']]], - ['disable_5funcalibrated_5fgyro_28',['disable_uncalibrated_gyro',['../class_b_n_o08x.html#aaf28212a5f1960c62a73282976142cfc',1,'BNO08x']]], - ['documentation_29',['Documentation',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md11',1,'']]] -]; diff --git a/documentation/html/search/all_4.js b/documentation/html/search/all_4.js deleted file mode 100644 index f0491d3..0000000 --- a/documentation/html/search/all_4.js +++ /dev/null @@ -1,54 +0,0 @@ -var searchData= -[ - ['enable_5faccelerometer_0',['enable_accelerometer',['../class_b_n_o08x.html#a2795c6579cf03e22f62a5eadc88dee91',1,'BNO08x::enable_accelerometer()'],['../_callback_tests_8cpp.html#a0f2cacda77ab92640f739aca52b1f99f',1,'enable_accelerometer(): CallbackTests.cpp']]], - ['enable_5factivity_5fclassifier_1',['enable_activity_classifier',['../class_b_n_o08x.html#a039e8770759e784baa438324ae17883c',1,'BNO08x']]], - ['enable_5farvr_5fstabilized_5fgame_5frotation_5fvector_2',['enable_ARVR_stabilized_game_rotation_vector',['../class_b_n_o08x.html#a5680148a41cb9cc96d1911150c46d2b8',1,'BNO08x']]], - ['enable_5farvr_5fstabilized_5frotation_5fvector_3',['enable_ARVR_stabilized_rotation_vector',['../class_b_n_o08x.html#a8a5f3b985989e846e831f70f7733d0bc',1,'BNO08x']]], - ['enable_5fcalibrated_5fgyro_4',['enable_calibrated_gyro',['../class_b_n_o08x.html#a9e72a094c4469c9eb9fb766744560c53',1,'BNO08x']]], - ['enable_5fgame_5frotation_5fvector_5',['enable_game_rotation_vector',['../class_b_n_o08x.html#abe04c38b5bd52d331bd8aefae1f51947',1,'BNO08x']]], - ['enable_5fgravity_6',['enable_gravity',['../class_b_n_o08x.html#a030eae12c3586acf09b48e94630b2544',1,'BNO08x']]], - ['enable_5fgyro_5fintegrated_5frotation_5fvector_7',['enable_gyro_integrated_rotation_vector',['../class_b_n_o08x.html#a7388c67de3906ad05b233fd7eff0514d',1,'BNO08x']]], - ['enable_5flinear_5faccelerometer_8',['enable_linear_accelerometer',['../class_b_n_o08x.html#ae1435b83ca83bc51b75f3303afe87f7b',1,'BNO08x::enable_linear_accelerometer()'],['../_callback_tests_8cpp.html#a3e937c8c4a4c07b81fb20077ee984fc0',1,'enable_linear_accelerometer(): CallbackTests.cpp']]], - ['enable_5fmagnetometer_9',['enable_magnetometer',['../class_b_n_o08x.html#a3c32120bcd0987c3ca1bb72910586b59',1,'BNO08x']]], - ['enable_5fraw_5fmems_5faccelerometer_10',['enable_raw_mems_accelerometer',['../class_b_n_o08x.html#a69f768318a621a7dc6620e5551926c3b',1,'BNO08x']]], - ['enable_5fraw_5fmems_5fgyro_11',['enable_raw_mems_gyro',['../class_b_n_o08x.html#a8be135ed41646199540583b29806d4e5',1,'BNO08x']]], - ['enable_5fraw_5fmems_5fmagnetometer_12',['enable_raw_mems_magnetometer',['../class_b_n_o08x.html#a69b3255550345bcb2d302476d50e38a5',1,'BNO08x']]], - ['enable_5freport_13',['enable_report',['../class_b_n_o08x.html#a789f9b9b8ad0a84a6ca45a85740823ca',1,'BNO08x']]], - ['enable_5frotation_5fvector_14',['enable_rotation_vector',['../class_b_n_o08x.html#ab4c1d5cde156af09b7e88913f3af62c7',1,'BNO08x']]], - ['enable_5fstability_5fclassifier_15',['enable_stability_classifier',['../class_b_n_o08x.html#ab0a60844b36fb140cad588a65b3a9655',1,'BNO08x']]], - ['enable_5fstep_5fcounter_16',['enable_step_counter',['../class_b_n_o08x.html#a5a0b0f5b8e962247a3b8aee8f1dc8e9f',1,'BNO08x']]], - ['enable_5ftap_5fdetector_17',['enable_tap_detector',['../class_b_n_o08x.html#ab4c8e37c730ddb168f78c29bd7ae6566',1,'BNO08x']]], - ['enable_5funcalibrated_5fgyro_18',['enable_uncalibrated_gyro',['../class_b_n_o08x.html#a7fe5de95b1f51da44247a87317fd0c75',1,'BNO08x']]], - ['enabled_5freport_5fcnt_19',['ENABLED_REPORT_CNT',['../_callback_tests_8cpp.html#aafbc34af64f3c93123dce5a8238efd38',1,'CallbackTests.cpp']]], - ['end_5fcalibration_20',['end_calibration',['../class_b_n_o08x.html#ac9d9b6636745e8180807284da67c92a2',1,'BNO08x']]], - ['evt_5fgrp_5freport_5fen_21',['evt_grp_report_en',['../class_b_n_o08x.html#a63eb6c8be6f3bc943a86bb0496871275',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5faccelerometer_5fbit_22',['EVT_GRP_RPT_ACCELEROMETER_BIT',['../class_b_n_o08x.html#a17b19c32d4dfbc9ae2761a0cdd873314',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5factivity_5fclassifier_5fbit_23',['EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BIT',['../class_b_n_o08x.html#a96eb1b1bfe1266791fd424b3ce402c56',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5fall_5fbits_24',['EVT_GRP_RPT_ALL_BITS',['../class_b_n_o08x.html#a89399e8a68a53bc2a269ab73625a2da2',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5farvr_5fs_5fgame_5frotation_5fvector_5fbit_25',['EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BIT',['../class_b_n_o08x.html#a79d3fff1e0f19467cad231b22edafa0f',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5farvr_5fs_5frotation_5fvector_5fbit_26',['EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BIT',['../class_b_n_o08x.html#aa9703cee46912a545b5e85e671f08e4b',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5fgame_5frotation_5fvector_5fbit_27',['EVT_GRP_RPT_GAME_ROTATION_VECTOR_BIT',['../class_b_n_o08x.html#a0f3f33d93b72ba6564f9d5fa93c24f98',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5fgravity_5fbit_28',['EVT_GRP_RPT_GRAVITY_BIT',['../class_b_n_o08x.html#ab94a8f69673a3db7556ba67775c5ea93',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5fgyro_5fbit_29',['EVT_GRP_RPT_GYRO_BIT',['../class_b_n_o08x.html#a3a8b12ea9b75f97191785a60d1aa962a',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5fgyro_5frotation_5fvector_5fbit_30',['EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BIT',['../class_b_n_o08x.html#a541155dc4544193451cf102e2a992da9',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5fgyro_5funcalibrated_5fbit_31',['EVT_GRP_RPT_GYRO_UNCALIBRATED_BIT',['../class_b_n_o08x.html#af86821bc0f1e7f5897de20b5e47a85bd',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5flinear_5faccelerometer_5fbit_32',['EVT_GRP_RPT_LINEAR_ACCELEROMETER_BIT',['../class_b_n_o08x.html#ad93161968a53ff53a6bb74ab7c34fbff',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5fmagnetometer_5fbit_33',['EVT_GRP_RPT_MAGNETOMETER_BIT',['../class_b_n_o08x.html#a901af6f2d552f197ee830d0a1c06679c',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5fraw_5faccelerometer_5fbit_34',['EVT_GRP_RPT_RAW_ACCELEROMETER_BIT',['../class_b_n_o08x.html#a3e56d12435f7be81956d68196f1a46b4',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5fraw_5fgyro_5fbit_35',['EVT_GRP_RPT_RAW_GYRO_BIT',['../class_b_n_o08x.html#a6be7b240e4447c2c643e706954093aa0',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5fraw_5fmagnetometer_5fbit_36',['EVT_GRP_RPT_RAW_MAGNETOMETER_BIT',['../class_b_n_o08x.html#ac28553b40b82c7cb409938681afe6cec',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5frotation_5fvector_5fbit_37',['EVT_GRP_RPT_ROTATION_VECTOR_BIT',['../class_b_n_o08x.html#a198da2ee3cd9cfa459c3c41c4f8c44b7',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5fstability_5fclassifier_5fbit_38',['EVT_GRP_RPT_STABILITY_CLASSIFIER_BIT',['../class_b_n_o08x.html#a7d6ee23222f55dbe9f70e04b36d9add2',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5fstep_5fcounter_5fbit_39',['EVT_GRP_RPT_STEP_COUNTER_BIT',['../class_b_n_o08x.html#ab264b65a3aa5a9a74ed11b8977164a73',1,'BNO08x']]], - ['evt_5fgrp_5frpt_5ftap_5fdetector_5fbit_40',['EVT_GRP_RPT_TAP_DETECTOR_BIT',['../class_b_n_o08x.html#a665464f781fe891b9179478d0174af47',1,'BNO08x']]], - ['evt_5fgrp_5fspi_41',['evt_grp_spi',['../class_b_n_o08x.html#aa2b4442b5cc63ebf0c495e6fb537c85e',1,'BNO08x']]], - ['evt_5fgrp_5fspi_5frx_5fdone_5fbit_42',['EVT_GRP_SPI_RX_DONE_BIT',['../class_b_n_o08x.html#a32cffd8f78881925d22d5a7cb55f2bbc',1,'BNO08x']]], - ['evt_5fgrp_5fspi_5frx_5finvalid_5fpacket_5fbit_43',['EVT_GRP_SPI_RX_INVALID_PACKET_BIT',['../class_b_n_o08x.html#a15e3f92812f8fe70b30966b73a7cb5b2',1,'BNO08x']]], - ['evt_5fgrp_5fspi_5frx_5fvalid_5fpacket_5fbit_44',['EVT_GRP_SPI_RX_VALID_PACKET_BIT',['../class_b_n_o08x.html#a96342b0182f339d5a8d6cac1214ce174',1,'BNO08x']]], - ['evt_5fgrp_5fspi_5ftx_5fdone_5fbit_45',['EVT_GRP_SPI_TX_DONE_BIT',['../class_b_n_o08x.html#adf2c292674e428c3b65c846cfab4deb7',1,'BNO08x']]], - ['evt_5fgrp_5ftask_5fflow_46',['evt_grp_task_flow',['../class_b_n_o08x.html#ac4b1fae7a1155c8b93b645b4eb6eb0f1',1,'BNO08x']]], - ['evt_5fgrp_5ftsk_5fflw_5frunning_5fbit_47',['EVT_GRP_TSK_FLW_RUNNING_BIT',['../class_b_n_o08x.html#a5fc8c8969043c5d08fce80eb1d74a761',1,'BNO08x']]], - ['example_48',['Example',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md7',1,'Call-Back Function Example'],['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md6',1,'Polling Example']]], - ['examples_49',['Examples',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md5',1,'']]], - ['ext_5frst_50',['EXT_RST',['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/all_5.js b/documentation/html/search/all_5.js deleted file mode 100644 index 31d57a0..0000000 --- a/documentation/html/search/all_5.js +++ /dev/null @@ -1,15 +0,0 @@ -var searchData= -[ - ['first_5fboot_0',['first_boot',['../class_b_n_o08x.html#ae4670fed6de963a087ab58f95fda319b',1,'BNO08x']]], - ['flowcharts_1',['Program Flowcharts',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md12',1,'']]], - ['flush_5frx_5fpackets_2',['flush_rx_packets',['../class_b_n_o08x.html#a48c1d43b66b1a0894cb1fc2179f62cdc',1,'BNO08x']]], - ['for_3',['for',['../_callback_tests_8cpp.html#a4ac223c58b5ab6a6c5203661fafa1caa',1,'CallbackTests.cpp']]], - ['frs_5fread_5fdata_4',['FRS_read_data',['../class_b_n_o08x.html#a40607e557eada666a5e1e416f42cd4a1',1,'BNO08x']]], - ['frs_5fread_5frequest_5',['FRS_read_request',['../class_b_n_o08x.html#adf789e709ac1667656db757c8d559af9',1,'BNO08x']]], - ['frs_5fread_5fword_6',['FRS_read_word',['../class_b_n_o08x.html#a27f5dce5c994be18a587fb622574ad41',1,'BNO08x']]], - ['frs_5frecord_5fid_5faccelerometer_7',['FRS_RECORD_ID_ACCELEROMETER',['../class_b_n_o08x.html#ad7ef7d7068af5f92239c12022dbeb16d',1,'BNO08x']]], - ['frs_5frecord_5fid_5fgyroscope_5fcalibrated_8',['FRS_RECORD_ID_GYROSCOPE_CALIBRATED',['../class_b_n_o08x.html#a35d8f641e73c308f92a5a0a772f90f48',1,'BNO08x']]], - ['frs_5frecord_5fid_5fmagnetic_5ffield_5fcalibrated_9',['FRS_RECORD_ID_MAGNETIC_FIELD_CALIBRATED',['../class_b_n_o08x.html#a0992d77f9bae0b8e3c8d9331fe84fe24',1,'BNO08x']]], - ['frs_5frecord_5fid_5frotation_5fvector_10',['FRS_RECORD_ID_ROTATION_VECTOR',['../class_b_n_o08x.html#a9f35840b19c8ad11fd1b4622c3269250',1,'BNO08x']]], - ['function_20example_11',['Call-Back Function Example',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md7',1,'']]] -]; diff --git a/documentation/html/search/all_6.js b/documentation/html/search/all_6.js deleted file mode 100644 index be22e9a..0000000 --- a/documentation/html/search/all_6.js +++ /dev/null @@ -1,90 +0,0 @@ -var searchData= -[ - ['get_5faccel_0',['get_accel',['../class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885',1,'BNO08x']]], - ['get_5faccel_5faccuracy_1',['get_accel_accuracy',['../class_b_n_o08x.html#a6eed9e2d3e639ec7e38dfdf092c14ea1',1,'BNO08x']]], - ['get_5faccel_5fx_2',['get_accel_X',['../class_b_n_o08x.html#abce574112a9079d2cbc58cfc352b8a69',1,'BNO08x']]], - ['get_5faccel_5fy_3',['get_accel_Y',['../class_b_n_o08x.html#afdf24bb3d54518b23972f21f007817c1',1,'BNO08x']]], - ['get_5faccel_5fz_4',['get_accel_Z',['../class_b_n_o08x.html#a0a72477cb7a330fedbcb3e2126b882b1',1,'BNO08x']]], - ['get_5factivity_5fclassifier_5',['get_activity_classifier',['../class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed',1,'BNO08x']]], - ['get_5fcalibrated_5fgyro_5fvelocity_6',['get_calibrated_gyro_velocity',['../class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f',1,'BNO08x']]], - ['get_5fcalibrated_5fgyro_5fvelocity_5fx_7',['get_calibrated_gyro_velocity_X',['../class_b_n_o08x.html#a7710e8bee76742e351cecfaf441f0889',1,'BNO08x']]], - ['get_5fcalibrated_5fgyro_5fvelocity_5fy_8',['get_calibrated_gyro_velocity_Y',['../class_b_n_o08x.html#a492d5bde7377d9f6773eae1d70967f50',1,'BNO08x']]], - ['get_5fcalibrated_5fgyro_5fvelocity_5fz_9',['get_calibrated_gyro_velocity_Z',['../class_b_n_o08x.html#a1599c0515f05a08c043f237c46d29dea',1,'BNO08x']]], - ['get_5fgravity_10',['get_gravity',['../class_b_n_o08x.html#a067678914e928a6691625b17c40237a0',1,'BNO08x']]], - ['get_5fgravity_5faccuracy_11',['get_gravity_accuracy',['../class_b_n_o08x.html#a77c82cece30dde944efcde81643fd62d',1,'BNO08x']]], - ['get_5fgravity_5fx_12',['get_gravity_X',['../class_b_n_o08x.html#a88679bccd9339b87ec35fc4fc4e745ae',1,'BNO08x']]], - ['get_5fgravity_5fy_13',['get_gravity_Y',['../class_b_n_o08x.html#a8a36db7f1c932f33e05e494632059801',1,'BNO08x']]], - ['get_5fgravity_5fz_14',['get_gravity_Z',['../class_b_n_o08x.html#a5622b4d1754648ea7eb400c1adf9e807',1,'BNO08x']]], - ['get_5fintegrated_5fgyro_5fvelocity_15',['get_integrated_gyro_velocity',['../class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f',1,'BNO08x']]], - ['get_5fintegrated_5fgyro_5fvelocity_5fx_16',['get_integrated_gyro_velocity_X',['../class_b_n_o08x.html#a2eb2accfbc70366e6e3eaf391622c1ff',1,'BNO08x']]], - ['get_5fintegrated_5fgyro_5fvelocity_5fy_17',['get_integrated_gyro_velocity_Y',['../class_b_n_o08x.html#aff9a7e0190b228f5032474a3f4feb9a1',1,'BNO08x']]], - ['get_5fintegrated_5fgyro_5fvelocity_5fz_18',['get_integrated_gyro_velocity_Z',['../class_b_n_o08x.html#aa5b483cb0036e9dd43bf797259634add',1,'BNO08x']]], - ['get_5flinear_5faccel_19',['get_linear_accel',['../class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46',1,'BNO08x']]], - ['get_5flinear_5faccel_5faccuracy_20',['get_linear_accel_accuracy',['../class_b_n_o08x.html#a6114ba3c8967ac8fde06233c81623c80',1,'BNO08x']]], - ['get_5flinear_5faccel_5fx_21',['get_linear_accel_X',['../class_b_n_o08x.html#a763c3a9699a1081d430fd9b9b7bc49a3',1,'BNO08x']]], - ['get_5flinear_5faccel_5fy_22',['get_linear_accel_Y',['../class_b_n_o08x.html#a1033bdd65b42b6706d1dfc67ece66191',1,'BNO08x']]], - ['get_5flinear_5faccel_5fz_23',['get_linear_accel_Z',['../class_b_n_o08x.html#afdfa7d50362702da689c5d18bf17fd84',1,'BNO08x']]], - ['get_5fmagf_24',['get_magf',['../class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb',1,'BNO08x']]], - ['get_5fmagf_5faccuracy_25',['get_magf_accuracy',['../class_b_n_o08x.html#a2d98b2cba47dffee8745de1955d234a9',1,'BNO08x']]], - ['get_5fmagf_5fx_26',['get_magf_X',['../class_b_n_o08x.html#a111601243b913751eb51c1f37cba4e7d',1,'BNO08x']]], - ['get_5fmagf_5fy_27',['get_magf_Y',['../class_b_n_o08x.html#a82ed8d7b9a5c25374839df75a3d220ea',1,'BNO08x']]], - ['get_5fmagf_5fz_28',['get_magf_Z',['../class_b_n_o08x.html#ab4c48a91d2f8b29430abc17b7f015282',1,'BNO08x']]], - ['get_5fpitch_29',['get_pitch',['../class_b_n_o08x.html#a1b91f234d81c45f1f5ca2f27c9f0f6a3',1,'BNO08x']]], - ['get_5fpitch_5fdeg_30',['get_pitch_deg',['../class_b_n_o08x.html#af50010400cbd1445e9ddfa259384b412',1,'BNO08x']]], - ['get_5fq1_31',['get_Q1',['../class_b_n_o08x.html#a4421c43323945946ad605f8422958dcf',1,'BNO08x']]], - ['get_5fq2_32',['get_Q2',['../class_b_n_o08x.html#a954dccdcbe8a8c4f1787f13ebb8d932b',1,'BNO08x']]], - ['get_5fq3_33',['get_Q3',['../class_b_n_o08x.html#a1590ba793668f9cb1a32a1f4dd07cb9a',1,'BNO08x']]], - ['get_5fquat_34',['get_quat',['../class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a',1,'BNO08x']]], - ['get_5fquat_5faccuracy_35',['get_quat_accuracy',['../class_b_n_o08x.html#a7c7a74367db26ea8bfbdea633ee1d654',1,'BNO08x']]], - ['get_5fquat_5fi_36',['get_quat_I',['../class_b_n_o08x.html#a12c12a8e078b28480fb8828d306656f5',1,'BNO08x']]], - ['get_5fquat_5fj_37',['get_quat_J',['../class_b_n_o08x.html#a9f6bb642fa0297a7b9bcc94dd7374015',1,'BNO08x']]], - ['get_5fquat_5fk_38',['get_quat_K',['../class_b_n_o08x.html#a9f42c70c2337a0d831064a40ecfe2dd8',1,'BNO08x']]], - ['get_5fquat_5fradian_5faccuracy_39',['get_quat_radian_accuracy',['../class_b_n_o08x.html#a61b7d10a98afc6903fea6b2cede27630',1,'BNO08x']]], - ['get_5fquat_5freal_40',['get_quat_real',['../class_b_n_o08x.html#a5a556c5ec1baaa7f1156779dbe47a7b7',1,'BNO08x']]], - ['get_5frange_41',['get_range',['../class_b_n_o08x.html#a0fff04c42c9502615ad73cd1457cb9b0',1,'BNO08x']]], - ['get_5fraw_5fmems_5faccel_42',['get_raw_mems_accel',['../class_b_n_o08x.html#aa6bbad8c9123b4dba5007f72a8806303',1,'BNO08x']]], - ['get_5fraw_5fmems_5faccel_5fx_43',['get_raw_mems_accel_X',['../class_b_n_o08x.html#a868b24d96cb12f614431a410bcc9e434',1,'BNO08x']]], - ['get_5fraw_5fmems_5faccel_5fy_44',['get_raw_mems_accel_Y',['../class_b_n_o08x.html#aebcbaf9c3aaf37d85a78d22dc22c614a',1,'BNO08x']]], - ['get_5fraw_5fmems_5faccel_5fz_45',['get_raw_mems_accel_Z',['../class_b_n_o08x.html#a85d1331ebe762f6823bde4bf76a33e21',1,'BNO08x']]], - ['get_5fraw_5fmems_5fgyro_46',['get_raw_mems_gyro',['../class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27',1,'BNO08x']]], - ['get_5fraw_5fmems_5fgyro_5fx_47',['get_raw_mems_gyro_X',['../class_b_n_o08x.html#a8872241c73bca2ac1698ae867f7d1913',1,'BNO08x']]], - ['get_5fraw_5fmems_5fgyro_5fy_48',['get_raw_mems_gyro_Y',['../class_b_n_o08x.html#a4bcc58423b5cc7c24080c2ef812d3d86',1,'BNO08x']]], - ['get_5fraw_5fmems_5fgyro_5fz_49',['get_raw_mems_gyro_Z',['../class_b_n_o08x.html#ae684dd13ef630dfdbb8de18ee5ea90bb',1,'BNO08x']]], - ['get_5fraw_5fmems_5fmagf_50',['get_raw_mems_magf',['../class_b_n_o08x.html#a929ad333f73614fb5830c186e3e03a00',1,'BNO08x']]], - ['get_5fraw_5fmems_5fmagf_5fx_51',['get_raw_mems_magf_X',['../class_b_n_o08x.html#a347444f461b2fab5ff37de346ba2a595',1,'BNO08x']]], - ['get_5fraw_5fmems_5fmagf_5fy_52',['get_raw_mems_magf_Y',['../class_b_n_o08x.html#ad8a215314ae96b25b59fdc363c52261c',1,'BNO08x']]], - ['get_5fraw_5fmems_5fmagf_5fz_53',['get_raw_mems_magf_Z',['../class_b_n_o08x.html#a780651af54485edb36d197f30c071615',1,'BNO08x']]], - ['get_5freset_5freason_54',['get_reset_reason',['../class_b_n_o08x.html#a96d47dd0f9aedfbe3f731f8ae76b2e85',1,'BNO08x']]], - ['get_5fresolution_55',['get_resolution',['../class_b_n_o08x.html#a1d6ea02d0d4b23ff6a15e9d5c6c92372',1,'BNO08x']]], - ['get_5froll_56',['get_roll',['../class_b_n_o08x.html#a89618eba08186ee8e679e7313907ddef',1,'BNO08x']]], - ['get_5froll_5fdeg_57',['get_roll_deg',['../class_b_n_o08x.html#a7077b9a130f1dcf0192454e387968dd6',1,'BNO08x']]], - ['get_5fstability_5fclassifier_58',['get_stability_classifier',['../class_b_n_o08x.html#a248544b262582d10d917a687190cb454',1,'BNO08x']]], - ['get_5fstep_5fcount_59',['get_step_count',['../class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef',1,'BNO08x']]], - ['get_5ftap_5fdetector_60',['get_tap_detector',['../class_b_n_o08x.html#a4797ec731de4c158716da1a7af9d1602',1,'BNO08x']]], - ['get_5ftest_5fimu_61',['get_test_imu',['../class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b',1,'BNO08xTestHelper']]], - ['get_5ftime_5fstamp_62',['get_time_stamp',['../class_b_n_o08x.html#ad9137777271421a58159f3fe5e05ed20',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fbias_5fx_63',['get_uncalibrated_gyro_bias_X',['../class_b_n_o08x.html#ad228cdf352b7ea95e484da993045a47b',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fbias_5fy_64',['get_uncalibrated_gyro_bias_Y',['../class_b_n_o08x.html#a74725517129dd548c7a3de705d5861bd',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fbias_5fz_65',['get_uncalibrated_gyro_bias_Z',['../class_b_n_o08x.html#a5050359272abd146ab3c7a6101effbd7',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fvelocity_66',['get_uncalibrated_gyro_velocity',['../class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fvelocity_5fx_67',['get_uncalibrated_gyro_velocity_X',['../class_b_n_o08x.html#a71bbcd4b4d63d55d4f7d5f0de6154486',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fvelocity_5fy_68',['get_uncalibrated_gyro_velocity_Y',['../class_b_n_o08x.html#a2d5a9fa5c960b9efa96d311d25f711de',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fvelocity_5fz_69',['get_uncalibrated_gyro_velocity_Z',['../class_b_n_o08x.html#ab6dc34d058002e21978f8a7e4cf24592',1,'BNO08x']]], - ['get_5fyaw_70',['get_yaw',['../class_b_n_o08x.html#a64d3e41750c6de9413d6982511f78f17',1,'BNO08x']]], - ['get_5fyaw_5fdeg_71',['get_yaw_deg',['../class_b_n_o08x.html#af80f7795656e695e036d3b1557aed94c',1,'BNO08x']]], - ['getting_20started_72',['Getting Started',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md1',1,'']]], - ['gpio_5finputs_73',['gpio_inputs',['../struct_b_n_o08x_1_1bno08x__init__status__t.html#a7439c3e0e98c3c2276f8607e5a36b557',1,'BNO08x::bno08x_init_status_t']]], - ['gpio_5foutputs_74',['gpio_outputs',['../struct_b_n_o08x_1_1bno08x__init__status__t.html#a918d393541f260ae059614ed477887df',1,'BNO08x::bno08x_init_status_t']]], - ['grav_5faccuracy_75',['grav_accuracy',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a735d099f3dd0ead4b8d986fd139af43d',1,'BNO08xTestHelper::imu_report_data_t']]], - ['grav_5fx_76',['grav_x',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ad2c17ea111250ebc1a4a763dae3c072a',1,'BNO08xTestHelper::imu_report_data_t']]], - ['grav_5fy_77',['grav_y',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a19fc4af8a26c10a027cbd859d67dba4a',1,'BNO08xTestHelper::imu_report_data_t']]], - ['grav_5fz_78',['grav_z',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af1887bdfef4fc2c683fe2134cb5cfb50',1,'BNO08xTestHelper::imu_report_data_t']]], - ['gravity_5faccuracy_79',['gravity_accuracy',['../class_b_n_o08x.html#ae01698d287ea999179a11e2244902022',1,'BNO08x']]], - ['gravity_5fdata_5fis_5fnew_80',['gravity_data_is_new',['../class_b_n_o08x_test_helper.html#a3c2514f3bad3f091de4646c5798f487a',1,'BNO08xTestHelper']]], - ['gravity_5fq1_81',['GRAVITY_Q1',['../class_b_n_o08x.html#ae10722334dfce9635e76519598e165a2',1,'BNO08x']]], - ['gravity_5fx_82',['gravity_X',['../class_b_n_o08x.html#af45016be9ea523d80be8467b2907b499',1,'BNO08x']]], - ['gravity_5fy_83',['gravity_Y',['../class_b_n_o08x.html#af20dcd487a9fe8fa6243817d51e37be5',1,'BNO08x']]], - ['gravity_5fz_84',['gravity_Z',['../class_b_n_o08x.html#afa1cf5c3afbb258d97c55c5fb187f2d6',1,'BNO08x']]], - ['gyro_5fintegrated_5frotation_5fvector_5fdata_5fis_5fnew_85',['gyro_integrated_rotation_vector_data_is_new',['../class_b_n_o08x_test_helper.html#ac5b0ac4c70bbfcba9f2e8f353b35f9f6',1,'BNO08xTestHelper']]], - ['gyro_5fq1_86',['GYRO_Q1',['../class_b_n_o08x.html#aa3bec8effefa61cec6fa170e9d02c4dd',1,'BNO08x']]] -]; diff --git a/documentation/html/search/all_7.js b/documentation/html/search/all_7.js deleted file mode 100644 index 9935ff3..0000000 --- a/documentation/html/search/all_7.js +++ /dev/null @@ -1,10 +0,0 @@ -var searchData= -[ - ['hard_5freset_0',['hard_reset',['../class_b_n_o08x.html#a28cd1c0b3477571d87133234e6358503',1,'BNO08x']]], - ['hard_5freset_5fdelay_5fms_1',['HARD_RESET_DELAY_MS',['../class_b_n_o08x.html#aa07e329d693eb8d9270a7f9ad6f1d94b',1,'BNO08x']]], - ['header_2',['header',['../struct_b_n_o08x_1_1bno08x__rx__packet__t.html#a667d671ccb272bd375008716e26e0b5b',1,'BNO08x::bno08x_rx_packet_t']]], - ['high_3',['HIGH',['../_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c',1,'BNO08x_global_types.hpp']]], - ['hint_5fhandler_4',['hint_handler',['../class_b_n_o08x.html#a804b95c58c30d36933fd251626b85bf7',1,'BNO08x']]], - ['host_5fint_5ftimeout_5fdefault_5fms_5',['HOST_INT_TIMEOUT_DEFAULT_MS',['../class_b_n_o08x.html#ae51d4e3228a91ee407d5866e604804c4',1,'BNO08x']]], - ['host_5fint_5ftimeout_5fms_6',['host_int_timeout_ms',['../class_b_n_o08x.html#ab0c1b4ef4dbcc05a2a6cf37ee039ba0e',1,'BNO08x']]] -]; diff --git a/documentation/html/search/all_8.js b/documentation/html/search/all_8.js deleted file mode 100644 index 95bc9de..0000000 --- a/documentation/html/search/all_8.js +++ /dev/null @@ -1,39 +0,0 @@ -var searchData= -[ - ['imu_0',['imu',['../_callback_tests_8cpp.html#ac36e56130d5d806898f3545d4cdf0f70',1,'CallbackTests.cpp']]], - ['imu_5fcfg_1',['imu_cfg',['../class_b_n_o08x_test_helper.html#a008b268f705b9d2925230cb8193c9f28',1,'BNO08xTestHelper']]], - ['imu_5fconfig_2',['imu_config',['../class_b_n_o08x.html#aeda443e9f608fccfec0e6770edc90c82',1,'BNO08x']]], - ['imu_5fconfig_5ft_3',['imu_config_t',['../_b_n_o08x__global__types_8hpp.html#aae502b3d91ddf903bba797646fd28d00',1,'BNO08x_global_types.hpp']]], - ['imu_5freport_5fdata_5ft_4',['imu_report_data_t',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html',1,'BNO08xTestHelper::imu_report_data_t'],['../class_b_n_o08x_test_helper.html#a0b3d9379e670b0c532ba76801cfb7580',1,'BNO08xTestHelper::imu_report_data_t']]], - ['imu_5fspi_5fconfig_5',['imu_spi_config',['../class_b_n_o08x.html#a425a1f5a9f3232aadc685caaf4c2f82e',1,'BNO08x']]], - ['imuaccuracy_6',['IMUAccuracy',['../_b_n_o08x__global__types_8hpp.html#a03fbbd71180a19088ce30d57ab050a22',1,'BNO08x_global_types.hpp']]], - ['imuresetreason_7',['IMUResetReason',['../_b_n_o08x__global__types_8hpp.html#aeee029e15be2a7d6d8134cabcc7c752b',1,'BNO08x_global_types.hpp']]], - ['in_5fvehicle_8',['IN_VEHICLE',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4',1,'IN_VEHICLE: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4',1,'IN_VEHICLE: BNO08x_global_types.hpp']]], - ['init_5fconfig_5fargs_9',['init_config_args',['../class_b_n_o08x.html#a589eb9780f5bf613bbd447ef5b9ade3d',1,'BNO08x']]], - ['init_5fgpio_10',['init_gpio',['../class_b_n_o08x.html#ae0dab25557befcf62bf384fdc241ef10',1,'BNO08x']]], - ['init_5fgpio_5finputs_11',['init_gpio_inputs',['../class_b_n_o08x.html#a8f34d5475474f00ae6a92f73c1fe14e4',1,'BNO08x']]], - ['init_5fgpio_5foutputs_12',['init_gpio_outputs',['../class_b_n_o08x.html#ad0b9e8f8d051798bb1da9b19598dbd64',1,'BNO08x']]], - ['init_5fhint_5fisr_13',['init_hint_isr',['../class_b_n_o08x.html#aa27026da2c52b4aca49b78863f10ec61',1,'BNO08x']]], - ['init_5fspi_14',['init_spi',['../class_b_n_o08x.html#a58f43c8bb1e7fe8560ce442d46240e81',1,'BNO08x']]], - ['init_5fstatus_15',['init_status',['../class_b_n_o08x.html#a4520fc3e1dec6389d470945786680013',1,'BNO08x']]], - ['initdeinittests_2ecpp_16',['InitDeinitTests.cpp',['../_init_deinit_tests_8cpp.html',1,'']]], - ['initialize_17',['initialize',['../class_b_n_o08x.html#aea8e2c6dd7a2c9899479a7f39fe94798',1,'BNO08x']]], - ['install_5fisr_5fservice_18',['install_isr_service',['../structbno08x__config__t.html#a0f629aaef6756aa80fec96b34476c627',1,'bno08x_config_t']]], - ['int_5frst_19',['INT_RST',['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f',1,'BNO08x_global_types.hpp']]], - ['integrated_5fgyro_5fvel_5fx_20',['integrated_gyro_vel_x',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a077a94b4de0b5c280d69611325208cf7',1,'BNO08xTestHelper::imu_report_data_t']]], - ['integrated_5fgyro_5fvel_5fy_21',['integrated_gyro_vel_y',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af4b75b320bc390c90656905711f1c791',1,'BNO08xTestHelper::imu_report_data_t']]], - ['integrated_5fgyro_5fvel_5fz_22',['integrated_gyro_vel_z',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a1aa67da9c3c6449dfce361a528c418d3',1,'BNO08xTestHelper::imu_report_data_t']]], - ['integrated_5fgyro_5fvelocity_5fx_23',['integrated_gyro_velocity_X',['../class_b_n_o08x.html#a6537ed69245cf71cad6a6a44480dddaa',1,'BNO08x']]], - ['integrated_5fgyro_5fvelocity_5fy_24',['integrated_gyro_velocity_Y',['../class_b_n_o08x.html#a00b39e22ea9fe306e88aaed490ee0a51',1,'BNO08x']]], - ['integrated_5fgyro_5fvelocity_5fz_25',['integrated_gyro_velocity_Z',['../class_b_n_o08x.html#ad112beb64badd22a2e1d717e1ee921c8',1,'BNO08x']]], - ['io_5fcs_26',['io_cs',['../structbno08x__config__t.html#ab1b5351b63da0c172c942463d0dc2505',1,'bno08x_config_t']]], - ['io_5fint_27',['io_int',['../structbno08x__config__t.html#a3cfe965659cfbc6b0c5269bd0211975f',1,'bno08x_config_t']]], - ['io_5fmiso_28',['io_miso',['../structbno08x__config__t.html#a9468180a773892977db39cc5ed9368e3',1,'bno08x_config_t']]], - ['io_5fmosi_29',['io_mosi',['../structbno08x__config__t.html#a79023fd80039e41a22b7f73ccd5fc861',1,'bno08x_config_t']]], - ['io_5frst_30',['io_rst',['../structbno08x__config__t.html#a62745c761219139f66ecd173b51577fc',1,'bno08x_config_t']]], - ['io_5fsclk_31',['io_sclk',['../structbno08x__config__t.html#a639685b91ae3198909d722316495246a',1,'bno08x_config_t']]], - ['io_5fwake_32',['io_wake',['../structbno08x__config__t.html#a90ad7f316dc443874d19dc7e723a0ce0',1,'bno08x_config_t']]], - ['is_5frotation_5fvector_5freport_33',['IS_ROTATION_VECTOR_REPORT',['../_b_n_o08x__macros_8hpp.html#a84602d112b6000375ad608904de5b0e3',1,'BNO08x_macros.hpp']]], - ['isr_5fhandler_34',['isr_handler',['../struct_b_n_o08x_1_1bno08x__init__status__t.html#aa04ab662c6a1a052944312ca79a17bc3',1,'BNO08x::bno08x_init_status_t']]], - ['isr_5fservice_35',['isr_service',['../struct_b_n_o08x_1_1bno08x__init__status__t.html#a277d28ef5596d4777476d64de3f2d905',1,'BNO08x::bno08x_init_status_t']]] -]; diff --git a/documentation/html/search/all_9.js b/documentation/html/search/all_9.js deleted file mode 100644 index f020acb..0000000 --- a/documentation/html/search/all_9.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['kill_5fall_5ftasks_0',['kill_all_tasks',['../class_b_n_o08x.html#a5adc21b484ff98c42622e2ad9871d5a0',1,'BNO08x']]] -]; diff --git a/documentation/html/search/all_a.js b/documentation/html/search/all_a.js deleted file mode 100644 index 54638e0..0000000 --- a/documentation/html/search/all_a.js +++ /dev/null @@ -1,14 +0,0 @@ -var searchData= -[ - ['largest_5fsample_5fperiod_5fus_0',['largest_sample_period_us',['../class_b_n_o08x.html#a7ffc2875b3dff21a827052e4faf273b7',1,'BNO08x']]], - ['launch_5ftasks_1',['launch_tasks',['../class_b_n_o08x.html#a06f99a6b2182b49a0e61e2107f2be6be',1,'BNO08x']]], - ['length_2',['length',['../struct_b_n_o08x_1_1bno08x__rx__packet__t.html#a645adb6ba8fb2afbb99ec58fe678e205',1,'BNO08x::bno08x_rx_packet_t::length'],['../struct_b_n_o08x_1_1bno08x__tx__packet__t.html#a73180537ea7605340c5e6b2132e2cbf5',1,'BNO08x::bno08x_tx_packet_t::length']]], - ['license_3',['License',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md14',1,'']]], - ['lin_5faccel_5faccuracy_4',['lin_accel_accuracy',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a48a249994c27f59ca4167b56bdda311a',1,'BNO08xTestHelper::imu_report_data_t']]], - ['lin_5faccel_5fx_5',['lin_accel_x',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3a62ed280657cd409d723e64f0c313b5',1,'BNO08xTestHelper::imu_report_data_t']]], - ['lin_5faccel_5fy_6',['lin_accel_y',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a553942aa784c35c833543ecc9a05f606',1,'BNO08xTestHelper::imu_report_data_t']]], - ['lin_5faccel_5fz_7',['lin_accel_z',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5bf43fc0daf3a86954924e066cad3a9b',1,'BNO08xTestHelper::imu_report_data_t']]], - ['linear_5faccelerometer_5fdata_5fis_5fnew_8',['linear_accelerometer_data_is_new',['../class_b_n_o08x_test_helper.html#ad398739ce46400c1ac35e1cf7603d590',1,'BNO08xTestHelper']]], - ['linear_5faccelerometer_5fq1_9',['LINEAR_ACCELEROMETER_Q1',['../class_b_n_o08x.html#ad0d37fe07ced24f2c9afc21145a74e7b',1,'BNO08x']]], - ['low_10',['LOW',['../_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/all_b.js b/documentation/html/search/all_b.js deleted file mode 100644 index ab9a15c..0000000 --- a/documentation/html/search/all_b.js +++ /dev/null @@ -1,26 +0,0 @@ -var searchData= -[ - ['magf_5faccuracy_0',['magf_accuracy',['../class_b_n_o08x.html#ac5d4e151690774687efa951ca41c16ae',1,'BNO08x::magf_accuracy'],['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0c962609a3bf7927204542521e9c5113',1,'BNO08xTestHelper::imu_report_data_t::magf_accuracy']]], - ['magf_5fx_1',['magf_x',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0e72f6dde1411e4aa1c616cedcc556c1',1,'BNO08xTestHelper::imu_report_data_t']]], - ['magf_5fy_2',['magf_y',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8738f60a2b9bd49d2b8dd0487db7ac97',1,'BNO08xTestHelper::imu_report_data_t']]], - ['magf_5fz_3',['magf_z',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a55187ebe06fa77def93681bcdf62595c',1,'BNO08xTestHelper::imu_report_data_t']]], - ['magnetometer_5fdata_5fis_5fnew_4',['magnetometer_data_is_new',['../class_b_n_o08x_test_helper.html#a157342da2def8b659d27ae4d24063cb5',1,'BNO08xTestHelper']]], - ['magnetometer_5fq1_5',['MAGNETOMETER_Q1',['../class_b_n_o08x.html#a9fac9b811b7c2117675a784cb4df204c',1,'BNO08x']]], - ['max_5fmetadata_5flength_6',['MAX_METADATA_LENGTH',['../class_b_n_o08x.html#a2a5b978233eab4c103ab01cfc33a1750',1,'BNO08x']]], - ['med_7',['MED',['../_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c',1,'BNO08x_global_types.hpp']]], - ['mems_5fraw_5faccel_5fx_8',['mems_raw_accel_X',['../class_b_n_o08x.html#a937cbdc4edaac72c8cad041d79de5701',1,'BNO08x']]], - ['mems_5fraw_5faccel_5fy_9',['mems_raw_accel_Y',['../class_b_n_o08x.html#ad83cecb8a5d2be01db6792755b6057e9',1,'BNO08x']]], - ['mems_5fraw_5faccel_5fz_10',['mems_raw_accel_Z',['../class_b_n_o08x.html#a59a4d75f1302ab693b1b26e9ccaa5341',1,'BNO08x']]], - ['mems_5fraw_5fgyro_5fx_11',['mems_raw_gyro_X',['../class_b_n_o08x.html#a3d6b6257462951ea023af7076c80f6dd',1,'BNO08x']]], - ['mems_5fraw_5fgyro_5fy_12',['mems_raw_gyro_Y',['../class_b_n_o08x.html#ab6b142416912a096886dd63ad0beb865',1,'BNO08x']]], - ['mems_5fraw_5fgyro_5fz_13',['mems_raw_gyro_Z',['../class_b_n_o08x.html#ac35d5b12721ab876eaeb1f714a9b3b1d',1,'BNO08x']]], - ['mems_5fraw_5fmagf_5fx_14',['mems_raw_magf_X',['../class_b_n_o08x.html#ab587cdf991342b69b7fff3b33f537eb5',1,'BNO08x']]], - ['mems_5fraw_5fmagf_5fy_15',['mems_raw_magf_Y',['../class_b_n_o08x.html#aad926054c81818fff611e10ed913706a',1,'BNO08x']]], - ['mems_5fraw_5fmagf_5fz_16',['mems_raw_magf_Z',['../class_b_n_o08x.html#a90f0cdf11decc276006f76a494d42ce3',1,'BNO08x']]], - ['menuconfig_17',['Menuconfig',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md4',1,'']]], - ['meta_5fdata_18',['meta_data',['../class_b_n_o08x.html#a7bd032712a975e73e66bd72a3502baba',1,'BNO08x']]], - ['mode_5fon_19',['mode_on',['../class_b_n_o08x.html#ac1b3de9b552c611ee9c455d7f19be698',1,'BNO08x']]], - ['mode_5fsleep_20',['mode_sleep',['../class_b_n_o08x.html#a176ae0112325c05105eacb4566bbfa0b',1,'BNO08x']]], - ['msg_5fbuff_21',['msg_buff',['../_callback_tests_8cpp.html#a4e7be0e1e700243053709d7544201596',1,'CallbackTests.cpp']]], - ['multireporttests_2ecpp_22',['MultiReportTests.cpp',['../_multi_report_tests_8cpp.html',1,'']]] -]; diff --git a/documentation/html/search/all_c.js b/documentation/html/search/all_c.js deleted file mode 100644 index e8a7418..0000000 --- a/documentation/html/search/all_c.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['new_5fdata_0',['new_data',['../_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876',1,'CallbackTests.cpp']]] -]; diff --git a/documentation/html/search/all_d.js b/documentation/html/search/all_d.js deleted file mode 100644 index d4defc3..0000000 --- a/documentation/html/search/all_d.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['on_5fbicycle_0',['ON_BICYCLE',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4',1,'ON_BICYCLE: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4',1,'ON_BICYCLE: BNO08x_global_types.hpp']]], - ['on_5ffoot_1',['ON_FOOT',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58',1,'ON_FOOT: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58',1,'ON_FOOT: BNO08x_global_types.hpp']]], - ['on_5fstairs_2',['ON_STAIRS',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515',1,'ON_STAIRS: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515',1,'ON_STAIRS: BNO08x_global_types.hpp']]], - ['on_5ftable_3',['ON_TABLE',['../_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a',1,'BNO08x_global_types.hpp']]], - ['other_4',['OTHER',['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/all_e.js b/documentation/html/search/all_e.js deleted file mode 100644 index 7eaf409..0000000 --- a/documentation/html/search/all_e.js +++ /dev/null @@ -1,51 +0,0 @@ -var searchData= -[ - ['parse_5fcommand_5freport_0',['parse_command_report',['../class_b_n_o08x.html#a4f66045a0528a0c17c52421ea51612e7',1,'BNO08x']]], - ['parse_5ffeature_5fget_5fresponse_5freport_1',['parse_feature_get_response_report',['../class_b_n_o08x.html#a206c0e3ddc3b745b56914976d6e69981',1,'BNO08x']]], - ['parse_5ffrs_5fread_5fresponse_5freport_2',['parse_frs_read_response_report',['../class_b_n_o08x.html#a51b360d795563b55559f11efb40be36a',1,'BNO08x']]], - ['parse_5ffrs_5fread_5fresponse_5freport_5fdata_5f1_3',['PARSE_FRS_READ_RESPONSE_REPORT_DATA_1',['../_b_n_o08x__macros_8hpp.html#ac70cde2db98355de4f0e56c8650556fe',1,'BNO08x_macros.hpp']]], - ['parse_5ffrs_5fread_5fresponse_5freport_5fdata_5f2_4',['PARSE_FRS_READ_RESPONSE_REPORT_DATA_2',['../_b_n_o08x__macros_8hpp.html#a2fcd254e9531069d6982795f575cb17a',1,'BNO08x_macros.hpp']]], - ['parse_5ffrs_5fread_5fresponse_5freport_5frecord_5fid_5',['PARSE_FRS_READ_RESPONSE_REPORT_RECORD_ID',['../_b_n_o08x__macros_8hpp.html#aa23c7c4d9748ce5551fcc0e5734e0a40',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5fintegrated_5frotation_5fvector_5freport_6',['parse_gyro_integrated_rotation_vector_report',['../class_b_n_o08x.html#a7be6047fef851a064c7cbc9eba092f6d',1,'BNO08x']]], - ['parse_5fgyro_5freport_5fraw_5fgyro_5fvel_5fx_7',['PARSE_GYRO_REPORT_RAW_GYRO_VEL_X',['../_b_n_o08x__macros_8hpp.html#a7aed5272074b2ee03da81b6fb7222813',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fgyro_5fvel_5fy_8',['PARSE_GYRO_REPORT_RAW_GYRO_VEL_Y',['../_b_n_o08x__macros_8hpp.html#a823d8c92faf40d07f5b0bb324f2a51bd',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fgyro_5fvel_5fz_9',['PARSE_GYRO_REPORT_RAW_GYRO_VEL_Z',['../_b_n_o08x__macros_8hpp.html#afcc41ef70ba1860c3178072e13ccf512',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fquat_5fi_10',['PARSE_GYRO_REPORT_RAW_QUAT_I',['../_b_n_o08x__macros_8hpp.html#a1f20ab3d051d5acb254e5a5e7b4505de',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fquat_5fj_11',['PARSE_GYRO_REPORT_RAW_QUAT_J',['../_b_n_o08x__macros_8hpp.html#afe721365113756a8b38a5db255f9d061',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fquat_5fk_12',['PARSE_GYRO_REPORT_RAW_QUAT_K',['../_b_n_o08x__macros_8hpp.html#a3ae7fd4e8febc54026e59e1ac544db84',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fquat_5freal_13',['PARSE_GYRO_REPORT_RAW_QUAT_REAL',['../_b_n_o08x__macros_8hpp.html#a73d50f6a746370f614161ee6b9b08424',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_14',['parse_input_report',['../class_b_n_o08x.html#a8d9db3e1b6208c2661e1c543deefa53d',1,'BNO08x']]], - ['parse_5finput_5freport_5fdata_15',['parse_input_report_data',['../class_b_n_o08x.html#a002aa97c9af8f6df2d0c83034e4f7b55',1,'BNO08x']]], - ['parse_5finput_5freport_5fdata_5f1_16',['PARSE_INPUT_REPORT_DATA_1',['../_b_n_o08x__macros_8hpp.html#a4664b5298e0059c173f71bb73a87d239',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fdata_5f2_17',['PARSE_INPUT_REPORT_DATA_2',['../_b_n_o08x__macros_8hpp.html#a455a8649345748be2d5f35036052f78a',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fdata_5f3_18',['PARSE_INPUT_REPORT_DATA_3',['../_b_n_o08x__macros_8hpp.html#a7d38fbfe154c526c822748fc812e7d52',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fdata_5f4_19',['PARSE_INPUT_REPORT_DATA_4',['../_b_n_o08x__macros_8hpp.html#a3d6971a39ce4858314247bdbbb754b33',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fdata_5f5_20',['PARSE_INPUT_REPORT_DATA_5',['../_b_n_o08x__macros_8hpp.html#afd61b5f28723a3f20874097b1bd46e1a',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fdata_5f6_21',['PARSE_INPUT_REPORT_DATA_6',['../_b_n_o08x__macros_8hpp.html#ae66870a6ac704d1ee582f4f7bd2ba6a7',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5freport_5fid_22',['PARSE_INPUT_REPORT_REPORT_ID',['../_b_n_o08x__macros_8hpp.html#a5be1d9a953a0657a4b8df88681b211bc',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fstatus_5fbits_23',['PARSE_INPUT_REPORT_STATUS_BITS',['../_b_n_o08x__macros_8hpp.html#ac4cad93c425c38fd5cd90d0982897611',1,'BNO08x_macros.hpp']]], - ['parse_5fpacket_24',['parse_packet',['../class_b_n_o08x.html#a1c47d27917ae3b2876efa121b803f924',1,'BNO08x']]], - ['parse_5fpacket_5flength_25',['PARSE_PACKET_LENGTH',['../_b_n_o08x__macros_8hpp.html#a432e15325e64ab36d5a3b30b65a71bf1',1,'BNO08x_macros.hpp']]], - ['parse_5fpacket_5ftimestamp_26',['PARSE_PACKET_TIMESTAMP',['../_b_n_o08x__macros_8hpp.html#afa3b6d75bbe499250e69043547a39208',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_27',['parse_product_id_report',['../class_b_n_o08x.html#a29cfd7fc2816483ebebe9d55b677a036',1,'BNO08x']]], - ['parse_5fproduct_5fid_5freport_5fproduct_5fid_28',['PARSE_PRODUCT_ID_REPORT_PRODUCT_ID',['../_b_n_o08x__macros_8hpp.html#a37c86278c2de384fe3b9304b8d2d3370',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5freset_5freason_29',['PARSE_PRODUCT_ID_REPORT_RESET_REASON',['../_b_n_o08x__macros_8hpp.html#a4c1a6f80fc6ab0ab5d6f803bc175b3e1',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5fsw_5fbuild_5fno_30',['PARSE_PRODUCT_ID_REPORT_SW_BUILD_NO',['../_b_n_o08x__macros_8hpp.html#a24ff2498d4883f329d70fb2a6f10e04a',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5fsw_5fpart_5fno_31',['PARSE_PRODUCT_ID_REPORT_SW_PART_NO',['../_b_n_o08x__macros_8hpp.html#a5e6be52a05421d50c4b3600c35868540',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5fsw_5fversion_5fmajor_32',['PARSE_PRODUCT_ID_REPORT_SW_VERSION_MAJOR',['../_b_n_o08x__macros_8hpp.html#af59b362a169fe8c11a0b679ca99383ee',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5fsw_5fversion_5fminor_33',['PARSE_PRODUCT_ID_REPORT_SW_VERSION_MINOR',['../_b_n_o08x__macros_8hpp.html#ad9773ac824ab751df0e331a7c16080a1',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5fsw_5fversion_5fpatch_34',['PARSE_PRODUCT_ID_REPORT_SW_VERSION_PATCH',['../_b_n_o08x__macros_8hpp.html#a23baa3c8a71f3b3021f135bef27a8ed9',1,'BNO08x_macros.hpp']]], - ['period_35',['period',['../struct_b_n_o08x_1_1bno08x__report__period__tracker__t.html#a7fe1403bb26f5f4dd845df019bac8614',1,'BNO08x::bno08x_report_period_tracker_t']]], - ['polling_20example_36',['Polling Example',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md6',1,'']]], - ['por_37',['POR',['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92',1,'BNO08x_global_types.hpp']]], - ['prev_5freport_5fdata_38',['prev_report_data',['../_callback_tests_8cpp.html#a8c57d66969fed0b55bdee9b57f6ed0a7',1,'CallbackTests.cpp']]], - ['print_5fbegin_5ftests_5fbanner_39',['print_begin_tests_banner',['../class_b_n_o08x_test_suite.html#a2fea3ea192a63c9573c774e772f5c085',1,'BNO08xTestSuite']]], - ['print_5fend_5ftests_5fbanner_40',['print_end_tests_banner',['../class_b_n_o08x_test_suite.html#a5a9b6538773911afed92b16c435ebceb',1,'BNO08xTestSuite']]], - ['print_5fheader_41',['print_header',['../class_b_n_o08x.html#a35856c108a47de8b3b38c4395aabb4eb',1,'BNO08x']]], - ['print_5fpacket_42',['print_packet',['../class_b_n_o08x.html#a05e4cd5861b55fc0182d7dd13bb85e49',1,'BNO08x']]], - ['print_5ftest_5fend_5fbanner_43',['print_test_end_banner',['../class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919',1,'BNO08xTestHelper']]], - ['print_5ftest_5fmsg_44',['print_test_msg',['../class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002',1,'BNO08xTestHelper']]], - ['print_5ftest_5fstart_5fbanner_45',['print_test_start_banner',['../class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885',1,'BNO08xTestHelper']]], - ['program_20flowcharts_46',['Program Flowcharts',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md12',1,'']]], - ['project_47',['Adding to Project',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html#autotoc_md3',1,'']]] -]; diff --git a/documentation/html/search/all_f.js b/documentation/html/search/all_f.js deleted file mode 100644 index c2768ea..0000000 --- a/documentation/html/search/all_f.js +++ /dev/null @@ -1,20 +0,0 @@ -var searchData= -[ - ['q_5fto_5ffloat_0',['q_to_float',['../class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9',1,'BNO08x']]], - ['quat_5faccuracy_1',['quat_accuracy',['../class_b_n_o08x.html#a36223f7124751fa71e860b2ef55dd2ac',1,'BNO08x::quat_accuracy'],['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#aac84ad10b65403ae1ee21dab5cdc77db',1,'BNO08xTestHelper::imu_report_data_t::quat_accuracy']]], - ['quat_5fi_2',['quat_I',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8d2c3cd33943cb1b4fd0e800f822607e',1,'BNO08xTestHelper::imu_report_data_t']]], - ['quat_5fj_3',['quat_J',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a20a09d197d5128aae64b7449df576c27',1,'BNO08xTestHelper::imu_report_data_t']]], - ['quat_5fk_4',['quat_K',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3c74d4c93fc4390f52b75e6ff2bea95b',1,'BNO08xTestHelper::imu_report_data_t']]], - ['quat_5fradian_5faccuracy_5',['quat_radian_accuracy',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae0a8fef0227dd4304d08466c43d901a5',1,'BNO08xTestHelper::imu_report_data_t']]], - ['quat_5freal_6',['quat_real',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a80525c4943154f825a62539b10337976',1,'BNO08xTestHelper::imu_report_data_t']]], - ['queue_5fcalibrate_5fcommand_7',['queue_calibrate_command',['../class_b_n_o08x.html#ad097849616c5caab1fd3eb3632ee2b91',1,'BNO08x']]], - ['queue_5fcommand_8',['queue_command',['../class_b_n_o08x.html#a5cc58139e4d5f0587b90e249ceb476f9',1,'BNO08x']]], - ['queue_5ffeature_5fcommand_9',['queue_feature_command',['../class_b_n_o08x.html#af7f960dbd26c6f1834661ef5f5bbd4d3',1,'BNO08x']]], - ['queue_5ffrs_5fread_5fdata_10',['queue_frs_read_data',['../class_b_n_o08x.html#a9a1c851e8fa5633e11f6abee293d7e9b',1,'BNO08x']]], - ['queue_5fpacket_11',['queue_packet',['../class_b_n_o08x.html#a62c570ba96512f4d0d10b2594048de1f',1,'BNO08x']]], - ['queue_5frequest_5fproduct_5fid_5fcommand_12',['queue_request_product_id_command',['../class_b_n_o08x.html#ab5f200069a2f8cb74cb79c6f162da5a1',1,'BNO08x']]], - ['queue_5freset_5freason_13',['queue_reset_reason',['../class_b_n_o08x.html#a84b3639cc159262e0137adb0db5cf9aa',1,'BNO08x']]], - ['queue_5frx_5fdata_14',['queue_rx_data',['../class_b_n_o08x.html#a7d4661d3aae56013caa8f2bff0f67c08',1,'BNO08x']]], - ['queue_5ftare_5fcommand_15',['queue_tare_command',['../class_b_n_o08x.html#a4c6353e795f734ed28613f9a3d161ea2',1,'BNO08x']]], - ['queue_5ftx_5fdata_16',['queue_tx_data',['../class_b_n_o08x.html#a4d5c5eee87a578de9c8318cd294b3a22',1,'BNO08x']]] -]; diff --git a/documentation/html/search/classes_0.js b/documentation/html/search/classes_0.js deleted file mode 100644 index 4d5f64f..0000000 --- a/documentation/html/search/classes_0.js +++ /dev/null @@ -1,11 +0,0 @@ -var searchData= -[ - ['bno08x_0',['BNO08x',['../class_b_n_o08x.html',1,'']]], - ['bno08x_5fconfig_5ft_1',['bno08x_config_t',['../structbno08x__config__t.html',1,'']]], - ['bno08x_5finit_5fstatus_5ft_2',['bno08x_init_status_t',['../struct_b_n_o08x_1_1bno08x__init__status__t.html',1,'BNO08x']]], - ['bno08x_5freport_5fperiod_5ftracker_5ft_3',['bno08x_report_period_tracker_t',['../struct_b_n_o08x_1_1bno08x__report__period__tracker__t.html',1,'BNO08x']]], - ['bno08x_5frx_5fpacket_5ft_4',['bno08x_rx_packet_t',['../struct_b_n_o08x_1_1bno08x__rx__packet__t.html',1,'BNO08x']]], - ['bno08x_5ftx_5fpacket_5ft_5',['bno08x_tx_packet_t',['../struct_b_n_o08x_1_1bno08x__tx__packet__t.html',1,'BNO08x']]], - ['bno08xtesthelper_6',['BNO08xTestHelper',['../class_b_n_o08x_test_helper.html',1,'']]], - ['bno08xtestsuite_7',['BNO08xTestSuite',['../class_b_n_o08x_test_suite.html',1,'']]] -]; diff --git a/documentation/html/search/classes_1.js b/documentation/html/search/classes_1.js deleted file mode 100644 index b46bfd9..0000000 --- a/documentation/html/search/classes_1.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['imu_5freport_5fdata_5ft_0',['imu_report_data_t',['../struct_b_n_o08x_test_helper_1_1imu__report__data__t.html',1,'BNO08xTestHelper']]] -]; diff --git a/documentation/html/search/close.svg b/documentation/html/search/close.svg deleted file mode 100644 index 337d6cc..0000000 --- a/documentation/html/search/close.svg +++ /dev/null @@ -1,18 +0,0 @@ - - - - - - diff --git a/documentation/html/search/defines_0.js b/documentation/html/search/defines_0.js deleted file mode 100644 index 1f6f68e..0000000 --- a/documentation/html/search/defines_0.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['check_5ftasks_5frunning_0',['CHECK_TASKS_RUNNING',['../_b_n_o08x__macros_8hpp.html#a59dd17f0673fdd60f6a65bba104a6f80',1,'BNO08x_macros.hpp']]] -]; diff --git a/documentation/html/search/defines_1.js b/documentation/html/search/defines_1.js deleted file mode 100644 index 02f96db..0000000 --- a/documentation/html/search/defines_1.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['is_5frotation_5fvector_5freport_0',['IS_ROTATION_VECTOR_REPORT',['../_b_n_o08x__macros_8hpp.html#a84602d112b6000375ad608904de5b0e3',1,'BNO08x_macros.hpp']]] -]; diff --git a/documentation/html/search/defines_2.js b/documentation/html/search/defines_2.js deleted file mode 100644 index dc214e4..0000000 --- a/documentation/html/search/defines_2.js +++ /dev/null @@ -1,30 +0,0 @@ -var searchData= -[ - ['parse_5ffrs_5fread_5fresponse_5freport_5fdata_5f1_0',['PARSE_FRS_READ_RESPONSE_REPORT_DATA_1',['../_b_n_o08x__macros_8hpp.html#ac70cde2db98355de4f0e56c8650556fe',1,'BNO08x_macros.hpp']]], - ['parse_5ffrs_5fread_5fresponse_5freport_5fdata_5f2_1',['PARSE_FRS_READ_RESPONSE_REPORT_DATA_2',['../_b_n_o08x__macros_8hpp.html#a2fcd254e9531069d6982795f575cb17a',1,'BNO08x_macros.hpp']]], - ['parse_5ffrs_5fread_5fresponse_5freport_5frecord_5fid_2',['PARSE_FRS_READ_RESPONSE_REPORT_RECORD_ID',['../_b_n_o08x__macros_8hpp.html#aa23c7c4d9748ce5551fcc0e5734e0a40',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fgyro_5fvel_5fx_3',['PARSE_GYRO_REPORT_RAW_GYRO_VEL_X',['../_b_n_o08x__macros_8hpp.html#a7aed5272074b2ee03da81b6fb7222813',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fgyro_5fvel_5fy_4',['PARSE_GYRO_REPORT_RAW_GYRO_VEL_Y',['../_b_n_o08x__macros_8hpp.html#a823d8c92faf40d07f5b0bb324f2a51bd',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fgyro_5fvel_5fz_5',['PARSE_GYRO_REPORT_RAW_GYRO_VEL_Z',['../_b_n_o08x__macros_8hpp.html#afcc41ef70ba1860c3178072e13ccf512',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fquat_5fi_6',['PARSE_GYRO_REPORT_RAW_QUAT_I',['../_b_n_o08x__macros_8hpp.html#a1f20ab3d051d5acb254e5a5e7b4505de',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fquat_5fj_7',['PARSE_GYRO_REPORT_RAW_QUAT_J',['../_b_n_o08x__macros_8hpp.html#afe721365113756a8b38a5db255f9d061',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fquat_5fk_8',['PARSE_GYRO_REPORT_RAW_QUAT_K',['../_b_n_o08x__macros_8hpp.html#a3ae7fd4e8febc54026e59e1ac544db84',1,'BNO08x_macros.hpp']]], - ['parse_5fgyro_5freport_5fraw_5fquat_5freal_9',['PARSE_GYRO_REPORT_RAW_QUAT_REAL',['../_b_n_o08x__macros_8hpp.html#a73d50f6a746370f614161ee6b9b08424',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fdata_5f1_10',['PARSE_INPUT_REPORT_DATA_1',['../_b_n_o08x__macros_8hpp.html#a4664b5298e0059c173f71bb73a87d239',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fdata_5f2_11',['PARSE_INPUT_REPORT_DATA_2',['../_b_n_o08x__macros_8hpp.html#a455a8649345748be2d5f35036052f78a',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fdata_5f3_12',['PARSE_INPUT_REPORT_DATA_3',['../_b_n_o08x__macros_8hpp.html#a7d38fbfe154c526c822748fc812e7d52',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fdata_5f4_13',['PARSE_INPUT_REPORT_DATA_4',['../_b_n_o08x__macros_8hpp.html#a3d6971a39ce4858314247bdbbb754b33',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fdata_5f5_14',['PARSE_INPUT_REPORT_DATA_5',['../_b_n_o08x__macros_8hpp.html#afd61b5f28723a3f20874097b1bd46e1a',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fdata_5f6_15',['PARSE_INPUT_REPORT_DATA_6',['../_b_n_o08x__macros_8hpp.html#ae66870a6ac704d1ee582f4f7bd2ba6a7',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5freport_5fid_16',['PARSE_INPUT_REPORT_REPORT_ID',['../_b_n_o08x__macros_8hpp.html#a5be1d9a953a0657a4b8df88681b211bc',1,'BNO08x_macros.hpp']]], - ['parse_5finput_5freport_5fstatus_5fbits_17',['PARSE_INPUT_REPORT_STATUS_BITS',['../_b_n_o08x__macros_8hpp.html#ac4cad93c425c38fd5cd90d0982897611',1,'BNO08x_macros.hpp']]], - ['parse_5fpacket_5flength_18',['PARSE_PACKET_LENGTH',['../_b_n_o08x__macros_8hpp.html#a432e15325e64ab36d5a3b30b65a71bf1',1,'BNO08x_macros.hpp']]], - ['parse_5fpacket_5ftimestamp_19',['PARSE_PACKET_TIMESTAMP',['../_b_n_o08x__macros_8hpp.html#afa3b6d75bbe499250e69043547a39208',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5fproduct_5fid_20',['PARSE_PRODUCT_ID_REPORT_PRODUCT_ID',['../_b_n_o08x__macros_8hpp.html#a37c86278c2de384fe3b9304b8d2d3370',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5freset_5freason_21',['PARSE_PRODUCT_ID_REPORT_RESET_REASON',['../_b_n_o08x__macros_8hpp.html#a4c1a6f80fc6ab0ab5d6f803bc175b3e1',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5fsw_5fbuild_5fno_22',['PARSE_PRODUCT_ID_REPORT_SW_BUILD_NO',['../_b_n_o08x__macros_8hpp.html#a24ff2498d4883f329d70fb2a6f10e04a',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5fsw_5fpart_5fno_23',['PARSE_PRODUCT_ID_REPORT_SW_PART_NO',['../_b_n_o08x__macros_8hpp.html#a5e6be52a05421d50c4b3600c35868540',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5fsw_5fversion_5fmajor_24',['PARSE_PRODUCT_ID_REPORT_SW_VERSION_MAJOR',['../_b_n_o08x__macros_8hpp.html#af59b362a169fe8c11a0b679ca99383ee',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5fsw_5fversion_5fminor_25',['PARSE_PRODUCT_ID_REPORT_SW_VERSION_MINOR',['../_b_n_o08x__macros_8hpp.html#ad9773ac824ab751df0e331a7c16080a1',1,'BNO08x_macros.hpp']]], - ['parse_5fproduct_5fid_5freport_5fsw_5fversion_5fpatch_26',['PARSE_PRODUCT_ID_REPORT_SW_VERSION_PATCH',['../_b_n_o08x__macros_8hpp.html#a23baa3c8a71f3b3021f135bef27a8ed9',1,'BNO08x_macros.hpp']]] -]; diff --git a/documentation/html/search/defines_3.js b/documentation/html/search/defines_3.js deleted file mode 100644 index 287721e..0000000 --- a/documentation/html/search/defines_3.js +++ /dev/null @@ -1,7 +0,0 @@ -var searchData= -[ - ['uint16_5fclr_5flsb_0',['UINT16_CLR_LSB',['../_b_n_o08x__macros_8hpp.html#ac89a0ae0c3d3067f02e9fa275521606b',1,'BNO08x_macros.hpp']]], - ['uint16_5fclr_5fmsb_1',['UINT16_CLR_MSB',['../_b_n_o08x__macros_8hpp.html#ad98f2fa811436866ff297a8288e34f40',1,'BNO08x_macros.hpp']]], - ['uint32_5fclr_5fbyte_2',['UINT32_CLR_BYTE',['../_b_n_o08x__macros_8hpp.html#a7de5c0b84ba545981105e1216925d8e9',1,'BNO08x_macros.hpp']]], - ['uint32_5fmsk_5fbyte_3',['UINT32_MSK_BYTE',['../_b_n_o08x__macros_8hpp.html#a6f459cc2cce1722c63d22a9556f06bc8',1,'BNO08x_macros.hpp']]] -]; diff --git a/documentation/html/search/enums_0.js b/documentation/html/search/enums_0.js deleted file mode 100644 index 3287c8b..0000000 --- a/documentation/html/search/enums_0.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['bno08xaccuracy_0',['BNO08xAccuracy',['../_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0',1,'BNO08x_global_types.hpp']]], - ['bno08xactivity_1',['BNO08xActivity',['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187',1,'BNO08x_global_types.hpp']]], - ['bno08xactivityenable_2',['BNO08xActivityEnable',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0f',1,'BNO08x_global_types.hpp']]], - ['bno08xresetreason_3',['BNO08xResetReason',['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147',1,'BNO08x_global_types.hpp']]], - ['bno08xstability_4',['BNO08xStability',['../_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enums_1.js b/documentation/html/search/enums_1.js deleted file mode 100644 index dfa7bf6..0000000 --- a/documentation/html/search/enums_1.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['channels_5ft_0',['channels_t',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638f',1,'BNO08x']]] -]; diff --git a/documentation/html/search/enumvalues_0.js b/documentation/html/search/enumvalues_0.js deleted file mode 100644 index dd8de93..0000000 --- a/documentation/html/search/enumvalues_0.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['all_0',['ALL',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enumvalues_1.js b/documentation/html/search/enumvalues_1.js deleted file mode 100644 index eb6b12a..0000000 --- a/documentation/html/search/enumvalues_1.js +++ /dev/null @@ -1,9 +0,0 @@ -var searchData= -[ - ['channel_5fcommand_0',['CHANNEL_COMMAND',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fad116268ebf7fb5e5cb4795ccc27867ed',1,'BNO08x']]], - ['channel_5fcontrol_1',['CHANNEL_CONTROL',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fa5b5d133bf4a91e14741fdd8e635e897e',1,'BNO08x']]], - ['channel_5fexecutable_2',['CHANNEL_EXECUTABLE',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fab1f28434b161c7ffa7b1a5c5f1a8a95b',1,'BNO08x']]], - ['channel_5fgyro_3',['CHANNEL_GYRO',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fadd3caa696e525dd901de7a8e3dbf0731',1,'BNO08x']]], - ['channel_5freports_4',['CHANNEL_REPORTS',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638fabeb0a4983bc57ad2ce9f98360742e03e',1,'BNO08x']]], - ['channel_5fwake_5freports_5',['CHANNEL_WAKE_REPORTS',['../class_b_n_o08x.html#ac14e319f54399031ed30cd24ad1c638faefb874de7f2f90fb99b42bedf9623d21',1,'BNO08x']]] -]; diff --git a/documentation/html/search/enumvalues_2.js b/documentation/html/search/enumvalues_2.js deleted file mode 100644 index 1d5abdd..0000000 --- a/documentation/html/search/enumvalues_2.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['ext_5frst_0',['EXT_RST',['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enumvalues_3.js b/documentation/html/search/enumvalues_3.js deleted file mode 100644 index 7668529..0000000 --- a/documentation/html/search/enumvalues_3.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['high_0',['HIGH',['../_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enumvalues_4.js b/documentation/html/search/enumvalues_4.js deleted file mode 100644 index d55a7b2..0000000 --- a/documentation/html/search/enumvalues_4.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['in_5fvehicle_0',['IN_VEHICLE',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4',1,'IN_VEHICLE: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4',1,'IN_VEHICLE: BNO08x_global_types.hpp']]], - ['int_5frst_1',['INT_RST',['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enumvalues_5.js b/documentation/html/search/enumvalues_5.js deleted file mode 100644 index be872f6..0000000 --- a/documentation/html/search/enumvalues_5.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['low_0',['LOW',['../_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enumvalues_6.js b/documentation/html/search/enumvalues_6.js deleted file mode 100644 index 97dac9c..0000000 --- a/documentation/html/search/enumvalues_6.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['med_0',['MED',['../_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enumvalues_7.js b/documentation/html/search/enumvalues_7.js deleted file mode 100644 index d4defc3..0000000 --- a/documentation/html/search/enumvalues_7.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['on_5fbicycle_0',['ON_BICYCLE',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4',1,'ON_BICYCLE: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4',1,'ON_BICYCLE: BNO08x_global_types.hpp']]], - ['on_5ffoot_1',['ON_FOOT',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58',1,'ON_FOOT: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58',1,'ON_FOOT: BNO08x_global_types.hpp']]], - ['on_5fstairs_2',['ON_STAIRS',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515',1,'ON_STAIRS: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515',1,'ON_STAIRS: BNO08x_global_types.hpp']]], - ['on_5ftable_3',['ON_TABLE',['../_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a',1,'BNO08x_global_types.hpp']]], - ['other_4',['OTHER',['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enumvalues_8.js b/documentation/html/search/enumvalues_8.js deleted file mode 100644 index 9ecdf40..0000000 --- a/documentation/html/search/enumvalues_8.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['por_0',['POR',['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enumvalues_9.js b/documentation/html/search/enumvalues_9.js deleted file mode 100644 index 3092923..0000000 --- a/documentation/html/search/enumvalues_9.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['running_0',['RUNNING',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd',1,'RUNNING: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd',1,'RUNNING: BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enumvalues_a.js b/documentation/html/search/enumvalues_a.js deleted file mode 100644 index d11d027..0000000 --- a/documentation/html/search/enumvalues_a.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['stationary_0',['STATIONARY',['../_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146',1,'BNO08x_global_types.hpp']]], - ['still_1',['STILL',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6',1,'STILL: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6',1,'STILL: BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enumvalues_b.js b/documentation/html/search/enumvalues_b.js deleted file mode 100644 index 2d2108d..0000000 --- a/documentation/html/search/enumvalues_b.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['tilting_0',['TILTING',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c',1,'TILTING: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c',1,'TILTING: BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enumvalues_c.js b/documentation/html/search/enumvalues_c.js deleted file mode 100644 index 8670534..0000000 --- a/documentation/html/search/enumvalues_c.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['undefined_0',['UNDEFINED',['../_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3',1,'UNDEFINED: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a0db45d2a4141101bdfe48e3314cfbca3',1,'UNDEFINED: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3',1,'UNDEFINED: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3',1,'UNDEFINED: BNO08x_global_types.hpp']]], - ['unknown_1',['UNKNOWN',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3',1,'UNKNOWN: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3',1,'UNKNOWN: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3',1,'UNKNOWN: BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/enumvalues_d.js b/documentation/html/search/enumvalues_d.js deleted file mode 100644 index f7c9663..0000000 --- a/documentation/html/search/enumvalues_d.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['walking_0',['WALKING',['../_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3',1,'WALKING: BNO08x_global_types.hpp'],['../_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3',1,'WALKING: BNO08x_global_types.hpp']]], - ['wtd_1',['WTD',['../_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36',1,'BNO08x_global_types.hpp']]] -]; diff --git a/documentation/html/search/files_0.js b/documentation/html/search/files_0.js deleted file mode 100644 index 792d4d3..0000000 --- a/documentation/html/search/files_0.js +++ /dev/null @@ -1,9 +0,0 @@ -var searchData= -[ - ['bno08x_2ecpp_0',['BNO08x.cpp',['../_b_n_o08x_8cpp.html',1,'']]], - ['bno08x_2ehpp_1',['BNO08x.hpp',['../_b_n_o08x_8hpp.html',1,'']]], - ['bno08x_5fglobal_5ftypes_2ehpp_2',['BNO08x_global_types.hpp',['../_b_n_o08x__global__types_8hpp.html',1,'']]], - ['bno08x_5fmacros_2ehpp_3',['BNO08x_macros.hpp',['../_b_n_o08x__macros_8hpp.html',1,'']]], - ['bno08xtesthelper_2ehpp_4',['BNO08xTestHelper.hpp',['../_b_n_o08x_test_helper_8hpp.html',1,'']]], - ['bno08xtestsuite_2ehpp_5',['BNO08xTestSuite.hpp',['../_b_n_o08x_test_suite_8hpp.html',1,'']]] -]; diff --git a/documentation/html/search/files_1.js b/documentation/html/search/files_1.js deleted file mode 100644 index 6e877df..0000000 --- a/documentation/html/search/files_1.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['callbacktests_2ecpp_0',['CallbackTests.cpp',['../_callback_tests_8cpp.html',1,'']]] -]; diff --git a/documentation/html/search/files_2.js b/documentation/html/search/files_2.js deleted file mode 100644 index af77718..0000000 --- a/documentation/html/search/files_2.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['initdeinittests_2ecpp_0',['InitDeinitTests.cpp',['../_init_deinit_tests_8cpp.html',1,'']]] -]; diff --git a/documentation/html/search/files_3.js b/documentation/html/search/files_3.js deleted file mode 100644 index 3b4c59a..0000000 --- a/documentation/html/search/files_3.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['multireporttests_2ecpp_0',['MultiReportTests.cpp',['../_multi_report_tests_8cpp.html',1,'']]] -]; diff --git a/documentation/html/search/files_4.js b/documentation/html/search/files_4.js deleted file mode 100644 index 4accdc1..0000000 --- a/documentation/html/search/files_4.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['readme_2emd_0',['README.md',['../_r_e_a_d_m_e_8md.html',1,'']]] -]; diff --git a/documentation/html/search/files_5.js b/documentation/html/search/files_5.js deleted file mode 100644 index a4a37b5..0000000 --- a/documentation/html/search/files_5.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['singlereporttests_2ecpp_0',['SingleReportTests.cpp',['../_single_report_tests_8cpp.html',1,'']]] -]; diff --git a/documentation/html/search/functions_0.js b/documentation/html/search/functions_0.js deleted file mode 100644 index 5252251..0000000 --- a/documentation/html/search/functions_0.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['accelerometer_5fdata_5fis_5fnew_0',['accelerometer_data_is_new',['../class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea',1,'BNO08xTestHelper']]], - ['activity_5fclassifier_5fdata_5fis_5fnew_1',['activity_classifier_data_is_new',['../class_b_n_o08x_test_helper.html#afc6cc734ad843aca30a7cb76ad6dedb9',1,'BNO08xTestHelper']]] -]; diff --git a/documentation/html/search/functions_1.js b/documentation/html/search/functions_1.js deleted file mode 100644 index 220ec5b..0000000 --- a/documentation/html/search/functions_1.js +++ /dev/null @@ -1,9 +0,0 @@ -var searchData= -[ - ['bno08x_0',['BNO08x',['../class_b_n_o08x.html#ad12fb6cf310ad7a04a4e53809833bd61',1,'BNO08x']]], - ['bno08x_5fconfig_5ft_1',['bno08x_config_t',['../structbno08x__config__t.html#a68e051212415a62e64c23678e7b40552',1,'bno08x_config_t::bno08x_config_t(bool install_isr_service=true)'],['../structbno08x__config__t.html#a3a4ef8ef437403592278110a73cafe70',1,'bno08x_config_t::bno08x_config_t(spi_host_device_t spi_peripheral, gpio_num_t io_mosi, gpio_num_t io_miso, gpio_num_t io_sclk, gpio_num_t io_cs, gpio_num_t io_int, gpio_num_t io_rst, gpio_num_t io_wake, uint32_t sclk_speed, bool install_isr_service=true)']]], - ['bno08x_5finit_5fstatus_5ft_2',['bno08x_init_status_t',['../struct_b_n_o08x_1_1bno08x__init__status__t.html#a26db0bb1cf4ad4272a363c9995cc6851',1,'BNO08x::bno08x_init_status_t']]], - ['bno08xaccuracy_5fto_5fstr_3',['BNO08xAccuracy_to_str',['../class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3',1,'BNO08xTestHelper']]], - ['bno08xactivity_5fto_5fstr_4',['BNO08xActivity_to_str',['../class_b_n_o08x_test_helper.html#ac95ba2892d54e6219123ad3ca0104750',1,'BNO08xTestHelper']]], - ['bno08xstability_5fto_5fstr_5',['BNO08xStability_to_str',['../class_b_n_o08x_test_helper.html#ae922f36719ab085550ef270d5a149059',1,'BNO08xTestHelper']]] -]; diff --git a/documentation/html/search/functions_10.js b/documentation/html/search/functions_10.js deleted file mode 100644 index e42a0de..0000000 --- a/documentation/html/search/functions_10.js +++ /dev/null @@ -1,6 +0,0 @@ -var searchData= -[ - ['tare_5fnow_0',['tare_now',['../class_b_n_o08x.html#a4549bbef48208bd9c745fc755b93012f',1,'BNO08x']]], - ['test_5fassert_5fequal_1',['TEST_ASSERT_EQUAL',['../_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3',1,'TEST_ASSERT_EQUAL(true, new_data[0]): CallbackTests.cpp'],['../_callback_tests_8cpp.html#aa6754207db4cfba956441680c7a6a97d',1,'TEST_ASSERT_EQUAL(true, new_data[1]): CallbackTests.cpp']]], - ['test_5fcase_2',['TEST_CASE',['../_callback_tests_8cpp.html#ac18b9cb122499f587331d82a538f23aa',1,'TEST_CASE("BNO08x Driver Creation for [CallbackTests] Tests", "[CallbackTests]"): CallbackTests.cpp'],['../_callback_tests_8cpp.html#a574f179a8295301510bc8b5475f02ba8',1,'TEST_CASE("BNO08x Driver Cleanup for [CallbackTests] Tests", "[CallbackTests]"): CallbackTests.cpp'],['../_init_deinit_tests_8cpp.html#a6ed5310154fb7e7f290e619e6fbed708',1,'TEST_CASE("Init Config Args", "[InitComprehensive]"): InitDeinitTests.cpp'],['../_init_deinit_tests_8cpp.html#a96d79e5c8f3096a207d806be926af15b',1,'TEST_CASE("Init GPIO", "[InitComprehensive]"): InitDeinitTests.cpp'],['../_init_deinit_tests_8cpp.html#ab8015ecd4179bc39223921d6eef1165a',1,'TEST_CASE("Init HINT ISR", "[InitComprehensive]"): InitDeinitTests.cpp'],['../_init_deinit_tests_8cpp.html#ad71fea7e4a2e587d48d2bf7fadd711cc',1,'TEST_CASE("Init SPI", "[InitComprehensive]"): InitDeinitTests.cpp'],['../_init_deinit_tests_8cpp.html#a9f7d58c894a252a5d5f4926f43c1da05',1,'TEST_CASE("InitComprehensive Tasks", "[InitComprehensive]"): InitDeinitTests.cpp'],['../_init_deinit_tests_8cpp.html#a69680e2934e7ec3c6a1771270dc59f05',1,'TEST_CASE("Finish Init", "[InitComprehensive]"): InitDeinitTests.cpp'],['../_init_deinit_tests_8cpp.html#ac4fb371054271d54830b58cc164dc0f6',1,'TEST_CASE("Init & Deinit", "[InitDenit]"): InitDeinitTests.cpp'],['../_multi_report_tests_8cpp.html#a1fd7b6a0d4dbb7f91fd5691b5b054bda',1,'TEST_CASE("BNO08x Driver Creation for [MultiReportEnableDisable] Tests", "[MultiReportEnableDisable]"): MultiReportTests.cpp'],['../_multi_report_tests_8cpp.html#aa9e0389fa75046b52d13286af2c3b2a7',1,'TEST_CASE("Dual Report Enable/Disable", "[MultiReportEnableDisable]"): MultiReportTests.cpp'],['../_multi_report_tests_8cpp.html#a915d6c272bf95057a8bb22abfb307882',1,'TEST_CASE("Tri Report Enable/Disable", "[MultiReportEnableDisable]"): MultiReportTests.cpp'],['../_multi_report_tests_8cpp.html#a1438f6b8587b635b6096dda2927fa9a1',1,'TEST_CASE("Quad Report Enable/Disable", "[MultiReportEnableDisable]"): MultiReportTests.cpp'],['../_multi_report_tests_8cpp.html#ad96cfd7c30e8693897688ce24bb53996',1,'TEST_CASE("Hex Report Enable", "[MultiReportEnableDisable]"): MultiReportTests.cpp'],['../_multi_report_tests_8cpp.html#ac92ec06fe64f7bedbbe37dee3e64c090',1,'TEST_CASE("BNO08x Driver Cleanup for [MultiReportEnableDisable] Tests", "[MultiReportEnableDisable]"): MultiReportTests.cpp'],['../_single_report_tests_8cpp.html#aac644123799c1f836d379c9789a064ab',1,'TEST_CASE("BNO08x Driver Creation for [SingleReportEnableDisable] Tests", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#af30c5c1549bda77b45a1e6fb5f76844a',1,'TEST_CASE("Enable Incorrect Report", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#ae436161f7f0085f01ce63d9373944ae8',1,'TEST_CASE("Enable/Disable Rotation Vector", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a90980a9fc26b3a692ab2529c9f8e4747',1,'TEST_CASE("Enable/Disable Game Rotation Vector", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#af9d07441bd8651bc21743664b7f99bb8',1,'TEST_CASE("Enable/Disable ARVR Stabilized Rotation Vector", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a35b0417a053d9fbf61a91a2110c3495c',1,'TEST_CASE("Enable/Disable ARVR Stabilized Game Rotation Vector", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a713376354af2a970230882e2a487050e',1,'TEST_CASE("Enable/Disable Gyro Integrated Rotation Vector", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a3cce613b379b768244a176a32b37667c',1,'TEST_CASE("Enable/Disable Uncalibrated Gyro", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#ace1544ccc126d0b9eadd433f9cb41486',1,'TEST_CASE("Enable/Disable Calibrated Gyro", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#aaefa1a1d4b3c190b7f46bb7f42512949',1,'TEST_CASE("Enable/Disable Accelerometer", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#ae4d70e11995e36808b6390b171aba0e8',1,'TEST_CASE("Enable/Disable Linear Accelerometer", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#ab9b4ae43e33572d90c4c889452cd91ee',1,'TEST_CASE("Enable/Disable Gravity", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a429f6e7897a9609ddd093d66b6f7b1ff',1,'TEST_CASE("Enable/Disable Magnetometer", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a9f2e049a5b61721869c5f4757e313502',1,'TEST_CASE("Enable/Disable Step Counter", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#acf249e215fca056266de6e833875925e',1,'TEST_CASE("Enable/Disable Stability Classifier", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a098111e0f361615318674b5b1b05ece4',1,'TEST_CASE("Enable/Disable Activity Classifier", "[SingleReportEnableDisable]"): SingleReportTests.cpp'],['../_single_report_tests_8cpp.html#a697ac897c8756d7553854e52229d36f5',1,'TEST_CASE("BNO08x Driver Cleanup for [SingleReportEnableDisable] Tests", "[SingleReportEnableDisable]"): SingleReportTests.cpp']]] -]; diff --git a/documentation/html/search/functions_11.js b/documentation/html/search/functions_11.js deleted file mode 100644 index b7f05f5..0000000 --- a/documentation/html/search/functions_11.js +++ /dev/null @@ -1,22 +0,0 @@ -var searchData= -[ - ['uncalibrated_5fgyro_5fdata_5fis_5fnew_0',['uncalibrated_gyro_data_is_new',['../class_b_n_o08x_test_helper.html#adb5952b2b96b553024b6a841e30adad2',1,'BNO08xTestHelper']]], - ['update_5faccelerometer_5fdata_1',['update_accelerometer_data',['../class_b_n_o08x.html#afe588fbd0055193d3bc08984d7732354',1,'BNO08x']]], - ['update_5fcalibrated_5fgyro_5fdata_2',['update_calibrated_gyro_data',['../class_b_n_o08x.html#a962b695ef4733d558c6f9684da0931ab',1,'BNO08x']]], - ['update_5fcommand_5fdata_3',['update_command_data',['../class_b_n_o08x.html#af971d82426740e62c1f05adcd2c9ce7c',1,'BNO08x']]], - ['update_5fgravity_5fdata_4',['update_gravity_data',['../class_b_n_o08x.html#ad7de3999d4df19038e27c01f9b02010e',1,'BNO08x']]], - ['update_5fintegrated_5fgyro_5frotation_5fvector_5fdata_5',['update_integrated_gyro_rotation_vector_data',['../class_b_n_o08x.html#ab02386f13caa446bab5921c1a71f92ab',1,'BNO08x']]], - ['update_5flin_5faccelerometer_5fdata_6',['update_lin_accelerometer_data',['../class_b_n_o08x.html#a7416d844f6188c8d16f181d6d4431708',1,'BNO08x']]], - ['update_5fmagf_5fdata_7',['update_magf_data',['../class_b_n_o08x.html#a3abf4a199bc7a03ac7447c2781673d88',1,'BNO08x']]], - ['update_5fpersonal_5factivity_5fclassifier_5fdata_8',['update_personal_activity_classifier_data',['../class_b_n_o08x.html#a04489cf9a125495c7cf07c6ba5e9f6c0',1,'BNO08x']]], - ['update_5fraw_5faccelerometer_5fdata_9',['update_raw_accelerometer_data',['../class_b_n_o08x.html#a83fed63c67957ec4338afd43087d6e22',1,'BNO08x']]], - ['update_5fraw_5fgyro_5fdata_10',['update_raw_gyro_data',['../class_b_n_o08x.html#ad0f0fec4e53029b4ba907414a36ac5ea',1,'BNO08x']]], - ['update_5fraw_5fmagf_5fdata_11',['update_raw_magf_data',['../class_b_n_o08x.html#a6ddc9600c53a4248d1affcab36f6f245',1,'BNO08x']]], - ['update_5freport_5fdata_12',['update_report_data',['../class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2',1,'BNO08xTestHelper']]], - ['update_5freport_5fperiod_5ftrackers_13',['update_report_period_trackers',['../class_b_n_o08x.html#a0ec9b1a10bbf25a057273605575f0d64',1,'BNO08x']]], - ['update_5frotation_5fvector_5fdata_14',['update_rotation_vector_data',['../class_b_n_o08x.html#aa309152750686fbf8ebf7d6de1f1254b',1,'BNO08x']]], - ['update_5fstability_5fclassifier_5fdata_15',['update_stability_classifier_data',['../class_b_n_o08x.html#a358316b883928c50dd381f024e6b0645',1,'BNO08x']]], - ['update_5fstep_5fcounter_5fdata_16',['update_step_counter_data',['../class_b_n_o08x.html#aa390bf840246e3233e07f6a424efcb6f',1,'BNO08x']]], - ['update_5ftap_5fdetector_5fdata_17',['update_tap_detector_data',['../class_b_n_o08x.html#ac75b7fb1a1b407d0888ea07d708831b1',1,'BNO08x']]], - ['update_5funcalibrated_5fgyro_5fdata_18',['update_uncalibrated_gyro_data',['../class_b_n_o08x.html#a8de12c9c47549502147bd85dbb7e364e',1,'BNO08x']]] -]; diff --git a/documentation/html/search/functions_12.js b/documentation/html/search/functions_12.js deleted file mode 100644 index d3793e0..0000000 --- a/documentation/html/search/functions_12.js +++ /dev/null @@ -1,6 +0,0 @@ -var searchData= -[ - ['wait_5ffor_5fdata_0',['wait_for_data',['../class_b_n_o08x.html#a4f12de628073f44b2a3fab2688cf1caf',1,'BNO08x']]], - ['wait_5ffor_5frx_5fdone_1',['wait_for_rx_done',['../class_b_n_o08x.html#a2897a178bf2c53cd99df0d4570edf72e',1,'BNO08x']]], - ['wait_5ffor_5ftx_5fdone_2',['wait_for_tx_done',['../class_b_n_o08x.html#a7cdeb849e728487de961cdfd4030c773',1,'BNO08x']]] -]; diff --git a/documentation/html/search/functions_13.js b/documentation/html/search/functions_13.js deleted file mode 100644 index 0c734b6..0000000 --- a/documentation/html/search/functions_13.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['_7ebno08x_0',['~BNO08x',['../class_b_n_o08x.html#a687eee44d68e1bcabce04780d7eb5fb9',1,'BNO08x']]] -]; diff --git a/documentation/html/search/functions_2.js b/documentation/html/search/functions_2.js deleted file mode 100644 index 45ed6b8..0000000 --- a/documentation/html/search/functions_2.js +++ /dev/null @@ -1,17 +0,0 @@ -var searchData= -[ - ['calibrate_5faccelerometer_0',['calibrate_accelerometer',['../class_b_n_o08x.html#aeffce374f558a167d5b5f19ad627e7cc',1,'BNO08x']]], - ['calibrate_5fall_1',['calibrate_all',['../class_b_n_o08x.html#afd0ca5f9b9741935543d143a5a43d128',1,'BNO08x']]], - ['calibrate_5fgyro_2',['calibrate_gyro',['../class_b_n_o08x.html#a9ada90f8ab6dd33fa2d7c168d9234af1',1,'BNO08x']]], - ['calibrate_5fmagnetometer_3',['calibrate_magnetometer',['../class_b_n_o08x.html#ac26350b55095a346d72598ab8aa74b4a',1,'BNO08x']]], - ['calibrate_5fplanar_5faccelerometer_4',['calibrate_planar_accelerometer',['../class_b_n_o08x.html#a1c6c49c97bc098db89db1aaa37e18f26',1,'BNO08x']]], - ['calibrated_5fgyro_5fdata_5fis_5fnew_5',['calibrated_gyro_data_is_new',['../class_b_n_o08x_test_helper.html#a084e65ff5c0e2f429b39ebb53b0e03c9',1,'BNO08xTestHelper']]], - ['calibration_5fcomplete_6',['calibration_complete',['../class_b_n_o08x.html#a71ca35f78b98d93d31eb0c187dc8543b',1,'BNO08x']]], - ['call_5finit_5fconfig_5fargs_7',['call_init_config_args',['../class_b_n_o08x_test_helper.html#a71d9fd7d459a98a7e9089a8587a21f8d',1,'BNO08xTestHelper']]], - ['call_5finit_5fgpio_8',['call_init_gpio',['../class_b_n_o08x_test_helper.html#a504749533ccd91890d73440809d38161',1,'BNO08xTestHelper']]], - ['call_5finit_5fhint_5fisr_9',['call_init_hint_isr',['../class_b_n_o08x_test_helper.html#a836c928981ac85d34668c9b97af17a15',1,'BNO08xTestHelper']]], - ['call_5finit_5fspi_10',['call_init_spi',['../class_b_n_o08x_test_helper.html#a7d2d784da1e850dab41154b35d7cdab5',1,'BNO08xTestHelper']]], - ['call_5flaunch_5ftasks_11',['call_launch_tasks',['../class_b_n_o08x_test_helper.html#adf2488d1f7e3dec21a0d0c99417c181a',1,'BNO08xTestHelper']]], - ['clear_5ftare_12',['clear_tare',['../class_b_n_o08x.html#afe39bfdede7b9a2b273983cb29a27d6e',1,'BNO08x']]], - ['create_5ftest_5fimu_13',['create_test_imu',['../class_b_n_o08x_test_helper.html#a6bd040c7d670a9713f2ab8a8a3913518',1,'BNO08xTestHelper']]] -]; diff --git a/documentation/html/search/functions_3.js b/documentation/html/search/functions_3.js deleted file mode 100644 index 466ad24..0000000 --- a/documentation/html/search/functions_3.js +++ /dev/null @@ -1,31 +0,0 @@ -var searchData= -[ - ['data_5favailable_0',['data_available',['../class_b_n_o08x.html#ab56b185d6c9e972a2b28c2621387bb86',1,'BNO08x']]], - ['data_5fproc_5ftask_1',['data_proc_task',['../class_b_n_o08x.html#ab4373e9b87837ea9fcbc0b536338c7b8',1,'BNO08x']]], - ['data_5fproc_5ftask_5ftrampoline_2',['data_proc_task_trampoline',['../class_b_n_o08x.html#a0ae135d7bf7a5f047a1d1aa5cc07e520',1,'BNO08x']]], - ['deinit_5fgpio_3',['deinit_gpio',['../class_b_n_o08x.html#a4f007dd431f10e741414d197bb4926c3',1,'BNO08x']]], - ['deinit_5fgpio_5finputs_4',['deinit_gpio_inputs',['../class_b_n_o08x.html#a1f0f4cd8dc7d38448e2198ea47d0018c',1,'BNO08x']]], - ['deinit_5fgpio_5foutputs_5',['deinit_gpio_outputs',['../class_b_n_o08x.html#ab132a061bd437fd109225446aa1f6010',1,'BNO08x']]], - ['deinit_5fhint_5fisr_6',['deinit_hint_isr',['../class_b_n_o08x.html#a9d96108b0f5b1e1e1ac431bc993ca758',1,'BNO08x']]], - ['deinit_5fspi_7',['deinit_spi',['../class_b_n_o08x.html#a233920ce97f685fbdabecccacf471d85',1,'BNO08x']]], - ['destroy_5ftest_5fimu_8',['destroy_test_imu',['../class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40',1,'BNO08xTestHelper']]], - ['disable_5faccelerometer_9',['disable_accelerometer',['../class_b_n_o08x.html#ad5c991150895b80bee68c933059a4058',1,'BNO08x::disable_accelerometer()'],['../_callback_tests_8cpp.html#a79547a2396efd083faeba3e54d94360d',1,'disable_accelerometer(): CallbackTests.cpp']]], - ['disable_5factivity_5fclassifier_10',['disable_activity_classifier',['../class_b_n_o08x.html#a4fdc39294922a9553d84cd96bdae4376',1,'BNO08x']]], - ['disable_5farvr_5fstabilized_5fgame_5frotation_5fvector_11',['disable_ARVR_stabilized_game_rotation_vector',['../class_b_n_o08x.html#ab187fe50fcfbb04bec9e80eb0fccf61c',1,'BNO08x']]], - ['disable_5farvr_5fstabilized_5frotation_5fvector_12',['disable_ARVR_stabilized_rotation_vector',['../class_b_n_o08x.html#aa59e3d8953c96dc1cc5958a1ac628df4',1,'BNO08x']]], - ['disable_5fcalibrated_5fgyro_13',['disable_calibrated_gyro',['../class_b_n_o08x.html#a4d6832a3c0b2b4014e28145e6ffe9c2c',1,'BNO08x']]], - ['disable_5fgame_5frotation_5fvector_14',['disable_game_rotation_vector',['../class_b_n_o08x.html#a7665cce95e791c89161ec863f49c0392',1,'BNO08x']]], - ['disable_5fgravity_15',['disable_gravity',['../class_b_n_o08x.html#a5e63a9e68dbe2968b37dcb6dae04de6f',1,'BNO08x']]], - ['disable_5fgyro_5fintegrated_5frotation_5fvector_16',['disable_gyro_integrated_rotation_vector',['../class_b_n_o08x.html#aac0a00bed7825d8a2c357a48c3626931',1,'BNO08x']]], - ['disable_5flinear_5faccelerometer_17',['disable_linear_accelerometer',['../class_b_n_o08x.html#afbd2b02d5abe7084ce9de49ee2c9142f',1,'BNO08x::disable_linear_accelerometer()'],['../_callback_tests_8cpp.html#a5cc5f7e6658e3b1634d99b73dbfd06ab',1,'disable_linear_accelerometer(): CallbackTests.cpp']]], - ['disable_5fmagnetometer_18',['disable_magnetometer',['../class_b_n_o08x.html#a6671b082d20dda8bf5c53cb47db0c338',1,'BNO08x']]], - ['disable_5fraw_5fmems_5faccelerometer_19',['disable_raw_mems_accelerometer',['../class_b_n_o08x.html#a6cd96063eeac75af5f292bdcd31972ce',1,'BNO08x']]], - ['disable_5fraw_5fmems_5fgyro_20',['disable_raw_mems_gyro',['../class_b_n_o08x.html#a5d3ed8a44a34553cf5239cdd4032e725',1,'BNO08x']]], - ['disable_5fraw_5fmems_5fmagnetometer_21',['disable_raw_mems_magnetometer',['../class_b_n_o08x.html#a62d634fc9bced0197103f2973f27bae2',1,'BNO08x']]], - ['disable_5freport_22',['disable_report',['../class_b_n_o08x.html#a00ec3857cb06ae885e32059ef1cab693',1,'BNO08x']]], - ['disable_5frotation_5fvector_23',['disable_rotation_vector',['../class_b_n_o08x.html#a1ebd456d2a67a22b5ba0911a95915921',1,'BNO08x']]], - ['disable_5fstability_5fclassifier_24',['disable_stability_classifier',['../class_b_n_o08x.html#ab307ed3352e04c9e998ab4dd066f8932',1,'BNO08x']]], - ['disable_5fstep_5fcounter_25',['disable_step_counter',['../class_b_n_o08x.html#a427550a4ba25252912436b899124e157',1,'BNO08x']]], - ['disable_5ftap_5fdetector_26',['disable_tap_detector',['../class_b_n_o08x.html#a16f83d1e85576a51abf2c65e5de58cd2',1,'BNO08x']]], - ['disable_5funcalibrated_5fgyro_27',['disable_uncalibrated_gyro',['../class_b_n_o08x.html#aaf28212a5f1960c62a73282976142cfc',1,'BNO08x']]] -]; diff --git a/documentation/html/search/functions_4.js b/documentation/html/search/functions_4.js deleted file mode 100644 index 841ea2b..0000000 --- a/documentation/html/search/functions_4.js +++ /dev/null @@ -1,23 +0,0 @@ -var searchData= -[ - ['enable_5faccelerometer_0',['enable_accelerometer',['../class_b_n_o08x.html#a2795c6579cf03e22f62a5eadc88dee91',1,'BNO08x::enable_accelerometer()'],['../_callback_tests_8cpp.html#a0f2cacda77ab92640f739aca52b1f99f',1,'enable_accelerometer(): CallbackTests.cpp']]], - ['enable_5factivity_5fclassifier_1',['enable_activity_classifier',['../class_b_n_o08x.html#a039e8770759e784baa438324ae17883c',1,'BNO08x']]], - ['enable_5farvr_5fstabilized_5fgame_5frotation_5fvector_2',['enable_ARVR_stabilized_game_rotation_vector',['../class_b_n_o08x.html#a5680148a41cb9cc96d1911150c46d2b8',1,'BNO08x']]], - ['enable_5farvr_5fstabilized_5frotation_5fvector_3',['enable_ARVR_stabilized_rotation_vector',['../class_b_n_o08x.html#a8a5f3b985989e846e831f70f7733d0bc',1,'BNO08x']]], - ['enable_5fcalibrated_5fgyro_4',['enable_calibrated_gyro',['../class_b_n_o08x.html#a9e72a094c4469c9eb9fb766744560c53',1,'BNO08x']]], - ['enable_5fgame_5frotation_5fvector_5',['enable_game_rotation_vector',['../class_b_n_o08x.html#abe04c38b5bd52d331bd8aefae1f51947',1,'BNO08x']]], - ['enable_5fgravity_6',['enable_gravity',['../class_b_n_o08x.html#a030eae12c3586acf09b48e94630b2544',1,'BNO08x']]], - ['enable_5fgyro_5fintegrated_5frotation_5fvector_7',['enable_gyro_integrated_rotation_vector',['../class_b_n_o08x.html#a7388c67de3906ad05b233fd7eff0514d',1,'BNO08x']]], - ['enable_5flinear_5faccelerometer_8',['enable_linear_accelerometer',['../class_b_n_o08x.html#ae1435b83ca83bc51b75f3303afe87f7b',1,'BNO08x::enable_linear_accelerometer()'],['../_callback_tests_8cpp.html#a3e937c8c4a4c07b81fb20077ee984fc0',1,'enable_linear_accelerometer(): CallbackTests.cpp']]], - ['enable_5fmagnetometer_9',['enable_magnetometer',['../class_b_n_o08x.html#a3c32120bcd0987c3ca1bb72910586b59',1,'BNO08x']]], - ['enable_5fraw_5fmems_5faccelerometer_10',['enable_raw_mems_accelerometer',['../class_b_n_o08x.html#a69f768318a621a7dc6620e5551926c3b',1,'BNO08x']]], - ['enable_5fraw_5fmems_5fgyro_11',['enable_raw_mems_gyro',['../class_b_n_o08x.html#a8be135ed41646199540583b29806d4e5',1,'BNO08x']]], - ['enable_5fraw_5fmems_5fmagnetometer_12',['enable_raw_mems_magnetometer',['../class_b_n_o08x.html#a69b3255550345bcb2d302476d50e38a5',1,'BNO08x']]], - ['enable_5freport_13',['enable_report',['../class_b_n_o08x.html#a789f9b9b8ad0a84a6ca45a85740823ca',1,'BNO08x']]], - ['enable_5frotation_5fvector_14',['enable_rotation_vector',['../class_b_n_o08x.html#ab4c1d5cde156af09b7e88913f3af62c7',1,'BNO08x']]], - ['enable_5fstability_5fclassifier_15',['enable_stability_classifier',['../class_b_n_o08x.html#ab0a60844b36fb140cad588a65b3a9655',1,'BNO08x']]], - ['enable_5fstep_5fcounter_16',['enable_step_counter',['../class_b_n_o08x.html#a5a0b0f5b8e962247a3b8aee8f1dc8e9f',1,'BNO08x']]], - ['enable_5ftap_5fdetector_17',['enable_tap_detector',['../class_b_n_o08x.html#ab4c8e37c730ddb168f78c29bd7ae6566',1,'BNO08x']]], - ['enable_5funcalibrated_5fgyro_18',['enable_uncalibrated_gyro',['../class_b_n_o08x.html#a7fe5de95b1f51da44247a87317fd0c75',1,'BNO08x']]], - ['end_5fcalibration_19',['end_calibration',['../class_b_n_o08x.html#ac9d9b6636745e8180807284da67c92a2',1,'BNO08x']]] -]; diff --git a/documentation/html/search/functions_5.js b/documentation/html/search/functions_5.js deleted file mode 100644 index 87aefbe..0000000 --- a/documentation/html/search/functions_5.js +++ /dev/null @@ -1,8 +0,0 @@ -var searchData= -[ - ['flush_5frx_5fpackets_0',['flush_rx_packets',['../class_b_n_o08x.html#a48c1d43b66b1a0894cb1fc2179f62cdc',1,'BNO08x']]], - ['for_1',['for',['../_callback_tests_8cpp.html#a4ac223c58b5ab6a6c5203661fafa1caa',1,'CallbackTests.cpp']]], - ['frs_5fread_5fdata_2',['FRS_read_data',['../class_b_n_o08x.html#a40607e557eada666a5e1e416f42cd4a1',1,'BNO08x']]], - ['frs_5fread_5frequest_3',['FRS_read_request',['../class_b_n_o08x.html#adf789e709ac1667656db757c8d559af9',1,'BNO08x']]], - ['frs_5fread_5fword_4',['FRS_read_word',['../class_b_n_o08x.html#a27f5dce5c994be18a587fb622574ad41',1,'BNO08x']]] -]; diff --git a/documentation/html/search/functions_6.js b/documentation/html/search/functions_6.js deleted file mode 100644 index b655454..0000000 --- a/documentation/html/search/functions_6.js +++ /dev/null @@ -1,77 +0,0 @@ -var searchData= -[ - ['get_5faccel_0',['get_accel',['../class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885',1,'BNO08x']]], - ['get_5faccel_5faccuracy_1',['get_accel_accuracy',['../class_b_n_o08x.html#a6eed9e2d3e639ec7e38dfdf092c14ea1',1,'BNO08x']]], - ['get_5faccel_5fx_2',['get_accel_X',['../class_b_n_o08x.html#abce574112a9079d2cbc58cfc352b8a69',1,'BNO08x']]], - ['get_5faccel_5fy_3',['get_accel_Y',['../class_b_n_o08x.html#afdf24bb3d54518b23972f21f007817c1',1,'BNO08x']]], - ['get_5faccel_5fz_4',['get_accel_Z',['../class_b_n_o08x.html#a0a72477cb7a330fedbcb3e2126b882b1',1,'BNO08x']]], - ['get_5factivity_5fclassifier_5',['get_activity_classifier',['../class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed',1,'BNO08x']]], - ['get_5fcalibrated_5fgyro_5fvelocity_6',['get_calibrated_gyro_velocity',['../class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f',1,'BNO08x']]], - ['get_5fcalibrated_5fgyro_5fvelocity_5fx_7',['get_calibrated_gyro_velocity_X',['../class_b_n_o08x.html#a7710e8bee76742e351cecfaf441f0889',1,'BNO08x']]], - ['get_5fcalibrated_5fgyro_5fvelocity_5fy_8',['get_calibrated_gyro_velocity_Y',['../class_b_n_o08x.html#a492d5bde7377d9f6773eae1d70967f50',1,'BNO08x']]], - ['get_5fcalibrated_5fgyro_5fvelocity_5fz_9',['get_calibrated_gyro_velocity_Z',['../class_b_n_o08x.html#a1599c0515f05a08c043f237c46d29dea',1,'BNO08x']]], - ['get_5fgravity_10',['get_gravity',['../class_b_n_o08x.html#a067678914e928a6691625b17c40237a0',1,'BNO08x']]], - ['get_5fgravity_5faccuracy_11',['get_gravity_accuracy',['../class_b_n_o08x.html#a77c82cece30dde944efcde81643fd62d',1,'BNO08x']]], - ['get_5fgravity_5fx_12',['get_gravity_X',['../class_b_n_o08x.html#a88679bccd9339b87ec35fc4fc4e745ae',1,'BNO08x']]], - ['get_5fgravity_5fy_13',['get_gravity_Y',['../class_b_n_o08x.html#a8a36db7f1c932f33e05e494632059801',1,'BNO08x']]], - ['get_5fgravity_5fz_14',['get_gravity_Z',['../class_b_n_o08x.html#a5622b4d1754648ea7eb400c1adf9e807',1,'BNO08x']]], - ['get_5fintegrated_5fgyro_5fvelocity_15',['get_integrated_gyro_velocity',['../class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f',1,'BNO08x']]], - ['get_5fintegrated_5fgyro_5fvelocity_5fx_16',['get_integrated_gyro_velocity_X',['../class_b_n_o08x.html#a2eb2accfbc70366e6e3eaf391622c1ff',1,'BNO08x']]], - ['get_5fintegrated_5fgyro_5fvelocity_5fy_17',['get_integrated_gyro_velocity_Y',['../class_b_n_o08x.html#aff9a7e0190b228f5032474a3f4feb9a1',1,'BNO08x']]], - ['get_5fintegrated_5fgyro_5fvelocity_5fz_18',['get_integrated_gyro_velocity_Z',['../class_b_n_o08x.html#aa5b483cb0036e9dd43bf797259634add',1,'BNO08x']]], - ['get_5flinear_5faccel_19',['get_linear_accel',['../class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46',1,'BNO08x']]], - ['get_5flinear_5faccel_5faccuracy_20',['get_linear_accel_accuracy',['../class_b_n_o08x.html#a6114ba3c8967ac8fde06233c81623c80',1,'BNO08x']]], - ['get_5flinear_5faccel_5fx_21',['get_linear_accel_X',['../class_b_n_o08x.html#a763c3a9699a1081d430fd9b9b7bc49a3',1,'BNO08x']]], - ['get_5flinear_5faccel_5fy_22',['get_linear_accel_Y',['../class_b_n_o08x.html#a1033bdd65b42b6706d1dfc67ece66191',1,'BNO08x']]], - ['get_5flinear_5faccel_5fz_23',['get_linear_accel_Z',['../class_b_n_o08x.html#afdfa7d50362702da689c5d18bf17fd84',1,'BNO08x']]], - ['get_5fmagf_24',['get_magf',['../class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb',1,'BNO08x']]], - ['get_5fmagf_5faccuracy_25',['get_magf_accuracy',['../class_b_n_o08x.html#a2d98b2cba47dffee8745de1955d234a9',1,'BNO08x']]], - ['get_5fmagf_5fx_26',['get_magf_X',['../class_b_n_o08x.html#a111601243b913751eb51c1f37cba4e7d',1,'BNO08x']]], - ['get_5fmagf_5fy_27',['get_magf_Y',['../class_b_n_o08x.html#a82ed8d7b9a5c25374839df75a3d220ea',1,'BNO08x']]], - ['get_5fmagf_5fz_28',['get_magf_Z',['../class_b_n_o08x.html#ab4c48a91d2f8b29430abc17b7f015282',1,'BNO08x']]], - ['get_5fpitch_29',['get_pitch',['../class_b_n_o08x.html#a1b91f234d81c45f1f5ca2f27c9f0f6a3',1,'BNO08x']]], - ['get_5fpitch_5fdeg_30',['get_pitch_deg',['../class_b_n_o08x.html#af50010400cbd1445e9ddfa259384b412',1,'BNO08x']]], - ['get_5fq1_31',['get_Q1',['../class_b_n_o08x.html#a4421c43323945946ad605f8422958dcf',1,'BNO08x']]], - ['get_5fq2_32',['get_Q2',['../class_b_n_o08x.html#a954dccdcbe8a8c4f1787f13ebb8d932b',1,'BNO08x']]], - ['get_5fq3_33',['get_Q3',['../class_b_n_o08x.html#a1590ba793668f9cb1a32a1f4dd07cb9a',1,'BNO08x']]], - ['get_5fquat_34',['get_quat',['../class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a',1,'BNO08x']]], - ['get_5fquat_5faccuracy_35',['get_quat_accuracy',['../class_b_n_o08x.html#a7c7a74367db26ea8bfbdea633ee1d654',1,'BNO08x']]], - ['get_5fquat_5fi_36',['get_quat_I',['../class_b_n_o08x.html#a12c12a8e078b28480fb8828d306656f5',1,'BNO08x']]], - ['get_5fquat_5fj_37',['get_quat_J',['../class_b_n_o08x.html#a9f6bb642fa0297a7b9bcc94dd7374015',1,'BNO08x']]], - ['get_5fquat_5fk_38',['get_quat_K',['../class_b_n_o08x.html#a9f42c70c2337a0d831064a40ecfe2dd8',1,'BNO08x']]], - ['get_5fquat_5fradian_5faccuracy_39',['get_quat_radian_accuracy',['../class_b_n_o08x.html#a61b7d10a98afc6903fea6b2cede27630',1,'BNO08x']]], - ['get_5fquat_5freal_40',['get_quat_real',['../class_b_n_o08x.html#a5a556c5ec1baaa7f1156779dbe47a7b7',1,'BNO08x']]], - ['get_5frange_41',['get_range',['../class_b_n_o08x.html#a0fff04c42c9502615ad73cd1457cb9b0',1,'BNO08x']]], - ['get_5fraw_5fmems_5faccel_42',['get_raw_mems_accel',['../class_b_n_o08x.html#aa6bbad8c9123b4dba5007f72a8806303',1,'BNO08x']]], - ['get_5fraw_5fmems_5faccel_5fx_43',['get_raw_mems_accel_X',['../class_b_n_o08x.html#a868b24d96cb12f614431a410bcc9e434',1,'BNO08x']]], - ['get_5fraw_5fmems_5faccel_5fy_44',['get_raw_mems_accel_Y',['../class_b_n_o08x.html#aebcbaf9c3aaf37d85a78d22dc22c614a',1,'BNO08x']]], - ['get_5fraw_5fmems_5faccel_5fz_45',['get_raw_mems_accel_Z',['../class_b_n_o08x.html#a85d1331ebe762f6823bde4bf76a33e21',1,'BNO08x']]], - ['get_5fraw_5fmems_5fgyro_46',['get_raw_mems_gyro',['../class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27',1,'BNO08x']]], - ['get_5fraw_5fmems_5fgyro_5fx_47',['get_raw_mems_gyro_X',['../class_b_n_o08x.html#a8872241c73bca2ac1698ae867f7d1913',1,'BNO08x']]], - ['get_5fraw_5fmems_5fgyro_5fy_48',['get_raw_mems_gyro_Y',['../class_b_n_o08x.html#a4bcc58423b5cc7c24080c2ef812d3d86',1,'BNO08x']]], - ['get_5fraw_5fmems_5fgyro_5fz_49',['get_raw_mems_gyro_Z',['../class_b_n_o08x.html#ae684dd13ef630dfdbb8de18ee5ea90bb',1,'BNO08x']]], - ['get_5fraw_5fmems_5fmagf_50',['get_raw_mems_magf',['../class_b_n_o08x.html#a929ad333f73614fb5830c186e3e03a00',1,'BNO08x']]], - ['get_5fraw_5fmems_5fmagf_5fx_51',['get_raw_mems_magf_X',['../class_b_n_o08x.html#a347444f461b2fab5ff37de346ba2a595',1,'BNO08x']]], - ['get_5fraw_5fmems_5fmagf_5fy_52',['get_raw_mems_magf_Y',['../class_b_n_o08x.html#ad8a215314ae96b25b59fdc363c52261c',1,'BNO08x']]], - ['get_5fraw_5fmems_5fmagf_5fz_53',['get_raw_mems_magf_Z',['../class_b_n_o08x.html#a780651af54485edb36d197f30c071615',1,'BNO08x']]], - ['get_5freset_5freason_54',['get_reset_reason',['../class_b_n_o08x.html#a96d47dd0f9aedfbe3f731f8ae76b2e85',1,'BNO08x']]], - ['get_5fresolution_55',['get_resolution',['../class_b_n_o08x.html#a1d6ea02d0d4b23ff6a15e9d5c6c92372',1,'BNO08x']]], - ['get_5froll_56',['get_roll',['../class_b_n_o08x.html#a89618eba08186ee8e679e7313907ddef',1,'BNO08x']]], - ['get_5froll_5fdeg_57',['get_roll_deg',['../class_b_n_o08x.html#a7077b9a130f1dcf0192454e387968dd6',1,'BNO08x']]], - ['get_5fstability_5fclassifier_58',['get_stability_classifier',['../class_b_n_o08x.html#a248544b262582d10d917a687190cb454',1,'BNO08x']]], - ['get_5fstep_5fcount_59',['get_step_count',['../class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef',1,'BNO08x']]], - ['get_5ftap_5fdetector_60',['get_tap_detector',['../class_b_n_o08x.html#a4797ec731de4c158716da1a7af9d1602',1,'BNO08x']]], - ['get_5ftest_5fimu_61',['get_test_imu',['../class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b',1,'BNO08xTestHelper']]], - ['get_5ftime_5fstamp_62',['get_time_stamp',['../class_b_n_o08x.html#ad9137777271421a58159f3fe5e05ed20',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fbias_5fx_63',['get_uncalibrated_gyro_bias_X',['../class_b_n_o08x.html#ad228cdf352b7ea95e484da993045a47b',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fbias_5fy_64',['get_uncalibrated_gyro_bias_Y',['../class_b_n_o08x.html#a74725517129dd548c7a3de705d5861bd',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fbias_5fz_65',['get_uncalibrated_gyro_bias_Z',['../class_b_n_o08x.html#a5050359272abd146ab3c7a6101effbd7',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fvelocity_66',['get_uncalibrated_gyro_velocity',['../class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fvelocity_5fx_67',['get_uncalibrated_gyro_velocity_X',['../class_b_n_o08x.html#a71bbcd4b4d63d55d4f7d5f0de6154486',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fvelocity_5fy_68',['get_uncalibrated_gyro_velocity_Y',['../class_b_n_o08x.html#a2d5a9fa5c960b9efa96d311d25f711de',1,'BNO08x']]], - ['get_5funcalibrated_5fgyro_5fvelocity_5fz_69',['get_uncalibrated_gyro_velocity_Z',['../class_b_n_o08x.html#ab6dc34d058002e21978f8a7e4cf24592',1,'BNO08x']]], - ['get_5fyaw_70',['get_yaw',['../class_b_n_o08x.html#a64d3e41750c6de9413d6982511f78f17',1,'BNO08x']]], - ['get_5fyaw_5fdeg_71',['get_yaw_deg',['../class_b_n_o08x.html#af80f7795656e695e036d3b1557aed94c',1,'BNO08x']]], - ['gravity_5fdata_5fis_5fnew_72',['gravity_data_is_new',['../class_b_n_o08x_test_helper.html#a3c2514f3bad3f091de4646c5798f487a',1,'BNO08xTestHelper']]], - ['gyro_5fintegrated_5frotation_5fvector_5fdata_5fis_5fnew_73',['gyro_integrated_rotation_vector_data_is_new',['../class_b_n_o08x_test_helper.html#ac5b0ac4c70bbfcba9f2e8f353b35f9f6',1,'BNO08xTestHelper']]] -]; diff --git a/documentation/html/search/functions_7.js b/documentation/html/search/functions_7.js deleted file mode 100644 index 0c3122f..0000000 --- a/documentation/html/search/functions_7.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['hard_5freset_0',['hard_reset',['../class_b_n_o08x.html#a28cd1c0b3477571d87133234e6358503',1,'BNO08x']]], - ['hint_5fhandler_1',['hint_handler',['../class_b_n_o08x.html#a804b95c58c30d36933fd251626b85bf7',1,'BNO08x']]] -]; diff --git a/documentation/html/search/functions_8.js b/documentation/html/search/functions_8.js deleted file mode 100644 index f881f26..0000000 --- a/documentation/html/search/functions_8.js +++ /dev/null @@ -1,10 +0,0 @@ -var searchData= -[ - ['init_5fconfig_5fargs_0',['init_config_args',['../class_b_n_o08x.html#a589eb9780f5bf613bbd447ef5b9ade3d',1,'BNO08x']]], - ['init_5fgpio_1',['init_gpio',['../class_b_n_o08x.html#ae0dab25557befcf62bf384fdc241ef10',1,'BNO08x']]], - ['init_5fgpio_5finputs_2',['init_gpio_inputs',['../class_b_n_o08x.html#a8f34d5475474f00ae6a92f73c1fe14e4',1,'BNO08x']]], - ['init_5fgpio_5foutputs_3',['init_gpio_outputs',['../class_b_n_o08x.html#ad0b9e8f8d051798bb1da9b19598dbd64',1,'BNO08x']]], - ['init_5fhint_5fisr_4',['init_hint_isr',['../class_b_n_o08x.html#aa27026da2c52b4aca49b78863f10ec61',1,'BNO08x']]], - ['init_5fspi_5',['init_spi',['../class_b_n_o08x.html#a58f43c8bb1e7fe8560ce442d46240e81',1,'BNO08x']]], - ['initialize_6',['initialize',['../class_b_n_o08x.html#aea8e2c6dd7a2c9899479a7f39fe94798',1,'BNO08x']]] -]; diff --git a/documentation/html/search/functions_9.js b/documentation/html/search/functions_9.js deleted file mode 100644 index f020acb..0000000 --- a/documentation/html/search/functions_9.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['kill_5fall_5ftasks_0',['kill_all_tasks',['../class_b_n_o08x.html#a5adc21b484ff98c42622e2ad9871d5a0',1,'BNO08x']]] -]; diff --git a/documentation/html/search/functions_a.js b/documentation/html/search/functions_a.js deleted file mode 100644 index d4888f9..0000000 --- a/documentation/html/search/functions_a.js +++ /dev/null @@ -1,5 +0,0 @@ -var searchData= -[ - ['launch_5ftasks_0',['launch_tasks',['../class_b_n_o08x.html#a06f99a6b2182b49a0e61e2107f2be6be',1,'BNO08x']]], - ['linear_5faccelerometer_5fdata_5fis_5fnew_1',['linear_accelerometer_data_is_new',['../class_b_n_o08x_test_helper.html#ad398739ce46400c1ac35e1cf7603d590',1,'BNO08xTestHelper']]] -]; diff --git a/documentation/html/search/functions_b.js b/documentation/html/search/functions_b.js deleted file mode 100644 index 9110185..0000000 --- a/documentation/html/search/functions_b.js +++ /dev/null @@ -1,6 +0,0 @@ -var searchData= -[ - ['magnetometer_5fdata_5fis_5fnew_0',['magnetometer_data_is_new',['../class_b_n_o08x_test_helper.html#a157342da2def8b659d27ae4d24063cb5',1,'BNO08xTestHelper']]], - ['mode_5fon_1',['mode_on',['../class_b_n_o08x.html#ac1b3de9b552c611ee9c455d7f19be698',1,'BNO08x']]], - ['mode_5fsleep_2',['mode_sleep',['../class_b_n_o08x.html#a176ae0112325c05105eacb4566bbfa0b',1,'BNO08x']]] -]; diff --git a/documentation/html/search/functions_c.js b/documentation/html/search/functions_c.js deleted file mode 100644 index 03a7773..0000000 --- a/documentation/html/search/functions_c.js +++ /dev/null @@ -1,18 +0,0 @@ -var searchData= -[ - ['parse_5fcommand_5freport_0',['parse_command_report',['../class_b_n_o08x.html#a4f66045a0528a0c17c52421ea51612e7',1,'BNO08x']]], - ['parse_5ffeature_5fget_5fresponse_5freport_1',['parse_feature_get_response_report',['../class_b_n_o08x.html#a206c0e3ddc3b745b56914976d6e69981',1,'BNO08x']]], - ['parse_5ffrs_5fread_5fresponse_5freport_2',['parse_frs_read_response_report',['../class_b_n_o08x.html#a51b360d795563b55559f11efb40be36a',1,'BNO08x']]], - ['parse_5fgyro_5fintegrated_5frotation_5fvector_5freport_3',['parse_gyro_integrated_rotation_vector_report',['../class_b_n_o08x.html#a7be6047fef851a064c7cbc9eba092f6d',1,'BNO08x']]], - ['parse_5finput_5freport_4',['parse_input_report',['../class_b_n_o08x.html#a8d9db3e1b6208c2661e1c543deefa53d',1,'BNO08x']]], - ['parse_5finput_5freport_5fdata_5',['parse_input_report_data',['../class_b_n_o08x.html#a002aa97c9af8f6df2d0c83034e4f7b55',1,'BNO08x']]], - ['parse_5fpacket_6',['parse_packet',['../class_b_n_o08x.html#a1c47d27917ae3b2876efa121b803f924',1,'BNO08x']]], - ['parse_5fproduct_5fid_5freport_7',['parse_product_id_report',['../class_b_n_o08x.html#a29cfd7fc2816483ebebe9d55b677a036',1,'BNO08x']]], - ['print_5fbegin_5ftests_5fbanner_8',['print_begin_tests_banner',['../class_b_n_o08x_test_suite.html#a2fea3ea192a63c9573c774e772f5c085',1,'BNO08xTestSuite']]], - ['print_5fend_5ftests_5fbanner_9',['print_end_tests_banner',['../class_b_n_o08x_test_suite.html#a5a9b6538773911afed92b16c435ebceb',1,'BNO08xTestSuite']]], - ['print_5fheader_10',['print_header',['../class_b_n_o08x.html#a35856c108a47de8b3b38c4395aabb4eb',1,'BNO08x']]], - ['print_5fpacket_11',['print_packet',['../class_b_n_o08x.html#a05e4cd5861b55fc0182d7dd13bb85e49',1,'BNO08x']]], - ['print_5ftest_5fend_5fbanner_12',['print_test_end_banner',['../class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919',1,'BNO08xTestHelper']]], - ['print_5ftest_5fmsg_13',['print_test_msg',['../class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002',1,'BNO08xTestHelper']]], - ['print_5ftest_5fstart_5fbanner_14',['print_test_start_banner',['../class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885',1,'BNO08xTestHelper']]] -]; diff --git a/documentation/html/search/functions_d.js b/documentation/html/search/functions_d.js deleted file mode 100644 index 8e310e2..0000000 --- a/documentation/html/search/functions_d.js +++ /dev/null @@ -1,10 +0,0 @@ -var searchData= -[ - ['q_5fto_5ffloat_0',['q_to_float',['../class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9',1,'BNO08x']]], - ['queue_5fcalibrate_5fcommand_1',['queue_calibrate_command',['../class_b_n_o08x.html#ad097849616c5caab1fd3eb3632ee2b91',1,'BNO08x']]], - ['queue_5fcommand_2',['queue_command',['../class_b_n_o08x.html#a5cc58139e4d5f0587b90e249ceb476f9',1,'BNO08x']]], - ['queue_5ffeature_5fcommand_3',['queue_feature_command',['../class_b_n_o08x.html#af7f960dbd26c6f1834661ef5f5bbd4d3',1,'BNO08x']]], - ['queue_5fpacket_4',['queue_packet',['../class_b_n_o08x.html#a62c570ba96512f4d0d10b2594048de1f',1,'BNO08x']]], - ['queue_5frequest_5fproduct_5fid_5fcommand_5',['queue_request_product_id_command',['../class_b_n_o08x.html#ab5f200069a2f8cb74cb79c6f162da5a1',1,'BNO08x']]], - ['queue_5ftare_5fcommand_6',['queue_tare_command',['../class_b_n_o08x.html#a4c6353e795f734ed28613f9a3d161ea2',1,'BNO08x']]] -]; diff --git a/documentation/html/search/functions_e.js b/documentation/html/search/functions_e.js deleted file mode 100644 index 1604e82..0000000 --- a/documentation/html/search/functions_e.js +++ /dev/null @@ -1,18 +0,0 @@ -var searchData= -[ - ['receive_5fpacket_0',['receive_packet',['../class_b_n_o08x.html#a8d9f28d8857279a3c4b1f62f6dabb638',1,'BNO08x']]], - ['receive_5fpacket_5fbody_1',['receive_packet_body',['../class_b_n_o08x.html#a9ee7e73f695af8965a9ede50136d5a8c',1,'BNO08x']]], - ['receive_5fpacket_5fheader_2',['receive_packet_header',['../class_b_n_o08x.html#acb246769719351e02bf2aff06d039475',1,'BNO08x']]], - ['register_5fcb_3',['register_cb',['../class_b_n_o08x.html#a06bb0c70305421b5357e64f31579fdc7',1,'BNO08x::register_cb()'],['../_callback_tests_8cpp.html#a6df8508e34beaeb28f34554ce0e20573',1,'register_cb([&imu, &new_data, &report_data, &prev_report_data, &msg_buff]() { static int cb_execution_cnt=0;cb_execution_cnt++;BNO08xTestHelper::update_report_data(&report_data);if(BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) { new_data=true;sprintf(msg_buff, "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " "%.2lf Accuracy %s", cb_execution_cnt, report_data.accel_x, report_data.accel_y, report_data.accel_z, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy));BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff);} }): CallbackTests.cpp'],['../_callback_tests_8cpp.html#a8dba989b01b464871f3232223050ec73',1,'register_cb([&imu, &new_data, &report_data, &prev_report_data, &msg_buff]() { static int cb_execution_cnt=0;cb_execution_cnt++;BNO08xTestHelper::update_report_data(&report_data);if(BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) { new_data[0]=true;sprintf(msg_buff, "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " "%.2lf Accuracy %s", cb_execution_cnt, report_data.accel_x, report_data.accel_y, report_data.accel_z, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy));BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff);} if(BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) { new_data[1]=true;sprintf(msg_buff, "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " "%.2lf Accuracy: %s",(cb_execution_cnt+1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy));BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff);} }): CallbackTests.cpp']]], - ['report_5fid_5fto_5freport_5fperiod_5ftracker_5fidx_4',['report_ID_to_report_period_tracker_idx',['../class_b_n_o08x.html#a27b5317d11a5b81028b87a73b7024bfa',1,'BNO08x']]], - ['request_5fcalibration_5fstatus_5',['request_calibration_status',['../class_b_n_o08x.html#affaaa35abbb872da5299ebab6e2c9b11',1,'BNO08x']]], - ['reset_5fall_5fdata_5fto_5fdefaults_6',['reset_all_data_to_defaults',['../class_b_n_o08x.html#a453ec8a70646651d4e5b10bf0b2e4d61',1,'BNO08x']]], - ['reset_5fall_5fimu_5fdata_5fto_5ftest_5fdefaults_7',['reset_all_imu_data_to_test_defaults',['../class_b_n_o08x_test_helper.html#ade6be1fd8ef3a99e0edae4cbf25eb528',1,'BNO08xTestHelper']]], - ['rotation_5fvector_5fdata_5fis_5fnew_8',['rotation_vector_data_is_new',['../class_b_n_o08x_test_helper.html#aeb8cd985faf8e403f62b60fced9cb2fd',1,'BNO08xTestHelper']]], - ['run_5fall_5ftests_9',['run_all_tests',['../class_b_n_o08x_test_suite.html#ac12545fe311a98e9c0ae6fea77da95fd',1,'BNO08xTestSuite']]], - ['run_5fcallback_5ftests_10',['run_callback_tests',['../class_b_n_o08x_test_suite.html#a8e294955bf512e2e88c086f04f6030a8',1,'BNO08xTestSuite']]], - ['run_5ffull_5fcalibration_5froutine_11',['run_full_calibration_routine',['../class_b_n_o08x.html#ae6e875a27ae74ebed806ee1a4576845a',1,'BNO08x']]], - ['run_5finit_5fdeinit_5ftests_12',['run_init_deinit_tests',['../class_b_n_o08x_test_suite.html#a53de9b0fe1b28c18e3a1ca4c68a06f16',1,'BNO08xTestSuite']]], - ['run_5fmulti_5freport_5ftests_13',['run_multi_report_tests',['../class_b_n_o08x_test_suite.html#a916cff374791381de61f1035f9935ac5',1,'BNO08xTestSuite']]], - ['run_5fsingle_5freport_5ftests_14',['run_single_report_tests',['../class_b_n_o08x_test_suite.html#a37899d7bf67fce5c3dd77dd5647f8ecb',1,'BNO08xTestSuite']]] -]; diff --git a/documentation/html/search/functions_f.js b/documentation/html/search/functions_f.js deleted file mode 100644 index d68a380..0000000 --- a/documentation/html/search/functions_f.js +++ /dev/null @@ -1,12 +0,0 @@ -var searchData= -[ - ['save_5fcalibration_0',['save_calibration',['../class_b_n_o08x.html#aa16609de88bfb7b389348859aa0cee54',1,'BNO08x']]], - ['save_5ftare_1',['save_tare',['../class_b_n_o08x.html#afb2ffc4e7ff0498917bc14a83af306e2',1,'BNO08x']]], - ['send_5fpacket_2',['send_packet',['../class_b_n_o08x.html#a2c359a44a2c8e83ecb258a340e2d0e1a',1,'BNO08x']]], - ['set_5ftest_5fimu_5fcfg_3',['set_test_imu_cfg',['../class_b_n_o08x_test_helper.html#a9e2f9bf13f28f1a6ba87e86bc5947cf1',1,'BNO08xTestHelper']]], - ['soft_5freset_4',['soft_reset',['../class_b_n_o08x.html#a973a1b1785f3302ee1b2702c6a27646e',1,'BNO08x']]], - ['spi_5ftask_5',['spi_task',['../class_b_n_o08x.html#a2ecd4ed60f82730ae230c61687ec92bf',1,'BNO08x']]], - ['spi_5ftask_5ftrampoline_6',['spi_task_trampoline',['../class_b_n_o08x.html#a0ce6d9db873555f1ebe7e095251eab74',1,'BNO08x']]], - ['stability_5fclassifier_5fdata_5fis_5fnew_7',['stability_classifier_data_is_new',['../class_b_n_o08x_test_helper.html#a95ed21657224358877a66d010eeefad3',1,'BNO08xTestHelper']]], - ['step_5fcounter_5fdata_5fis_5fnew_8',['step_counter_data_is_new',['../class_b_n_o08x_test_helper.html#aa7eb152d4192c3949bb3443ef6221782',1,'BNO08xTestHelper']]] -]; diff --git a/documentation/html/search/mag.svg b/documentation/html/search/mag.svg deleted file mode 100644 index ffb6cf0..0000000 --- a/documentation/html/search/mag.svg +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - diff --git a/documentation/html/search/mag_d.svg b/documentation/html/search/mag_d.svg deleted file mode 100644 index 4122773..0000000 --- a/documentation/html/search/mag_d.svg +++ /dev/null @@ -1,24 +0,0 @@ - - - - - - - diff --git a/documentation/html/search/mag_sel.svg b/documentation/html/search/mag_sel.svg deleted file mode 100644 index 553dba8..0000000 --- a/documentation/html/search/mag_sel.svg +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/search/mag_seld.svg b/documentation/html/search/mag_seld.svg deleted file mode 100644 index c906f84..0000000 --- a/documentation/html/search/mag_seld.svg +++ /dev/null @@ -1,31 +0,0 @@ - - - - - - - - - diff --git a/documentation/html/search/pages_0.js b/documentation/html/search/pages_0.js deleted file mode 100644 index c42e3bf..0000000 --- a/documentation/html/search/pages_0.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['readme_0',['README',['../md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.html',1,'']]] -]; diff --git a/documentation/html/search/related_0.js b/documentation/html/search/related_0.js deleted file mode 100644 index 4501427..0000000 --- a/documentation/html/search/related_0.js +++ /dev/null @@ -1,4 +0,0 @@ -var searchData= -[ - ['bno08xtesthelper_0',['BNO08xTestHelper',['../class_b_n_o08x.html#a190775b71c35d8007faae7dd6a9f1030',1,'BNO08x']]] -]; diff --git a/documentation/html/search/search.css b/documentation/html/search/search.css deleted file mode 100644 index 19f76f9..0000000 --- a/documentation/html/search/search.css +++ /dev/null @@ -1,291 +0,0 @@ -/*---------------- Search Box positioning */ - -#main-menu > li:last-child { - /* This
  • object is the parent of the search bar */ - display: flex; - justify-content: center; - align-items: center; - height: 36px; - margin-right: 1em; -} - -/*---------------- Search box styling */ - -.SRPage * { - font-weight: normal; - line-height: normal; -} - -dark-mode-toggle { - margin-left: 5px; - display: flex; - float: right; -} - -#MSearchBox { - display: inline-block; - white-space : nowrap; - background: var(--search-background-color); - border-radius: 0.65em; - box-shadow: var(--search-box-shadow); - z-index: 102; -} - -#MSearchBox .left { - display: inline-block; - vertical-align: middle; - height: 1.4em; -} - -#MSearchSelect { - display: inline-block; - vertical-align: middle; - width: 20px; - height: 19px; - background-image: var(--search-magnification-select-image); - margin: 0 0 0 0.3em; - padding: 0; -} - -#MSearchSelectExt { - display: inline-block; - vertical-align: middle; - width: 10px; - height: 19px; - background-image: var(--search-magnification-image); - margin: 0 0 0 0.5em; - padding: 0; -} - - -#MSearchField { - display: inline-block; - vertical-align: middle; - width: 7.5em; - height: 19px; - margin: 0 0.15em; - padding: 0; - line-height: 1em; - border:none; - color: var(--search-foreground-color); - outline: none; - font-family: var(--font-family-search); - -webkit-border-radius: 0px; - border-radius: 0px; - background: none; -} - -@media(hover: none) { - /* to avoid zooming on iOS */ - #MSearchField { - font-size: 16px; - } -} - -#MSearchBox .right { - display: inline-block; - vertical-align: middle; - width: 1.4em; - height: 1.4em; -} - -#MSearchClose { - display: none; - font-size: inherit; - background : none; - border: none; - margin: 0; - padding: 0; - outline: none; - -} - -#MSearchCloseImg { - padding: 0.3em; - margin: 0; -} - -.MSearchBoxActive #MSearchField { - color: var(--search-active-color); -} - - - -/*---------------- Search filter selection */ - -#MSearchSelectWindow { - display: none; - position: absolute; - left: 0; top: 0; - border: 1px solid var(--search-filter-border-color); - background-color: var(--search-filter-background-color); - z-index: 10001; - padding-top: 4px; - padding-bottom: 4px; - -moz-border-radius: 4px; - -webkit-border-top-left-radius: 4px; - -webkit-border-top-right-radius: 4px; - -webkit-border-bottom-left-radius: 4px; - -webkit-border-bottom-right-radius: 4px; - -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); -} - -.SelectItem { - font: 8pt var(--font-family-search); - padding-left: 2px; - padding-right: 12px; - border: 0px; -} - -span.SelectionMark { - margin-right: 4px; - font-family: var(--font-family-monospace); - outline-style: none; - text-decoration: none; -} - -a.SelectItem { - display: block; - outline-style: none; - color: var(--search-filter-foreground-color); - text-decoration: none; - padding-left: 6px; - padding-right: 12px; -} - -a.SelectItem:focus, -a.SelectItem:active { - color: var(--search-filter-foreground-color); - outline-style: none; - text-decoration: none; -} - -a.SelectItem:hover { - color: var(--search-filter-highlight-text-color); - background-color: var(--search-filter-highlight-bg-color); - outline-style: none; - text-decoration: none; - cursor: pointer; - display: block; -} - -/*---------------- Search results window */ - -iframe#MSearchResults { - /*width: 60ex;*/ - height: 15em; -} - -#MSearchResultsWindow { - display: none; - position: absolute; - left: 0; top: 0; - border: 1px solid var(--search-results-border-color); - background-color: var(--search-results-background-color); - z-index:10000; - width: 300px; - height: 400px; - overflow: auto; -} - -/* ----------------------------------- */ - - -#SRIndex { - clear:both; -} - -.SREntry { - font-size: 10pt; - padding-left: 1ex; -} - -.SRPage .SREntry { - font-size: 8pt; - padding: 1px 5px; -} - -div.SRPage { - margin: 5px 2px; - background-color: var(--search-results-background-color); -} - -.SRChildren { - padding-left: 3ex; padding-bottom: .5em -} - -.SRPage .SRChildren { - display: none; -} - -.SRSymbol { - font-weight: bold; - color: var(--search-results-foreground-color); - font-family: var(--font-family-search); - text-decoration: none; - outline: none; -} - -a.SRScope { - display: block; - color: var(--search-results-foreground-color); - font-family: var(--font-family-search); - font-size: 8pt; - text-decoration: none; - outline: none; -} - -a.SRSymbol:focus, a.SRSymbol:active, -a.SRScope:focus, a.SRScope:active { - text-decoration: underline; -} - -span.SRScope { - padding-left: 4px; - font-family: var(--font-family-search); -} - -.SRPage .SRStatus { - padding: 2px 5px; - font-size: 8pt; - font-style: italic; - font-family: var(--font-family-search); -} - -.SRResult { - display: none; -} - -div.searchresults { - margin-left: 10px; - margin-right: 10px; -} - -/*---------------- External search page results */ - -.pages b { - color: white; - padding: 5px 5px 3px 5px; - background-image: var(--nav-gradient-active-image-parent); - background-repeat: repeat-x; - text-shadow: 0 1px 1px #000000; -} - -.pages { - line-height: 17px; - margin-left: 4px; - text-decoration: none; -} - -.hl { - font-weight: bold; -} - -#searchresults { - margin-bottom: 20px; -} - -.searchpages { - margin-top: 10px; -} - diff --git a/documentation/html/search/search.js b/documentation/html/search/search.js deleted file mode 100644 index 666af01..0000000 --- a/documentation/html/search/search.js +++ /dev/null @@ -1,694 +0,0 @@ -/* - @licstart The following is the entire license notice for the JavaScript code in this file. - - The MIT License (MIT) - - Copyright (C) 1997-2020 by Dimitri van Heesch - - Permission is hereby granted, free of charge, to any person obtaining a copy of this software - and associated documentation files (the "Software"), to deal in the Software without restriction, - including without limitation the rights to use, copy, modify, merge, publish, distribute, - sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is - furnished to do so, subject to the following conditions: - - The above copyright notice and this permission notice shall be included in all copies or - substantial portions of the Software. - - THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING - BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND - NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, - DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, - OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. - - @licend The above is the entire license notice for the JavaScript code in this file - */ -const SEARCH_COOKIE_NAME = ''+'search_grp'; - -const searchResults = new SearchResults(); - -/* A class handling everything associated with the search panel. - - Parameters: - name - The name of the global variable that will be - storing this instance. Is needed to be able to set timeouts. - resultPath - path to use for external files -*/ -function SearchBox(name, resultsPath, extension) { - if (!name || !resultsPath) { alert("Missing parameters to SearchBox."); } - if (!extension || extension == "") { extension = ".html"; } - - function getXPos(item) { - let x = 0; - if (item.offsetWidth) { - while (item && item!=document.body) { - x += item.offsetLeft; - item = item.offsetParent; - } - } - return x; - } - - function getYPos(item) { - let y = 0; - if (item.offsetWidth) { - while (item && item!=document.body) { - y += item.offsetTop; - item = item.offsetParent; - } - } - return y; - } - - // ---------- Instance variables - this.name = name; - this.resultsPath = resultsPath; - this.keyTimeout = 0; - this.keyTimeoutLength = 500; - this.closeSelectionTimeout = 300; - this.lastSearchValue = ""; - this.lastResultsPage = ""; - this.hideTimeout = 0; - this.searchIndex = 0; - this.searchActive = false; - this.extension = extension; - - // ----------- DOM Elements - - this.DOMSearchField = () => document.getElementById("MSearchField"); - this.DOMSearchSelect = () => document.getElementById("MSearchSelect"); - this.DOMSearchSelectWindow = () => document.getElementById("MSearchSelectWindow"); - this.DOMPopupSearchResults = () => document.getElementById("MSearchResults"); - this.DOMPopupSearchResultsWindow = () => document.getElementById("MSearchResultsWindow"); - this.DOMSearchClose = () => document.getElementById("MSearchClose"); - this.DOMSearchBox = () => document.getElementById("MSearchBox"); - - // ------------ Event Handlers - - // Called when focus is added or removed from the search field. - this.OnSearchFieldFocus = function(isActive) { - this.Activate(isActive); - } - - this.OnSearchSelectShow = function() { - const searchSelectWindow = this.DOMSearchSelectWindow(); - const searchField = this.DOMSearchSelect(); - - const left = getXPos(searchField); - const top = getYPos(searchField) + searchField.offsetHeight; - - // show search selection popup - searchSelectWindow.style.display='block'; - searchSelectWindow.style.left = left + 'px'; - searchSelectWindow.style.top = top + 'px'; - - // stop selection hide timer - if (this.hideTimeout) { - clearTimeout(this.hideTimeout); - this.hideTimeout=0; - } - return false; // to avoid "image drag" default event - } - - this.OnSearchSelectHide = function() { - this.hideTimeout = setTimeout(this.CloseSelectionWindow.bind(this), - this.closeSelectionTimeout); - } - - // Called when the content of the search field is changed. - this.OnSearchFieldChange = function(evt) { - if (this.keyTimeout) { // kill running timer - clearTimeout(this.keyTimeout); - this.keyTimeout = 0; - } - - const e = evt ? evt : window.event; // for IE - if (e.keyCode==40 || e.keyCode==13) { - if (e.shiftKey==1) { - this.OnSearchSelectShow(); - const win=this.DOMSearchSelectWindow(); - for (let i=0;i do a search - this.Search(); - } - } - - this.OnSearchSelectKey = function(evt) { - const e = (evt) ? evt : window.event; // for IE - if (e.keyCode==40 && this.searchIndex0) { // Up - this.searchIndex--; - this.OnSelectItem(this.searchIndex); - } else if (e.keyCode==13 || e.keyCode==27) { - e.stopPropagation(); - this.OnSelectItem(this.searchIndex); - this.CloseSelectionWindow(); - this.DOMSearchField().focus(); - } - return false; - } - - // --------- Actions - - // Closes the results window. - this.CloseResultsWindow = function() { - this.DOMPopupSearchResultsWindow().style.display = 'none'; - this.DOMSearchClose().style.display = 'none'; - this.Activate(false); - } - - this.CloseSelectionWindow = function() { - this.DOMSearchSelectWindow().style.display = 'none'; - } - - // Performs a search. - this.Search = function() { - this.keyTimeout = 0; - - // strip leading whitespace - const searchValue = this.DOMSearchField().value.replace(/^ +/, ""); - - const code = searchValue.toLowerCase().charCodeAt(0); - let idxChar = searchValue.substr(0, 1).toLowerCase(); - if ( 0xD800 <= code && code <= 0xDBFF && searchValue > 1) { // surrogate pair - idxChar = searchValue.substr(0, 2); - } - - let jsFile; - let idx = indexSectionsWithContent[this.searchIndex].indexOf(idxChar); - if (idx!=-1) { - const hexCode=idx.toString(16); - jsFile = this.resultsPath + indexSectionNames[this.searchIndex] + '_' + hexCode + '.js'; - } - - const loadJS = function(url, impl, loc) { - const scriptTag = document.createElement('script'); - scriptTag.src = url; - scriptTag.onload = impl; - scriptTag.onreadystatechange = impl; - loc.appendChild(scriptTag); - } - - const domPopupSearchResultsWindow = this.DOMPopupSearchResultsWindow(); - const domSearchBox = this.DOMSearchBox(); - const domPopupSearchResults = this.DOMPopupSearchResults(); - const domSearchClose = this.DOMSearchClose(); - const resultsPath = this.resultsPath; - - const handleResults = function() { - document.getElementById("Loading").style.display="none"; - if (typeof searchData !== 'undefined') { - createResults(resultsPath); - document.getElementById("NoMatches").style.display="none"; - } - - if (idx!=-1) { - searchResults.Search(searchValue); - } else { // no file with search results => force empty search results - searchResults.Search('===='); - } - - if (domPopupSearchResultsWindow.style.display!='block') { - domSearchClose.style.display = 'inline-block'; - let left = getXPos(domSearchBox) + 150; - let top = getYPos(domSearchBox) + 20; - domPopupSearchResultsWindow.style.display = 'block'; - left -= domPopupSearchResults.offsetWidth; - const maxWidth = document.body.clientWidth; - const maxHeight = document.body.clientHeight; - let width = 300; - if (left<10) left=10; - if (width+left+8>maxWidth) width=maxWidth-left-8; - let height = 400; - if (height+top+8>maxHeight) height=maxHeight-top-8; - domPopupSearchResultsWindow.style.top = top + 'px'; - domPopupSearchResultsWindow.style.left = left + 'px'; - domPopupSearchResultsWindow.style.width = width + 'px'; - domPopupSearchResultsWindow.style.height = height + 'px'; - } - } - - if (jsFile) { - loadJS(jsFile, handleResults, this.DOMPopupSearchResultsWindow()); - } else { - handleResults(); - } - - this.lastSearchValue = searchValue; - } - - // -------- Activation Functions - - // Activates or deactivates the search panel, resetting things to - // their default values if necessary. - this.Activate = function(isActive) { - if (isActive || // open it - this.DOMPopupSearchResultsWindow().style.display == 'block' - ) { - this.DOMSearchBox().className = 'MSearchBoxActive'; - this.searchActive = true; - } else if (!isActive) { // directly remove the panel - this.DOMSearchBox().className = 'MSearchBoxInactive'; - this.searchActive = false; - this.lastSearchValue = '' - this.lastResultsPage = ''; - this.DOMSearchField().value = ''; - } - } -} - -// ----------------------------------------------------------------------- - -// The class that handles everything on the search results page. -function SearchResults() { - - function convertToId(search) { - let result = ''; - for (let i=0;i. - this.lastMatchCount = 0; - this.lastKey = 0; - this.repeatOn = false; - - // Toggles the visibility of the passed element ID. - this.FindChildElement = function(id) { - const parentElement = document.getElementById(id); - let element = parentElement.firstChild; - - while (element && element!=parentElement) { - if (element.nodeName.toLowerCase() == 'div' && element.className == 'SRChildren') { - return element; - } - - if (element.nodeName.toLowerCase() == 'div' && element.hasChildNodes()) { - element = element.firstChild; - } else if (element.nextSibling) { - element = element.nextSibling; - } else { - do { - element = element.parentNode; - } - while (element && element!=parentElement && !element.nextSibling); - - if (element && element!=parentElement) { - element = element.nextSibling; - } - } - } - } - - this.Toggle = function(id) { - const element = this.FindChildElement(id); - if (element) { - if (element.style.display == 'block') { - element.style.display = 'none'; - } else { - element.style.display = 'block'; - } - } - } - - // Searches for the passed string. If there is no parameter, - // it takes it from the URL query. - // - // Always returns true, since other documents may try to call it - // and that may or may not be possible. - this.Search = function(search) { - if (!search) { // get search word from URL - search = window.location.search; - search = search.substring(1); // Remove the leading '?' - search = unescape(search); - } - - search = search.replace(/^ +/, ""); // strip leading spaces - search = search.replace(/ +$/, ""); // strip trailing spaces - search = search.toLowerCase(); - search = convertToId(search); - - const resultRows = document.getElementsByTagName("div"); - let matches = 0; - - let i = 0; - while (i < resultRows.length) { - const row = resultRows.item(i); - if (row.className == "SRResult") { - let rowMatchName = row.id.toLowerCase(); - rowMatchName = rowMatchName.replace(/^sr\d*_/, ''); // strip 'sr123_' - - if (search.length<=rowMatchName.length && - rowMatchName.substr(0, search.length)==search) { - row.style.display = 'block'; - matches++; - } else { - row.style.display = 'none'; - } - } - i++; - } - document.getElementById("Searching").style.display='none'; - if (matches == 0) { // no results - document.getElementById("NoMatches").style.display='block'; - } else { // at least one result - document.getElementById("NoMatches").style.display='none'; - } - this.lastMatchCount = matches; - return true; - } - - // return the first item with index index or higher that is visible - this.NavNext = function(index) { - let focusItem; - for (;;) { - const focusName = 'Item'+index; - focusItem = document.getElementById(focusName); - if (focusItem && focusItem.parentNode.parentNode.style.display=='block') { - break; - } else if (!focusItem) { // last element - break; - } - focusItem=null; - index++; - } - return focusItem; - } - - this.NavPrev = function(index) { - let focusItem; - for (;;) { - const focusName = 'Item'+index; - focusItem = document.getElementById(focusName); - if (focusItem && focusItem.parentNode.parentNode.style.display=='block') { - break; - } else if (!focusItem) { // last element - break; - } - focusItem=null; - index--; - } - return focusItem; - } - - this.ProcessKeys = function(e) { - if (e.type == "keydown") { - this.repeatOn = false; - this.lastKey = e.keyCode; - } else if (e.type == "keypress") { - if (!this.repeatOn) { - if (this.lastKey) this.repeatOn = true; - return false; // ignore first keypress after keydown - } - } else if (e.type == "keyup") { - this.lastKey = 0; - this.repeatOn = false; - } - return this.lastKey!=0; - } - - this.Nav = function(evt,itemIndex) { - const e = (evt) ? evt : window.event; // for IE - if (e.keyCode==13) return true; - if (!this.ProcessKeys(e)) return false; - - if (this.lastKey==38) { // Up - const newIndex = itemIndex-1; - let focusItem = this.NavPrev(newIndex); - if (focusItem) { - let child = this.FindChildElement(focusItem.parentNode.parentNode.id); - if (child && child.style.display == 'block') { // children visible - let n=0; - let tmpElem; - for (;;) { // search for last child - tmpElem = document.getElementById('Item'+newIndex+'_c'+n); - if (tmpElem) { - focusItem = tmpElem; - } else { // found it! - break; - } - n++; - } - } - } - if (focusItem) { - focusItem.focus(); - } else { // return focus to search field - document.getElementById("MSearchField").focus(); - } - } else if (this.lastKey==40) { // Down - const newIndex = itemIndex+1; - let focusItem; - const item = document.getElementById('Item'+itemIndex); - const elem = this.FindChildElement(item.parentNode.parentNode.id); - if (elem && elem.style.display == 'block') { // children visible - focusItem = document.getElementById('Item'+itemIndex+'_c0'); - } - if (!focusItem) focusItem = this.NavNext(newIndex); - if (focusItem) focusItem.focus(); - } else if (this.lastKey==39) { // Right - const item = document.getElementById('Item'+itemIndex); - const elem = this.FindChildElement(item.parentNode.parentNode.id); - if (elem) elem.style.display = 'block'; - } else if (this.lastKey==37) { // Left - const item = document.getElementById('Item'+itemIndex); - const elem = this.FindChildElement(item.parentNode.parentNode.id); - if (elem) elem.style.display = 'none'; - } else if (this.lastKey==27) { // Escape - e.stopPropagation(); - searchBox.CloseResultsWindow(); - document.getElementById("MSearchField").focus(); - } else if (this.lastKey==13) { // Enter - return true; - } - return false; - } - - this.NavChild = function(evt,itemIndex,childIndex) { - const e = (evt) ? evt : window.event; // for IE - if (e.keyCode==13) return true; - if (!this.ProcessKeys(e)) return false; - - if (this.lastKey==38) { // Up - if (childIndex>0) { - const newIndex = childIndex-1; - document.getElementById('Item'+itemIndex+'_c'+newIndex).focus(); - } else { // already at first child, jump to parent - document.getElementById('Item'+itemIndex).focus(); - } - } else if (this.lastKey==40) { // Down - const newIndex = childIndex+1; - let elem = document.getElementById('Item'+itemIndex+'_c'+newIndex); - if (!elem) { // last child, jump to parent next parent - elem = this.NavNext(itemIndex+1); - } - if (elem) { - elem.focus(); - } - } else if (this.lastKey==27) { // Escape - e.stopPropagation(); - searchBox.CloseResultsWindow(); - document.getElementById("MSearchField").focus(); - } else if (this.lastKey==13) { // Enter - return true; - } - return false; - } -} - -function createResults(resultsPath) { - - function setKeyActions(elem,action) { - elem.setAttribute('onkeydown',action); - elem.setAttribute('onkeypress',action); - elem.setAttribute('onkeyup',action); - } - - function setClassAttr(elem,attr) { - elem.setAttribute('class',attr); - elem.setAttribute('className',attr); - } - - const results = document.getElementById("SRResults"); - results.innerHTML = ''; - searchData.forEach((elem,index) => { - const id = elem[0]; - const srResult = document.createElement('div'); - srResult.setAttribute('id','SR_'+id); - setClassAttr(srResult,'SRResult'); - const srEntry = document.createElement('div'); - setClassAttr(srEntry,'SREntry'); - const srLink = document.createElement('a'); - srLink.setAttribute('id','Item'+index); - setKeyActions(srLink,'return searchResults.Nav(event,'+index+')'); - setClassAttr(srLink,'SRSymbol'); - srLink.innerHTML = elem[1][0]; - srEntry.appendChild(srLink); - if (elem[1].length==2) { // single result - srLink.setAttribute('href',resultsPath+elem[1][1][0]); - srLink.setAttribute('onclick','searchBox.CloseResultsWindow()'); - if (elem[1][1][1]) { - srLink.setAttribute('target','_parent'); - } else { - srLink.setAttribute('target','_blank'); - } - const srScope = document.createElement('span'); - setClassAttr(srScope,'SRScope'); - srScope.innerHTML = elem[1][1][2]; - srEntry.appendChild(srScope); - } else { // multiple results - srLink.setAttribute('href','javascript:searchResults.Toggle("SR_'+id+'")'); - const srChildren = document.createElement('div'); - setClassAttr(srChildren,'SRChildren'); - for (let c=0; c - - - - - - -esp32_BNO08x: Member List - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - - - - - - diff --git a/documentation/html/struct_b_n_o08x_1_1bno08x__init__status__t.html b/documentation/html/struct_b_n_o08x_1_1bno08x__init__status__t.html deleted file mode 100644 index 7e4dc62..0000000 --- a/documentation/html/struct_b_n_o08x_1_1bno08x__init__status__t.html +++ /dev/null @@ -1,327 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08x::bno08x_init_status_t Struct Reference - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    - -
    BNO08x::bno08x_init_status_t Struct Reference
    -
    -
    - -

    Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup). - More...

    - - - - -

    -Public Member Functions

     bno08x_init_status_t ()
     
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Attributes

    bool gpio_outputs
     True if GPIO outputs have been initialized.
     
    bool gpio_inputs
     True if GPIO inputs have been initialized.
     
    bool isr_service
     True if global ISR service has been initialized.
     
    bool isr_handler
     True if HINT ISR handler has been initialized.
     
    uint8_t task_count
     How many successfully initialized tasks (max of TSK_CNT)
     
    bool data_proc_task
     True if xTaskCreate has been called successfully for data_proc_task.
     
    bool spi_task
     True if xTaskCreate has been called successfully for spi_task.
     
    bool spi_bus
     True if spi_bus_initialize() has been called successfully.
     
    bool spi_device
     True if spi_bus_add_device() has been called successfully.
     
    -

    Detailed Description

    -

    Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup).

    -

    Constructor & Destructor Documentation

    - -

    ◆ bno08x_init_status_t()

    - -
    -
    - - - - - -
    - - - - - - - -
    BNO08x::bno08x_init_status_t::bno08x_init_status_t ()
    -
    -inline
    -
    - -
    -
    -

    Member Data Documentation

    - -

    ◆ data_proc_task

    - -
    -
    - - - - -
    bool BNO08x::bno08x_init_status_t::data_proc_task
    -
    - -

    True if xTaskCreate has been called successfully for data_proc_task.

    - -
    -
    - -

    ◆ gpio_inputs

    - -
    -
    - - - - -
    bool BNO08x::bno08x_init_status_t::gpio_inputs
    -
    - -

    True if GPIO inputs have been initialized.

    - -
    -
    - -

    ◆ gpio_outputs

    - -
    -
    - - - - -
    bool BNO08x::bno08x_init_status_t::gpio_outputs
    -
    - -

    True if GPIO outputs have been initialized.

    - -
    -
    - -

    ◆ isr_handler

    - -
    -
    - - - - -
    bool BNO08x::bno08x_init_status_t::isr_handler
    -
    - -

    True if HINT ISR handler has been initialized.

    - -
    -
    - -

    ◆ isr_service

    - -
    -
    - - - - -
    bool BNO08x::bno08x_init_status_t::isr_service
    -
    - -

    True if global ISR service has been initialized.

    - -
    -
    - -

    ◆ spi_bus

    - -
    -
    - - - - -
    bool BNO08x::bno08x_init_status_t::spi_bus
    -
    - -

    True if spi_bus_initialize() has been called successfully.

    - -
    -
    - -

    ◆ spi_device

    - -
    -
    - - - - -
    bool BNO08x::bno08x_init_status_t::spi_device
    -
    - -

    True if spi_bus_add_device() has been called successfully.

    - -
    -
    - -

    ◆ spi_task

    - -
    -
    - - - - -
    bool BNO08x::bno08x_init_status_t::spi_task
    -
    - -

    True if xTaskCreate has been called successfully for spi_task.

    - -
    -
    - -

    ◆ task_count

    - -
    -
    - - - - -
    uint8_t BNO08x::bno08x_init_status_t::task_count
    -
    - -

    How many successfully initialized tasks (max of TSK_CNT)

    - -
    -
    -
    The documentation for this struct was generated from the following file: -
    -
    - - - - diff --git a/documentation/html/struct_b_n_o08x_1_1bno08x__init__status__t.js b/documentation/html/struct_b_n_o08x_1_1bno08x__init__status__t.js deleted file mode 100644 index d6ba843..0000000 --- a/documentation/html/struct_b_n_o08x_1_1bno08x__init__status__t.js +++ /dev/null @@ -1,13 +0,0 @@ -var struct_b_n_o08x_1_1bno08x__init__status__t = -[ - [ "bno08x_init_status_t", "struct_b_n_o08x_1_1bno08x__init__status__t.html#a26db0bb1cf4ad4272a363c9995cc6851", null ], - [ "data_proc_task", "struct_b_n_o08x_1_1bno08x__init__status__t.html#a04ef18c7f80f305a621b6cc3e5b6107d", null ], - [ "gpio_inputs", "struct_b_n_o08x_1_1bno08x__init__status__t.html#a7439c3e0e98c3c2276f8607e5a36b557", null ], - [ "gpio_outputs", "struct_b_n_o08x_1_1bno08x__init__status__t.html#a918d393541f260ae059614ed477887df", null ], - [ "isr_handler", "struct_b_n_o08x_1_1bno08x__init__status__t.html#aa04ab662c6a1a052944312ca79a17bc3", null ], - [ "isr_service", "struct_b_n_o08x_1_1bno08x__init__status__t.html#a277d28ef5596d4777476d64de3f2d905", null ], - [ "spi_bus", "struct_b_n_o08x_1_1bno08x__init__status__t.html#a9855844dee2cd51e734693294d5cc438", null ], - [ "spi_device", "struct_b_n_o08x_1_1bno08x__init__status__t.html#aa7c583b48551710dd4f71bb5a72c029a", null ], - [ "spi_task", "struct_b_n_o08x_1_1bno08x__init__status__t.html#a92f78cc3fd3161bbc1fcad08b9c6bcb5", null ], - [ "task_count", "struct_b_n_o08x_1_1bno08x__init__status__t.html#a6b2d0002d0e817d6384a1064453eb84d", null ] -]; \ No newline at end of file diff --git a/documentation/html/struct_b_n_o08x_1_1bno08x__report__period__tracker__t-members.html b/documentation/html/struct_b_n_o08x_1_1bno08x__report__period__tracker__t-members.html deleted file mode 100644 index 267080f..0000000 --- a/documentation/html/struct_b_n_o08x_1_1bno08x__report__period__tracker__t-members.html +++ /dev/null @@ -1,112 +0,0 @@ - - - - - - - -esp32_BNO08x: Member List - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    BNO08x::bno08x_report_period_tracker_t Member List
    -
    -
    - -

    This is the complete list of members for BNO08x::bno08x_report_period_tracker_t, including all inherited members.

    - - - -
    periodBNO08x::bno08x_report_period_tracker_t
    report_IDBNO08x::bno08x_report_period_tracker_t
    -
    - - - - diff --git a/documentation/html/struct_b_n_o08x_1_1bno08x__report__period__tracker__t.html b/documentation/html/struct_b_n_o08x_1_1bno08x__report__period__tracker__t.html deleted file mode 100644 index 34415eb..0000000 --- a/documentation/html/struct_b_n_o08x_1_1bno08x__report__period__tracker__t.html +++ /dev/null @@ -1,151 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08x::bno08x_report_period_tracker_t Struct Reference - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    - -
    BNO08x::bno08x_report_period_tracker_t Struct Reference
    -
    -
    - - - - - - -

    -Public Attributes

    uint8_t report_ID
     
    uint32_t period
     
    -

    Member Data Documentation

    - -

    ◆ period

    - -
    -
    - - - - -
    uint32_t BNO08x::bno08x_report_period_tracker_t::period
    -
    - -
    -
    - -

    ◆ report_ID

    - -
    -
    - - - - -
    uint8_t BNO08x::bno08x_report_period_tracker_t::report_ID
    -
    - -
    -
    -
    The documentation for this struct was generated from the following file: -
    -
    - - - - diff --git a/documentation/html/struct_b_n_o08x_1_1bno08x__report__period__tracker__t.js b/documentation/html/struct_b_n_o08x_1_1bno08x__report__period__tracker__t.js deleted file mode 100644 index b72fb09..0000000 --- a/documentation/html/struct_b_n_o08x_1_1bno08x__report__period__tracker__t.js +++ /dev/null @@ -1,5 +0,0 @@ -var struct_b_n_o08x_1_1bno08x__report__period__tracker__t = -[ - [ "period", "struct_b_n_o08x_1_1bno08x__report__period__tracker__t.html#a7fe1403bb26f5f4dd845df019bac8614", null ], - [ "report_ID", "struct_b_n_o08x_1_1bno08x__report__period__tracker__t.html#a05dd1697e0b5fda59d112af2c396295c", null ] -]; \ No newline at end of file diff --git a/documentation/html/struct_b_n_o08x_1_1bno08x__rx__packet__t-members.html b/documentation/html/struct_b_n_o08x_1_1bno08x__rx__packet__t-members.html deleted file mode 100644 index e9e67a7..0000000 --- a/documentation/html/struct_b_n_o08x_1_1bno08x__rx__packet__t-members.html +++ /dev/null @@ -1,113 +0,0 @@ - - - - - - - -esp32_BNO08x: Member List - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    BNO08x::bno08x_rx_packet_t Member List
    -
    -
    - -

    This is the complete list of members for BNO08x::bno08x_rx_packet_t, including all inherited members.

    - - - - -
    bodyBNO08x::bno08x_rx_packet_t
    headerBNO08x::bno08x_rx_packet_t
    lengthBNO08x::bno08x_rx_packet_t
    -
    - - - - diff --git a/documentation/html/struct_b_n_o08x_1_1bno08x__rx__packet__t.html b/documentation/html/struct_b_n_o08x_1_1bno08x__rx__packet__t.html deleted file mode 100644 index e21362f..0000000 --- a/documentation/html/struct_b_n_o08x_1_1bno08x__rx__packet__t.html +++ /dev/null @@ -1,179 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08x::bno08x_rx_packet_t Struct Reference - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    - -
    BNO08x::bno08x_rx_packet_t Struct Reference
    -
    -
    - -

    Holds data that is received over spi. - More...

    - - - - - - - - - - -

    -Public Attributes

    uint8_t header [4]
     Header of SHTP packet.
     
    uint8_t body [300]
     
    uint16_t length
     Body of SHTP packet.
     
    -

    Detailed Description

    -

    Holds data that is received over spi.

    -

    Member Data Documentation

    - -

    ◆ body

    - -
    -
    - - - - -
    uint8_t BNO08x::bno08x_rx_packet_t::body[300]
    -
    - -
    -
    - -

    ◆ header

    - -
    -
    - - - - -
    uint8_t BNO08x::bno08x_rx_packet_t::header[4]
    -
    - -

    Header of SHTP packet.

    - -
    -
    - -

    ◆ length

    - -
    -
    - - - - -
    uint16_t BNO08x::bno08x_rx_packet_t::length
    -
    - -

    Body of SHTP packet.

    -

    Packet length in bytes.

    - -
    -
    -
    The documentation for this struct was generated from the following file: -
    -
    - - - - diff --git a/documentation/html/struct_b_n_o08x_1_1bno08x__rx__packet__t.js b/documentation/html/struct_b_n_o08x_1_1bno08x__rx__packet__t.js deleted file mode 100644 index ea3522a..0000000 --- a/documentation/html/struct_b_n_o08x_1_1bno08x__rx__packet__t.js +++ /dev/null @@ -1,6 +0,0 @@ -var struct_b_n_o08x_1_1bno08x__rx__packet__t = -[ - [ "body", "struct_b_n_o08x_1_1bno08x__rx__packet__t.html#ab422d75e1fcd776ef412f4d623cc293e", null ], - [ "header", "struct_b_n_o08x_1_1bno08x__rx__packet__t.html#a667d671ccb272bd375008716e26e0b5b", null ], - [ "length", "struct_b_n_o08x_1_1bno08x__rx__packet__t.html#a645adb6ba8fb2afbb99ec58fe678e205", null ] -]; \ No newline at end of file diff --git a/documentation/html/struct_b_n_o08x_1_1bno08x__tx__packet__t-members.html b/documentation/html/struct_b_n_o08x_1_1bno08x__tx__packet__t-members.html deleted file mode 100644 index f6ca3fe..0000000 --- a/documentation/html/struct_b_n_o08x_1_1bno08x__tx__packet__t-members.html +++ /dev/null @@ -1,112 +0,0 @@ - - - - - - - -esp32_BNO08x: Member List - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    BNO08x::bno08x_tx_packet_t Member List
    -
    -
    - -

    This is the complete list of members for BNO08x::bno08x_tx_packet_t, including all inherited members.

    - - - -
    bodyBNO08x::bno08x_tx_packet_t
    lengthBNO08x::bno08x_tx_packet_t
    -
    - - - - diff --git a/documentation/html/struct_b_n_o08x_1_1bno08x__tx__packet__t.html b/documentation/html/struct_b_n_o08x_1_1bno08x__tx__packet__t.html deleted file mode 100644 index 9bbe6fa..0000000 --- a/documentation/html/struct_b_n_o08x_1_1bno08x__tx__packet__t.html +++ /dev/null @@ -1,162 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08x::bno08x_tx_packet_t Struct Reference - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    - -
    BNO08x::bno08x_tx_packet_t Struct Reference
    -
    -
    - -

    Holds data that is sent over spi. - More...

    - - - - - - - - -

    -Public Attributes

    uint8_t body [50]
     Body of SHTP the packet (header + body)
     
    uint16_t length
     Packet length in bytes.
     
    -

    Detailed Description

    -

    Holds data that is sent over spi.

    -

    Member Data Documentation

    - -

    ◆ body

    - -
    -
    - - - - -
    uint8_t BNO08x::bno08x_tx_packet_t::body[50]
    -
    - -

    Body of SHTP the packet (header + body)

    - -
    -
    - -

    ◆ length

    - -
    -
    - - - - -
    uint16_t BNO08x::bno08x_tx_packet_t::length
    -
    - -

    Packet length in bytes.

    - -
    -
    -
    The documentation for this struct was generated from the following file: -
    -
    - - - - diff --git a/documentation/html/struct_b_n_o08x_1_1bno08x__tx__packet__t.js b/documentation/html/struct_b_n_o08x_1_1bno08x__tx__packet__t.js deleted file mode 100644 index ab42188..0000000 --- a/documentation/html/struct_b_n_o08x_1_1bno08x__tx__packet__t.js +++ /dev/null @@ -1,5 +0,0 @@ -var struct_b_n_o08x_1_1bno08x__tx__packet__t = -[ - [ "body", "struct_b_n_o08x_1_1bno08x__tx__packet__t.html#a4478c6cd9e87907eacc56dd06ad4a69d", null ], - [ "length", "struct_b_n_o08x_1_1bno08x__tx__packet__t.html#a73180537ea7605340c5e6b2132e2cbf5", null ] -]; \ No newline at end of file diff --git a/documentation/html/struct_b_n_o08x_test_helper_1_1imu__report__data__t-members.html b/documentation/html/struct_b_n_o08x_test_helper_1_1imu__report__data__t-members.html deleted file mode 100644 index a91a2f6..0000000 --- a/documentation/html/struct_b_n_o08x_test_helper_1_1imu__report__data__t-members.html +++ /dev/null @@ -1,151 +0,0 @@ - - - - - - - -esp32_BNO08x: Member List - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    BNO08xTestHelper::imu_report_data_t Member List
    -
    -
    - -

    This is the complete list of members for BNO08xTestHelper::imu_report_data_t, including all inherited members.

    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    accel_accuracyBNO08xTestHelper::imu_report_data_t
    accel_xBNO08xTestHelper::imu_report_data_t
    accel_yBNO08xTestHelper::imu_report_data_t
    accel_zBNO08xTestHelper::imu_report_data_t
    activity_classifierBNO08xTestHelper::imu_report_data_t
    calib_gyro_vel_xBNO08xTestHelper::imu_report_data_t
    calib_gyro_vel_yBNO08xTestHelper::imu_report_data_t
    calib_gyro_vel_zBNO08xTestHelper::imu_report_data_t
    grav_accuracyBNO08xTestHelper::imu_report_data_t
    grav_xBNO08xTestHelper::imu_report_data_t
    grav_yBNO08xTestHelper::imu_report_data_t
    grav_zBNO08xTestHelper::imu_report_data_t
    integrated_gyro_vel_xBNO08xTestHelper::imu_report_data_t
    integrated_gyro_vel_yBNO08xTestHelper::imu_report_data_t
    integrated_gyro_vel_zBNO08xTestHelper::imu_report_data_t
    lin_accel_accuracyBNO08xTestHelper::imu_report_data_t
    lin_accel_xBNO08xTestHelper::imu_report_data_t
    lin_accel_yBNO08xTestHelper::imu_report_data_t
    lin_accel_zBNO08xTestHelper::imu_report_data_t
    magf_accuracyBNO08xTestHelper::imu_report_data_t
    magf_xBNO08xTestHelper::imu_report_data_t
    magf_yBNO08xTestHelper::imu_report_data_t
    magf_zBNO08xTestHelper::imu_report_data_t
    quat_accuracyBNO08xTestHelper::imu_report_data_t
    quat_IBNO08xTestHelper::imu_report_data_t
    quat_JBNO08xTestHelper::imu_report_data_t
    quat_KBNO08xTestHelper::imu_report_data_t
    quat_radian_accuracyBNO08xTestHelper::imu_report_data_t
    quat_realBNO08xTestHelper::imu_report_data_t
    raw_mems_gyro_xBNO08xTestHelper::imu_report_data_t
    raw_mems_gyro_yBNO08xTestHelper::imu_report_data_t
    raw_mems_gyro_zBNO08xTestHelper::imu_report_data_t
    stability_classifierBNO08xTestHelper::imu_report_data_t
    step_countBNO08xTestHelper::imu_report_data_t
    time_stampBNO08xTestHelper::imu_report_data_t
    uncalib_gyro_drift_xBNO08xTestHelper::imu_report_data_t
    uncalib_gyro_drift_yBNO08xTestHelper::imu_report_data_t
    uncalib_gyro_drift_zBNO08xTestHelper::imu_report_data_t
    uncalib_gyro_vel_xBNO08xTestHelper::imu_report_data_t
    uncalib_gyro_vel_yBNO08xTestHelper::imu_report_data_t
    uncalib_gyro_vel_zBNO08xTestHelper::imu_report_data_t
    -
    - - - - diff --git a/documentation/html/struct_b_n_o08x_test_helper_1_1imu__report__data__t.html b/documentation/html/struct_b_n_o08x_test_helper_1_1imu__report__data__t.html deleted file mode 100644 index 44c317c..0000000 --- a/documentation/html/struct_b_n_o08x_test_helper_1_1imu__report__data__t.html +++ /dev/null @@ -1,782 +0,0 @@ - - - - - - - -esp32_BNO08x: BNO08xTestHelper::imu_report_data_t Struct Reference - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    - -
    BNO08xTestHelper::imu_report_data_t Struct Reference
    -
    -
    - -

    IMU configuration settings passed into constructor. - More...

    - -

    #include <BNO08xTestHelper.hpp>

    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Attributes

    uint32_t time_stamp
     
    float quat_I
     
    float quat_J
     
    float quat_K
     
    float quat_real
     
    float quat_radian_accuracy
     
    BNO08xAccuracy quat_accuracy
     
    float integrated_gyro_vel_x
     
    float integrated_gyro_vel_y
     
    float integrated_gyro_vel_z
     
    float accel_x
     
    float accel_y
     
    float accel_z
     
    BNO08xAccuracy accel_accuracy
     
    float lin_accel_x
     
    float lin_accel_y
     
    float lin_accel_z
     
    BNO08xAccuracy lin_accel_accuracy
     
    float grav_x
     
    float grav_y
     
    float grav_z
     
    BNO08xAccuracy grav_accuracy
     
    float calib_gyro_vel_x
     
    float calib_gyro_vel_y
     
    float calib_gyro_vel_z
     
    float uncalib_gyro_vel_x
     
    float uncalib_gyro_vel_y
     
    float uncalib_gyro_vel_z
     
    float uncalib_gyro_drift_x
     
    float uncalib_gyro_drift_y
     
    float uncalib_gyro_drift_z
     
    float magf_x
     
    float magf_y
     
    float magf_z
     
    BNO08xAccuracy magf_accuracy
     
    uint16_t raw_mems_gyro_x
     
    uint16_t raw_mems_gyro_y
     
    uint16_t raw_mems_gyro_z
     
    uint16_t step_count
     
    BNO08xStability stability_classifier
     
    BNO08xActivity activity_classifier
     
    -

    Detailed Description

    -

    IMU configuration settings passed into constructor.

    -

    Member Data Documentation

    - -

    ◆ accel_accuracy

    - -
    -
    - - - - -
    BNO08xAccuracy BNO08xTestHelper::imu_report_data_t::accel_accuracy
    -
    - -
    -
    - -

    ◆ accel_x

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::accel_x
    -
    - -
    -
    - -

    ◆ accel_y

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::accel_y
    -
    - -
    -
    - -

    ◆ accel_z

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::accel_z
    -
    - -
    -
    - -

    ◆ activity_classifier

    - -
    -
    - - - - -
    BNO08xActivity BNO08xTestHelper::imu_report_data_t::activity_classifier
    -
    - -
    -
    - -

    ◆ calib_gyro_vel_x

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::calib_gyro_vel_x
    -
    - -
    -
    - -

    ◆ calib_gyro_vel_y

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::calib_gyro_vel_y
    -
    - -
    -
    - -

    ◆ calib_gyro_vel_z

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::calib_gyro_vel_z
    -
    - -
    -
    - -

    ◆ grav_accuracy

    - -
    -
    - - - - -
    BNO08xAccuracy BNO08xTestHelper::imu_report_data_t::grav_accuracy
    -
    - -
    -
    - -

    ◆ grav_x

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::grav_x
    -
    - -
    -
    - -

    ◆ grav_y

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::grav_y
    -
    - -
    -
    - -

    ◆ grav_z

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::grav_z
    -
    - -
    -
    - -

    ◆ integrated_gyro_vel_x

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::integrated_gyro_vel_x
    -
    - -
    -
    - -

    ◆ integrated_gyro_vel_y

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::integrated_gyro_vel_y
    -
    - -
    -
    - -

    ◆ integrated_gyro_vel_z

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::integrated_gyro_vel_z
    -
    - -
    -
    - -

    ◆ lin_accel_accuracy

    - -
    -
    - - - - -
    BNO08xAccuracy BNO08xTestHelper::imu_report_data_t::lin_accel_accuracy
    -
    - -
    -
    - -

    ◆ lin_accel_x

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::lin_accel_x
    -
    - -
    -
    - -

    ◆ lin_accel_y

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::lin_accel_y
    -
    - -
    -
    - -

    ◆ lin_accel_z

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::lin_accel_z
    -
    - -
    -
    - -

    ◆ magf_accuracy

    - -
    -
    - - - - -
    BNO08xAccuracy BNO08xTestHelper::imu_report_data_t::magf_accuracy
    -
    - -
    -
    - -

    ◆ magf_x

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::magf_x
    -
    - -
    -
    - -

    ◆ magf_y

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::magf_y
    -
    - -
    -
    - -

    ◆ magf_z

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::magf_z
    -
    - -
    -
    - -

    ◆ quat_accuracy

    - -
    -
    - - - - -
    BNO08xAccuracy BNO08xTestHelper::imu_report_data_t::quat_accuracy
    -
    - -
    -
    - -

    ◆ quat_I

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::quat_I
    -
    - -
    -
    - -

    ◆ quat_J

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::quat_J
    -
    - -
    -
    - -

    ◆ quat_K

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::quat_K
    -
    - -
    -
    - -

    ◆ quat_radian_accuracy

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::quat_radian_accuracy
    -
    - -
    -
    - -

    ◆ quat_real

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::quat_real
    -
    - -
    -
    - -

    ◆ raw_mems_gyro_x

    - -
    -
    - - - - -
    uint16_t BNO08xTestHelper::imu_report_data_t::raw_mems_gyro_x
    -
    - -
    -
    - -

    ◆ raw_mems_gyro_y

    - -
    -
    - - - - -
    uint16_t BNO08xTestHelper::imu_report_data_t::raw_mems_gyro_y
    -
    - -
    -
    - -

    ◆ raw_mems_gyro_z

    - -
    -
    - - - - -
    uint16_t BNO08xTestHelper::imu_report_data_t::raw_mems_gyro_z
    -
    - -
    -
    - -

    ◆ stability_classifier

    - -
    -
    - - - - -
    BNO08xStability BNO08xTestHelper::imu_report_data_t::stability_classifier
    -
    - -
    -
    - -

    ◆ step_count

    - -
    -
    - - - - -
    uint16_t BNO08xTestHelper::imu_report_data_t::step_count
    -
    - -
    -
    - -

    ◆ time_stamp

    - -
    -
    - - - - -
    uint32_t BNO08xTestHelper::imu_report_data_t::time_stamp
    -
    - -
    -
    - -

    ◆ uncalib_gyro_drift_x

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::uncalib_gyro_drift_x
    -
    - -
    -
    - -

    ◆ uncalib_gyro_drift_y

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::uncalib_gyro_drift_y
    -
    - -
    -
    - -

    ◆ uncalib_gyro_drift_z

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::uncalib_gyro_drift_z
    -
    - -
    -
    - -

    ◆ uncalib_gyro_vel_x

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::uncalib_gyro_vel_x
    -
    - -
    -
    - -

    ◆ uncalib_gyro_vel_y

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::uncalib_gyro_vel_y
    -
    - -
    -
    - -

    ◆ uncalib_gyro_vel_z

    - -
    -
    - - - - -
    float BNO08xTestHelper::imu_report_data_t::uncalib_gyro_vel_z
    -
    - -
    -
    -
    The documentation for this struct was generated from the following file: -
    -
    - - - - diff --git a/documentation/html/struct_b_n_o08x_test_helper_1_1imu__report__data__t.js b/documentation/html/struct_b_n_o08x_test_helper_1_1imu__report__data__t.js deleted file mode 100644 index e6b0f51..0000000 --- a/documentation/html/struct_b_n_o08x_test_helper_1_1imu__report__data__t.js +++ /dev/null @@ -1,44 +0,0 @@ -var struct_b_n_o08x_test_helper_1_1imu__report__data__t = -[ - [ "accel_accuracy", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac5d393de0f15176ba81bc63a80b49ca3", null ], - [ "accel_x", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5c01b349cc9e4e45c78c576882d633fd", null ], - [ "accel_y", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e594d0a1e86fb575f72c6f330c8983c", null ], - [ "accel_z", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af134cb789c29120033d81916e0c100d4", null ], - [ "activity_classifier", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0455033deba9570f248e8059cf6a3ce1", null ], - [ "calib_gyro_vel_x", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a89b427579a281440ab94a340c0ec8443", null ], - [ "calib_gyro_vel_y", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af9e11fd749123f5723b2e281c8d2fd16", null ], - [ "calib_gyro_vel_z", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a769ddae74a6c89a2d319c28f95ed6479", null ], - [ "grav_accuracy", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a735d099f3dd0ead4b8d986fd139af43d", null ], - [ "grav_x", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ad2c17ea111250ebc1a4a763dae3c072a", null ], - [ "grav_y", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a19fc4af8a26c10a027cbd859d67dba4a", null ], - [ "grav_z", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af1887bdfef4fc2c683fe2134cb5cfb50", null ], - [ "integrated_gyro_vel_x", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a077a94b4de0b5c280d69611325208cf7", null ], - [ "integrated_gyro_vel_y", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af4b75b320bc390c90656905711f1c791", null ], - [ "integrated_gyro_vel_z", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a1aa67da9c3c6449dfce361a528c418d3", null ], - [ "lin_accel_accuracy", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a48a249994c27f59ca4167b56bdda311a", null ], - [ "lin_accel_x", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3a62ed280657cd409d723e64f0c313b5", null ], - [ "lin_accel_y", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a553942aa784c35c833543ecc9a05f606", null ], - [ "lin_accel_z", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5bf43fc0daf3a86954924e066cad3a9b", null ], - [ "magf_accuracy", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0c962609a3bf7927204542521e9c5113", null ], - [ "magf_x", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0e72f6dde1411e4aa1c616cedcc556c1", null ], - [ "magf_y", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8738f60a2b9bd49d2b8dd0487db7ac97", null ], - [ "magf_z", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a55187ebe06fa77def93681bcdf62595c", null ], - [ "quat_accuracy", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#aac84ad10b65403ae1ee21dab5cdc77db", null ], - [ "quat_I", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8d2c3cd33943cb1b4fd0e800f822607e", null ], - [ "quat_J", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a20a09d197d5128aae64b7449df576c27", null ], - [ "quat_K", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3c74d4c93fc4390f52b75e6ff2bea95b", null ], - [ "quat_radian_accuracy", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae0a8fef0227dd4304d08466c43d901a5", null ], - [ "quat_real", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a80525c4943154f825a62539b10337976", null ], - [ "raw_mems_gyro_x", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a94befe7132d3a6a6ce2a7890e96ec091", null ], - [ "raw_mems_gyro_y", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e9cd7e43d70932c5f84e3cfadf8bb47", null ], - [ "raw_mems_gyro_z", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a9df84179bd44a7febfa1058afe3dad6c", null ], - [ "stability_classifier", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a86473c2bd8cbe2c76276393ee20d568b", null ], - [ "step_count", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae8435a931eac7f4376a94acfcbf6a784", null ], - [ "time_stamp", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae5e8705ad014ed3f70e5de527cb2cb66", null ], - [ "uncalib_gyro_drift_x", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac70a65027c3e740eca2b1f172b7cefa3", null ], - [ "uncalib_gyro_drift_y", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a29d5ae3e0ed3463cb9297f9cdc0e8472", null ], - [ "uncalib_gyro_drift_z", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a27b52e2d96cb948c4257de4553053f72", null ], - [ "uncalib_gyro_vel_x", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a292b1c36fed6a9c9742edf730299c4f4", null ], - [ "uncalib_gyro_vel_y", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#adfd6bf2e2264cf25bd02814446600ab4", null ], - [ "uncalib_gyro_vel_z", "struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ab39fd6f409288bb35fb1542ff4b9cbe4", null ] -]; \ No newline at end of file diff --git a/documentation/html/structbno08x__config__t-members.html b/documentation/html/structbno08x__config__t-members.html deleted file mode 100644 index f858774..0000000 --- a/documentation/html/structbno08x__config__t-members.html +++ /dev/null @@ -1,122 +0,0 @@ - - - - - - - -esp32_BNO08x: Member List - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    -
    bno08x_config_t Member List
    -
    -
    - -

    This is the complete list of members for bno08x_config_t, including all inherited members.

    - - - - - - - - - - - - - -
    bno08x_config_t(bool install_isr_service=true)bno08x_config_tinline
    bno08x_config_t(spi_host_device_t spi_peripheral, gpio_num_t io_mosi, gpio_num_t io_miso, gpio_num_t io_sclk, gpio_num_t io_cs, gpio_num_t io_int, gpio_num_t io_rst, gpio_num_t io_wake, uint32_t sclk_speed, bool install_isr_service=true)bno08x_config_tinline
    install_isr_servicebno08x_config_t
    io_csbno08x_config_t
    io_intbno08x_config_t
    io_misobno08x_config_t
    io_mosibno08x_config_t
    io_rstbno08x_config_t
    io_sclkbno08x_config_t
    io_wakebno08x_config_t
    sclk_speedbno08x_config_t
    spi_peripheralbno08x_config_t
    -
    - - - - diff --git a/documentation/html/structbno08x__config__t.html b/documentation/html/structbno08x__config__t.html deleted file mode 100644 index 2b5c0fe..0000000 --- a/documentation/html/structbno08x__config__t.html +++ /dev/null @@ -1,423 +0,0 @@ - - - - - - - -esp32_BNO08x: bno08x_config_t Struct Reference - - - - - - - - - - - - - - - -
    -
    - - - - - - -
    -
    esp32_BNO08x 1.2 -
    -
    C++ BNO08x IMU driver component for esp-idf.
    -
    -
    - - - - - - - -
    -
    - -
    -
    -
    - -
    - -
    -
    - - -
    -
    -
    -
    -
    -
    Loading...
    -
    Searching...
    -
    No Matches
    -
    -
    -
    -
    - -
    - -
    bno08x_config_t Struct Reference
    -
    -
    - -

    IMU configuration settings passed into constructor. - More...

    - -

    #include <BNO08x_global_types.hpp>

    - - - - - - - - -

    -Public Member Functions

     bno08x_config_t (bool install_isr_service=true)
     Default IMU configuration settings constructor. To modify default GPIO pins, run "idf.py menuconfig" esp32_BNO08x->GPIO Configuration. Alternatively, edit the default values in "Kconfig.projbuild".
     
     bno08x_config_t (spi_host_device_t spi_peripheral, gpio_num_t io_mosi, gpio_num_t io_miso, gpio_num_t io_sclk, gpio_num_t io_cs, gpio_num_t io_int, gpio_num_t io_rst, gpio_num_t io_wake, uint32_t sclk_speed, bool install_isr_service=true)
     Overloaded IMU configuration settings constructor for custom pin settings.
     
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -

    -Public Attributes

    spi_host_device_t spi_peripheral
     SPI peripheral to be used.
     
    gpio_num_t io_mosi
     MOSI GPIO pin (connects to BNO08x DI pin)
     
    gpio_num_t io_miso
     MISO GPIO pin (connects to BNO08x SDA pin)
     
    gpio_num_t io_sclk
     SCLK pin (connects to BNO08x SCL pin)
     
    gpio_num_t io_cs
     
    gpio_num_t io_int
     Chip select pin (connects to BNO08x CS pin)
     
    gpio_num_t io_rst
     Host interrupt pin (connects to BNO08x INT pin)
     
    gpio_num_t io_wake
     Reset pin (connects to BNO08x RST pin)
     
    uint32_t sclk_speed
     Desired SPI SCLK speed in Hz (max 3MHz)
     
    bool install_isr_service
     Indicates whether the ISR service for the HINT should be installed at IMU initialization, (if gpio_install_isr_service() is called before initialize() set this to false)
     
    -

    Detailed Description

    -

    IMU configuration settings passed into constructor.

    -

    Constructor & Destructor Documentation

    - -

    ◆ bno08x_config_t() [1/2]

    - -
    -
    - - - - - -
    - - - - - - - -
    bno08x_config_t::bno08x_config_t (bool install_isr_service = true)
    -
    -inline
    -
    - -

    Default IMU configuration settings constructor. To modify default GPIO pins, run "idf.py menuconfig" esp32_BNO08x->GPIO Configuration. Alternatively, edit the default values in "Kconfig.projbuild".

    - -
    -
    - -

    ◆ bno08x_config_t() [2/2]

    - -
    -
    - - - - - -
    - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - -
    bno08x_config_t::bno08x_config_t (spi_host_device_t spi_peripheral,
    gpio_num_t io_mosi,
    gpio_num_t io_miso,
    gpio_num_t io_sclk,
    gpio_num_t io_cs,
    gpio_num_t io_int,
    gpio_num_t io_rst,
    gpio_num_t io_wake,
    uint32_t sclk_speed,
    bool install_isr_service = true )
    -
    -inline
    -
    - -

    Overloaded IMU configuration settings constructor for custom pin settings.

    - -
    -
    -

    Member Data Documentation

    - -

    ◆ install_isr_service

    - -
    -
    - - - - -
    bool bno08x_config_t::install_isr_service
    -
    - -

    Indicates whether the ISR service for the HINT should be installed at IMU initialization, (if gpio_install_isr_service() is called before initialize() set this to false)

    - -
    -
    - -

    ◆ io_cs

    - -
    -
    - - - - -
    gpio_num_t bno08x_config_t::io_cs
    -
    - -
    -
    - -

    ◆ io_int

    - -
    -
    - - - - -
    gpio_num_t bno08x_config_t::io_int
    -
    - -

    Chip select pin (connects to BNO08x CS pin)

    - -
    -
    - -

    ◆ io_miso

    - -
    -
    - - - - -
    gpio_num_t bno08x_config_t::io_miso
    -
    - -

    MISO GPIO pin (connects to BNO08x SDA pin)

    - -
    -
    - -

    ◆ io_mosi

    - -
    -
    - - - - -
    gpio_num_t bno08x_config_t::io_mosi
    -
    - -

    MOSI GPIO pin (connects to BNO08x DI pin)

    - -
    -
    - -

    ◆ io_rst

    - -
    -
    - - - - -
    gpio_num_t bno08x_config_t::io_rst
    -
    - -

    Host interrupt pin (connects to BNO08x INT pin)

    - -
    -
    - -

    ◆ io_sclk

    - -
    -
    - - - - -
    gpio_num_t bno08x_config_t::io_sclk
    -
    - -

    SCLK pin (connects to BNO08x SCL pin)

    - -
    -
    - -

    ◆ io_wake

    - -
    -
    - - - - -
    gpio_num_t bno08x_config_t::io_wake
    -
    - -

    Reset pin (connects to BNO08x RST pin)

    -

    Wake pin (optional, connects to BNO08x P0)

    - -
    -
    - -

    ◆ sclk_speed

    - -
    -
    - - - - -
    uint32_t bno08x_config_t::sclk_speed
    -
    - -

    Desired SPI SCLK speed in Hz (max 3MHz)

    - -
    -
    - -

    ◆ spi_peripheral

    - -
    -
    - - - - -
    spi_host_device_t bno08x_config_t::spi_peripheral
    -
    - -

    SPI peripheral to be used.

    - -
    -
    -
    The documentation for this struct was generated from the following file: -
    -
    - - - - diff --git a/documentation/html/structbno08x__config__t.js b/documentation/html/structbno08x__config__t.js deleted file mode 100644 index f2dbefb..0000000 --- a/documentation/html/structbno08x__config__t.js +++ /dev/null @@ -1,15 +0,0 @@ -var structbno08x__config__t = -[ - [ "bno08x_config_t", "structbno08x__config__t.html#a68e051212415a62e64c23678e7b40552", null ], - [ "bno08x_config_t", "structbno08x__config__t.html#a3a4ef8ef437403592278110a73cafe70", null ], - [ "install_isr_service", "structbno08x__config__t.html#a0f629aaef6756aa80fec96b34476c627", null ], - [ "io_cs", "structbno08x__config__t.html#ab1b5351b63da0c172c942463d0dc2505", null ], - [ "io_int", "structbno08x__config__t.html#a3cfe965659cfbc6b0c5269bd0211975f", null ], - [ "io_miso", "structbno08x__config__t.html#a9468180a773892977db39cc5ed9368e3", null ], - [ "io_mosi", "structbno08x__config__t.html#a79023fd80039e41a22b7f73ccd5fc861", null ], - [ "io_rst", "structbno08x__config__t.html#a62745c761219139f66ecd173b51577fc", null ], - [ "io_sclk", "structbno08x__config__t.html#a639685b91ae3198909d722316495246a", null ], - [ "io_wake", "structbno08x__config__t.html#a90ad7f316dc443874d19dc7e723a0ce0", null ], - [ "sclk_speed", "structbno08x__config__t.html#a231614c3b20888360def2ce9db83f52a", null ], - [ "spi_peripheral", "structbno08x__config__t.html#a020d2343750bb7debc2a108ae038c9ec", null ] -]; \ No newline at end of file diff --git a/documentation/html/sync_off.png b/documentation/html/sync_off.png deleted file mode 100644 index 3b443fc..0000000 Binary files a/documentation/html/sync_off.png and /dev/null differ diff --git a/documentation/html/sync_on.png b/documentation/html/sync_on.png deleted file mode 100644 index e08320f..0000000 Binary files a/documentation/html/sync_on.png and /dev/null differ diff --git a/documentation/html/tab_a.png b/documentation/html/tab_a.png deleted file mode 100644 index 3b725c4..0000000 Binary files a/documentation/html/tab_a.png and /dev/null differ diff --git a/documentation/html/tab_ad.png b/documentation/html/tab_ad.png deleted file mode 100644 index e34850a..0000000 Binary files a/documentation/html/tab_ad.png and /dev/null differ diff --git a/documentation/html/tab_b.png b/documentation/html/tab_b.png deleted file mode 100644 index e2b4a86..0000000 Binary files a/documentation/html/tab_b.png and /dev/null differ diff --git a/documentation/html/tab_bd.png b/documentation/html/tab_bd.png deleted file mode 100644 index 91c2524..0000000 Binary files a/documentation/html/tab_bd.png and /dev/null differ diff --git a/documentation/html/tab_h.png b/documentation/html/tab_h.png deleted file mode 100644 index fd5cb70..0000000 Binary files a/documentation/html/tab_h.png and /dev/null differ diff --git a/documentation/html/tab_hd.png b/documentation/html/tab_hd.png deleted file mode 100644 index 2489273..0000000 Binary files a/documentation/html/tab_hd.png and /dev/null differ diff --git a/documentation/html/tab_s.png b/documentation/html/tab_s.png deleted file mode 100644 index ab478c9..0000000 Binary files a/documentation/html/tab_s.png and /dev/null differ diff --git a/documentation/html/tab_sd.png b/documentation/html/tab_sd.png deleted file mode 100644 index 757a565..0000000 Binary files a/documentation/html/tab_sd.png and /dev/null differ diff --git a/documentation/html/tabs.css b/documentation/html/tabs.css deleted file mode 100644 index fe4854a..0000000 --- a/documentation/html/tabs.css +++ /dev/null @@ -1 +0,0 @@ -.sm{position:relative;z-index:9999}.sm,.sm ul,.sm li{display:block;list-style:none;margin:0;padding:0;line-height:normal;direction:ltr;text-align:left;-webkit-tap-highlight-color:rgba(0,0,0,0)}.sm-rtl,.sm-rtl ul,.sm-rtl li{direction:rtl;text-align:right}.sm>li>h1,.sm>li>h2,.sm>li>h3,.sm>li>h4,.sm>li>h5,.sm>li>h6{margin:0;padding:0}.sm ul{display:none}.sm li,.sm a{position:relative}.sm a{display:block}.sm a.disabled{cursor:not-allowed}.sm:after{content:"\00a0";display:block;height:0;font:0/0 serif;clear:both;visibility:hidden;overflow:hidden}.sm,.sm *,.sm *:before,.sm *:after{-moz-box-sizing:border-box;-webkit-box-sizing:border-box;box-sizing:border-box}.main-menu-btn{position:relative;display:inline-block;width:36px;height:36px;text-indent:36px;margin-left:8px;white-space:nowrap;overflow:hidden;cursor:pointer;-webkit-tap-highlight-color:rgba(0,0,0,0)}.main-menu-btn-icon,.main-menu-btn-icon:before,.main-menu-btn-icon:after{position:absolute;top:50%;left:2px;height:2px;width:24px;background:var(--nav-menu-button-color);-webkit-transition:all .25s;transition:all .25s}.main-menu-btn-icon:before{content:'';top:-7px;left:0}.main-menu-btn-icon:after{content:'';top:7px;left:0}#main-menu-state:checked ~ .main-menu-btn .main-menu-btn-icon{height:0}#main-menu-state:checked ~ .main-menu-btn .main-menu-btn-icon:before{top:0;-webkit-transform:rotate(-45deg);transform:rotate(-45deg)}#main-menu-state:checked ~ .main-menu-btn .main-menu-btn-icon:after{top:0;-webkit-transform:rotate(45deg);transform:rotate(45deg)}#main-menu-state{position:absolute;width:1px;height:1px;margin:-1px;border:0;padding:0;overflow:hidden;clip:rect(1px,1px,1px,1px)}#main-menu-state:not(:checked) ~ #main-menu{display:none}#main-menu-state:checked ~ #main-menu{display:block}@media(min-width:768px){.main-menu-btn{position:absolute;top:-99999px}#main-menu-state:not(:checked) ~ #main-menu{display:block}}.sm-dox{background-image:var(--nav-gradient-image)}.sm-dox a,.sm-dox a:focus,.sm-dox a:hover,.sm-dox a:active{padding:0 12px;padding-right:43px;font-family:var(--font-family-nav);font-size:13px;font-weight:bold;line-height:36px;text-decoration:none;text-shadow:var(--nav-text-normal-shadow);color:var(--nav-text-normal-color);outline:0}.sm-dox a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:var(--nav-text-hover-shadow)}.sm-dox a.current{color:#d23600}.sm-dox a.disabled{color:#bbb}.sm-dox a span.sub-arrow{position:absolute;top:50%;margin-top:-14px;left:auto;right:3px;width:28px;height:28px;overflow:hidden;font:bold 12px/28px monospace !important;text-align:center;text-shadow:none;background:var(--nav-menu-toggle-color);-moz-border-radius:5px;-webkit-border-radius:5px;border-radius:5px}.sm-dox a span.sub-arrow:before{display:block;content:'+'}.sm-dox a.highlighted span.sub-arrow:before{display:block;content:'-'}.sm-dox>li:first-child>a,.sm-dox>li:first-child>:not(ul) a{-moz-border-radius:5px 5px 0 0;-webkit-border-radius:5px;border-radius:5px 5px 0 0}.sm-dox>li:last-child>a,.sm-dox>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul{-moz-border-radius:0 0 5px 5px;-webkit-border-radius:0;border-radius:0 0 5px 5px}.sm-dox>li:last-child>a.highlighted,.sm-dox>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted{-moz-border-radius:0;-webkit-border-radius:0;border-radius:0}.sm-dox ul{background:var(--nav-menu-background-color)}.sm-dox ul a,.sm-dox ul a:focus,.sm-dox ul a:hover,.sm-dox ul a:active{font-size:12px;border-left:8px solid transparent;line-height:36px;text-shadow:none;background-color:var(--nav-menu-background-color);background-image:none}.sm-dox ul a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:0 1px 1px black}.sm-dox ul ul a,.sm-dox ul ul a:hover,.sm-dox ul ul a:focus,.sm-dox ul ul a:active{border-left:16px solid transparent}.sm-dox ul ul ul a,.sm-dox ul ul ul a:hover,.sm-dox ul ul ul a:focus,.sm-dox ul ul ul a:active{border-left:24px solid transparent}.sm-dox ul ul ul ul a,.sm-dox ul ul ul ul a:hover,.sm-dox ul ul ul ul a:focus,.sm-dox ul ul ul ul a:active{border-left:32px solid transparent}.sm-dox ul ul ul ul ul a,.sm-dox ul ul ul ul ul a:hover,.sm-dox ul ul ul ul ul a:focus,.sm-dox ul ul ul ul ul a:active{border-left:40px solid transparent}@media(min-width:768px){.sm-dox ul{position:absolute;width:12em}.sm-dox li{float:left}.sm-dox.sm-rtl li{float:right}.sm-dox ul li,.sm-dox.sm-rtl ul li,.sm-dox.sm-vertical li{float:none}.sm-dox a{white-space:nowrap}.sm-dox ul a,.sm-dox.sm-vertical a{white-space:normal}.sm-dox .sm-nowrap>li>a,.sm-dox .sm-nowrap>li>:not(ul) a{white-space:nowrap}.sm-dox{padding:0 10px;background-image:var(--nav-gradient-image);line-height:36px}.sm-dox a span.sub-arrow{top:50%;margin-top:-2px;right:12px;width:0;height:0;border-width:4px;border-style:solid dashed dashed dashed;border-color:var(--nav-text-normal-color) transparent transparent transparent;background:transparent;-moz-border-radius:0;-webkit-border-radius:0;border-radius:0}.sm-dox a,.sm-dox a:focus,.sm-dox a:active,.sm-dox a:hover,.sm-dox a.highlighted{padding:0 12px;background-image:var(--nav-separator-image);background-repeat:no-repeat;background-position:right;-moz-border-radius:0 !important;-webkit-border-radius:0;border-radius:0 !important}.sm-dox a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:var(--nav-text-hover-shadow)}.sm-dox a:hover span.sub-arrow{border-color:var(--nav-text-hover-color) transparent transparent transparent}.sm-dox a.has-submenu{padding-right:24px}.sm-dox li{border-top:0}.sm-dox>li>ul:before,.sm-dox>li>ul:after{content:'';position:absolute;top:-18px;left:30px;width:0;height:0;overflow:hidden;border-width:9px;border-style:dashed dashed solid dashed;border-color:transparent transparent #bbb transparent}.sm-dox>li>ul:after{top:-16px;left:31px;border-width:8px;border-color:transparent transparent var(--nav-menu-background-color) transparent}.sm-dox ul{border:1px solid #bbb;padding:5px 0;background:var(--nav-menu-background-color);-moz-border-radius:5px !important;-webkit-border-radius:5px;border-radius:5px !important;-moz-box-shadow:0 5px 9px rgba(0,0,0,0.2);-webkit-box-shadow:0 5px 9px rgba(0,0,0,0.2);box-shadow:0 5px 9px rgba(0,0,0,0.2)}.sm-dox ul a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-color:transparent transparent transparent var(--nav-menu-foreground-color);border-style:dashed dashed dashed solid}.sm-dox ul a,.sm-dox ul a:hover,.sm-dox ul a:focus,.sm-dox ul a:active,.sm-dox ul a.highlighted{color:var(--nav-menu-foreground-color);background-image:none;border:0 !important}.sm-dox ul a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:var(--nav-text-hover-shadow)}.sm-dox ul a:hover span.sub-arrow{border-color:transparent transparent transparent var(--nav-text-hover-color)}.sm-dox span.scroll-up,.sm-dox span.scroll-down{position:absolute;display:none;visibility:hidden;overflow:hidden;background:var(--nav-menu-background-color);height:36px}.sm-dox span.scroll-up:hover,.sm-dox span.scroll-down:hover{background:#eee}.sm-dox span.scroll-up:hover span.scroll-up-arrow,.sm-dox span.scroll-up:hover span.scroll-down-arrow{border-color:transparent transparent #d23600 transparent}.sm-dox span.scroll-down:hover span.scroll-down-arrow{border-color:#d23600 transparent transparent transparent}.sm-dox span.scroll-up-arrow,.sm-dox span.scroll-down-arrow{position:absolute;top:0;left:50%;margin-left:-6px;width:0;height:0;overflow:hidden;border-width:6px;border-style:dashed dashed solid dashed;border-color:transparent transparent var(--nav-menu-foreground-color) transparent}.sm-dox span.scroll-down-arrow{top:8px;border-style:solid dashed dashed dashed;border-color:var(--nav-menu-foreground-color) transparent transparent transparent}.sm-dox.sm-rtl a.has-submenu{padding-right:12px;padding-left:24px}.sm-dox.sm-rtl a span.sub-arrow{right:auto;left:12px}.sm-dox.sm-rtl.sm-vertical a.has-submenu{padding:10px 20px}.sm-dox.sm-rtl.sm-vertical a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-rtl>li>ul:before{left:auto;right:30px}.sm-dox.sm-rtl>li>ul:after{left:auto;right:31px}.sm-dox.sm-rtl ul a.has-submenu{padding:10px 20px !important}.sm-dox.sm-rtl ul a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-vertical{padding:10px 0;-moz-border-radius:5px;-webkit-border-radius:5px;border-radius:5px}.sm-dox.sm-vertical a{padding:10px 20px}.sm-dox.sm-vertical a:hover,.sm-dox.sm-vertical a:focus,.sm-dox.sm-vertical a:active,.sm-dox.sm-vertical a.highlighted{background:#fff}.sm-dox.sm-vertical a.disabled{background-image:var(--nav-gradient-image)}.sm-dox.sm-vertical a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-style:dashed dashed dashed solid;border-color:transparent transparent transparent #555}.sm-dox.sm-vertical>li>ul:before,.sm-dox.sm-vertical>li>ul:after{display:none}.sm-dox.sm-vertical ul a{padding:10px 20px}.sm-dox.sm-vertical ul a:hover,.sm-dox.sm-vertical ul a:focus,.sm-dox.sm-vertical ul a:active,.sm-dox.sm-vertical ul a.highlighted{background:#eee}.sm-dox.sm-vertical ul a.disabled{background:var(--nav-menu-background-color)}} \ No newline at end of file diff --git a/documentation/latex/Makefile b/documentation/latex/Makefile deleted file mode 100644 index 7f82972..0000000 --- a/documentation/latex/Makefile +++ /dev/null @@ -1,27 +0,0 @@ -LATEX_CMD?=pdflatex -MKIDX_CMD?=makeindex -BIBTEX_CMD?=bibtex -LATEX_COUNT?=8 -MANUAL_FILE?=refman - -all: $(MANUAL_FILE).pdf - -pdf: $(MANUAL_FILE).pdf - -$(MANUAL_FILE).pdf: clean $(MANUAL_FILE).tex - $(LATEX_CMD) $(MANUAL_FILE) - $(MKIDX_CMD) $(MANUAL_FILE).idx - $(LATEX_CMD) $(MANUAL_FILE) - latex_count=$(LATEX_COUNT) ; \ - while grep -E -s 'Rerun (LaTeX|to get cross-references right|to get bibliographical references right)' $(MANUAL_FILE).log && [ $$latex_count -gt 0 ] ;\ - do \ - echo "Rerunning latex...." ;\ - $(LATEX_CMD) $(MANUAL_FILE) ;\ - latex_count=`expr $$latex_count - 1` ;\ - done - $(MKIDX_CMD) $(MANUAL_FILE).idx - $(LATEX_CMD) $(MANUAL_FILE) - - -clean: - rm -f *.ps *.dvi *.aux *.toc *.idx *.ind *.ilg *.log *.out *.brf *.blg *.bbl $(MANUAL_FILE).pdf diff --git a/documentation/latex/_b_n_o08x_8cpp.tex b/documentation/latex/_b_n_o08x_8cpp.tex deleted file mode 100644 index b27d4f0..0000000 --- a/documentation/latex/_b_n_o08x_8cpp.tex +++ /dev/null @@ -1,12 +0,0 @@ -\doxysection{BNO08x.\+cpp File Reference} -\hypertarget{_b_n_o08x_8cpp}{}\label{_b_n_o08x_8cpp}\index{BNO08x.cpp@{BNO08x.cpp}} -{\ttfamily \#include "{}BNO08x.\+hpp"{}}\newline -{\ttfamily \#include "{}BNO08x\+\_\+macros.\+hpp"{}}\newline -Include dependency graph for BNO08x.\+cpp\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_b_n_o08x_8cpp__incl} -\end{center} -\end{figure} diff --git a/documentation/latex/_b_n_o08x_8cpp__incl.md5 b/documentation/latex/_b_n_o08x_8cpp__incl.md5 deleted file mode 100644 index 24618f5..0000000 --- a/documentation/latex/_b_n_o08x_8cpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -9e2bc480e00bb71e6489ffcc8111f4a0 \ No newline at end of file diff --git a/documentation/latex/_b_n_o08x_8cpp__incl.pdf b/documentation/latex/_b_n_o08x_8cpp__incl.pdf deleted file mode 100644 index 847f1ce..0000000 Binary files a/documentation/latex/_b_n_o08x_8cpp__incl.pdf and /dev/null differ diff --git a/documentation/latex/_b_n_o08x_8hpp.tex b/documentation/latex/_b_n_o08x_8hpp.tex deleted file mode 100644 index 4f0b678..0000000 --- a/documentation/latex/_b_n_o08x_8hpp.tex +++ /dev/null @@ -1,53 +0,0 @@ -\doxysection{BNO08x.\+hpp File Reference} -\hypertarget{_b_n_o08x_8hpp}{}\label{_b_n_o08x_8hpp}\index{BNO08x.hpp@{BNO08x.hpp}} -{\ttfamily \#include $<$inttypes.\+h$>$}\newline -{\ttfamily \#include $<$math.\+h$>$}\newline -{\ttfamily \#include $<$stdio.\+h$>$}\newline -{\ttfamily \#include $<$cstring$>$}\newline -{\ttfamily \#include $<$functional$>$}\newline -{\ttfamily \#include $<$vector$>$}\newline -{\ttfamily \#include $<$esp\+\_\+log.\+h$>$}\newline -{\ttfamily \#include $<$esp\+\_\+rom\+\_\+gpio.\+h$>$}\newline -{\ttfamily \#include $<$esp\+\_\+timer.\+h$>$}\newline -{\ttfamily \#include $<$freertos/\+Free\+RTOS.\+h$>$}\newline -{\ttfamily \#include $<$freertos/task.\+h$>$}\newline -{\ttfamily \#include $<$freertos/event\+\_\+groups.\+h$>$}\newline -{\ttfamily \#include $<$freertos/queue.\+h$>$}\newline -{\ttfamily \#include $<$freertos/semphr.\+h$>$}\newline -{\ttfamily \#include $<$rom/ets\+\_\+sys.\+h$>$}\newline -{\ttfamily \#include "{}BNO08x\+\_\+global\+\_\+types.\+hpp"{}}\newline -Include dependency graph for BNO08x.\+hpp\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_b_n_o08x_8hpp__incl} -\end{center} -\end{figure} -This graph shows which files directly or indirectly include this file\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_b_n_o08x_8hpp__dep__incl} -\end{center} -\end{figure} -\doxysubsubsection*{Classes} -\begin{DoxyCompactItemize} -\item -class \mbox{\hyperlink{class_b_n_o08x}{BNO08x}} -\begin{DoxyCompactList}\small\item\em \doxylink{class_b_n_o08x}{BNO08x} IMU driver class. \end{DoxyCompactList}\item -struct \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{BNO08x\+::bno08x\+\_\+rx\+\_\+packet\+\_\+t}} -\begin{DoxyCompactList}\small\item\em Holds data that is received over spi. \end{DoxyCompactList}\item -struct \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__tx__packet__t}{BNO08x\+::bno08x\+\_\+tx\+\_\+packet\+\_\+t}} -\begin{DoxyCompactList}\small\item\em Holds data that is sent over spi. \end{DoxyCompactList}\item -struct \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__report__period__tracker__t}{BNO08x\+::bno08x\+\_\+report\+\_\+period\+\_\+tracker\+\_\+t}} -\item -struct \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t}{BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t}} -\begin{DoxyCompactList}\small\item\em Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup). \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -\begin{DoxyAuthor}{Author} -Myles Parfeniuk -\end{DoxyAuthor} diff --git a/documentation/latex/_b_n_o08x_8hpp__dep__incl.md5 b/documentation/latex/_b_n_o08x_8hpp__dep__incl.md5 deleted file mode 100644 index 073579f..0000000 --- a/documentation/latex/_b_n_o08x_8hpp__dep__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -cd2c79f45328f64ca27f89cf7784d6bf \ No newline at end of file diff --git a/documentation/latex/_b_n_o08x_8hpp__dep__incl.pdf b/documentation/latex/_b_n_o08x_8hpp__dep__incl.pdf deleted file mode 100644 index d4c9cfb..0000000 Binary files a/documentation/latex/_b_n_o08x_8hpp__dep__incl.pdf and /dev/null differ diff --git a/documentation/latex/_b_n_o08x_8hpp__incl.md5 b/documentation/latex/_b_n_o08x_8hpp__incl.md5 deleted file mode 100644 index 851a917..0000000 --- a/documentation/latex/_b_n_o08x_8hpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -af3711eb54ac1ad91d0e2e984c9a0fc1 \ No newline at end of file diff --git a/documentation/latex/_b_n_o08x_8hpp__incl.pdf b/documentation/latex/_b_n_o08x_8hpp__incl.pdf deleted file mode 100644 index a0bb816..0000000 Binary files a/documentation/latex/_b_n_o08x_8hpp__incl.pdf and /dev/null differ diff --git a/documentation/latex/_b_n_o08x_8hpp_source.tex b/documentation/latex/_b_n_o08x_8hpp_source.tex deleted file mode 100644 index 39f8fd1..0000000 --- a/documentation/latex/_b_n_o08x_8hpp_source.tex +++ /dev/null @@ -1,557 +0,0 @@ -\doxysection{BNO08x.\+hpp} -\hypertarget{_b_n_o08x_8hpp_source}{}\label{_b_n_o08x_8hpp_source}\index{BNO08x.hpp@{BNO08x.hpp}} -\mbox{\hyperlink{_b_n_o08x_8hpp}{Go to the documentation of this file.}} -\begin{DoxyCode}{0} -\DoxyCodeLine{00001\ } -\DoxyCodeLine{00005\ \textcolor{preprocessor}{\#pragma\ once}} -\DoxyCodeLine{00006\ \textcolor{comment}{//\ standard\ library\ includes}} -\DoxyCodeLine{00007\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00008\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00009\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00010\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00011\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00012\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00013\ } -\DoxyCodeLine{00014\ \textcolor{comment}{//\ esp-\/idf\ includes}} -\DoxyCodeLine{00015\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00016\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00017\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00018\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00019\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00020\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00021\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00022\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00023\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00024\ } -\DoxyCodeLine{00025\ \textcolor{comment}{//\ in-\/house\ includes}} -\DoxyCodeLine{00026\ \textcolor{preprocessor}{\#include\ "{}\mbox{\hyperlink{_b_n_o08x__global__types_8hpp}{BNO08x\_global\_types.hpp}}"{}}} -\DoxyCodeLine{00027\ } -\DoxyCodeLine{00033\ \textcolor{keyword}{class\ }\mbox{\hyperlink{class_b_n_o08x}{BNO08x}}} -\DoxyCodeLine{00034\ \{} -\DoxyCodeLine{00035\ \ \ \ \ \textcolor{keyword}{public}:} -\DoxyCodeLine{00036\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ad12fb6cf310ad7a04a4e53809833bd61}{BNO08x}}(\mbox{\hyperlink{structbno08x__config__t}{bno08x\_config\_t}}\ \mbox{\hyperlink{class_b_n_o08x_aeda443e9f608fccfec0e6770edc90c82}{imu\_config}}\ =\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a648bbdbf22731476890dd8da977d7503}{bno08x\_config\_t}}());} -\DoxyCodeLine{00037\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9}{\string~BNO08x}}();} -\DoxyCodeLine{00038\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798}{initialize}}();} -\DoxyCodeLine{00039\ } -\DoxyCodeLine{00040\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_a28cd1c0b3477571d87133234e6358503}{hard\_reset}}();} -\DoxyCodeLine{00041\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e}{soft\_reset}}();} -\DoxyCodeLine{00042\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147}{BNO08xResetReason}}\ \mbox{\hyperlink{class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85}{get\_reset\_reason}}();} -\DoxyCodeLine{00043\ } -\DoxyCodeLine{00044\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b}{mode\_sleep}}();} -\DoxyCodeLine{00045\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698}{mode\_on}}();} -\DoxyCodeLine{00046\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9}{q\_to\_float}}(int16\_t\ fixed\_point\_value,\ uint8\_t\ q\_point);} -\DoxyCodeLine{00047\ } -\DoxyCodeLine{00048\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a}{run\_full\_calibration\_routine}}();} -\DoxyCodeLine{00049\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128}{calibrate\_all}}();} -\DoxyCodeLine{00050\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc}{calibrate\_accelerometer}}();} -\DoxyCodeLine{00051\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1}{calibrate\_gyro}}();} -\DoxyCodeLine{00052\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a}{calibrate\_magnetometer}}();} -\DoxyCodeLine{00053\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26}{calibrate\_planar\_accelerometer}}();} -\DoxyCodeLine{00054\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11}{request\_calibration\_status}}();} -\DoxyCodeLine{00055\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b}{calibration\_complete}}();} -\DoxyCodeLine{00056\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2}{end\_calibration}}();} -\DoxyCodeLine{00057\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54}{save\_calibration}}();} -\DoxyCodeLine{00058\ } -\DoxyCodeLine{00059\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7}{enable\_rotation\_vector}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00060\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947}{enable\_game\_rotation\_vector}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00061\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc}{enable\_ARVR\_stabilized\_rotation\_vector}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00062\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8}{enable\_ARVR\_stabilized\_game\_rotation\_vector}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00063\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d}{enable\_gyro\_integrated\_rotation\_vector}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00064\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75}{enable\_uncalibrated\_gyro}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00065\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53}{enable\_calibrated\_gyro}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00066\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91}{enable\_accelerometer}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00067\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b}{enable\_linear\_accelerometer}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00068\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a030eae12c3586acf09b48e94630b2544}{enable\_gravity}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00069\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59}{enable\_magnetometer}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00070\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566}{enable\_tap\_detector}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00071\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f}{enable\_step\_counter}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00072\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655}{enable\_stability\_classifier}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00073\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a039e8770759e784baa438324ae17883c}{enable\_activity\_classifier}}(uint32\_t\ time\_between\_reports,\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0f}{BNO08xActivityEnable}}\ activities\_to\_enable,\ uint8\_t\ (\&activity\_confidence\_vals)[9]);} -\DoxyCodeLine{00074\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a8be135ed41646199540583b29806d4e5}{enable\_raw\_mems\_gyro}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00075\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b}{enable\_raw\_mems\_accelerometer}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00076\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5}{enable\_raw\_mems\_magnetometer}}(uint32\_t\ time\_between\_reports);} -\DoxyCodeLine{00077\ } -\DoxyCodeLine{00078\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921}{disable\_rotation\_vector}}();} -\DoxyCodeLine{00079\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a7665cce95e791c89161ec863f49c0392}{disable\_game\_rotation\_vector}}();} -\DoxyCodeLine{00080\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4}{disable\_ARVR\_stabilized\_rotation\_vector}}();} -\DoxyCodeLine{00081\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c}{disable\_ARVR\_stabilized\_game\_rotation\_vector}}();} -\DoxyCodeLine{00082\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931}{disable\_gyro\_integrated\_rotation\_vector}}();} -\DoxyCodeLine{00083\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ad5c991150895b80bee68c933059a4058}{disable\_accelerometer}}();} -\DoxyCodeLine{00084\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f}{disable\_linear\_accelerometer}}();} -\DoxyCodeLine{00085\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f}{disable\_gravity}}();} -\DoxyCodeLine{00086\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c}{disable\_calibrated\_gyro}}();} -\DoxyCodeLine{00087\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc}{disable\_uncalibrated\_gyro}}();} -\DoxyCodeLine{00088\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338}{disable\_magnetometer}}();} -\DoxyCodeLine{00089\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a427550a4ba25252912436b899124e157}{disable\_step\_counter}}();} -\DoxyCodeLine{00090\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932}{disable\_stability\_classifier}}();} -\DoxyCodeLine{00091\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376}{disable\_activity\_classifier}}();} -\DoxyCodeLine{00092\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2}{disable\_tap\_detector}}();} -\DoxyCodeLine{00093\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce}{disable\_raw\_mems\_accelerometer}}();} -\DoxyCodeLine{00094\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725}{disable\_raw\_mems\_gyro}}();} -\DoxyCodeLine{00095\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2}{disable\_raw\_mems\_magnetometer}}();} -\DoxyCodeLine{00096\ } -\DoxyCodeLine{00097\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f}{tare\_now}}(uint8\_t\ axis\_sel\ =\ \mbox{\hyperlink{class_b_n_o08x_a1ef13f6f330810934416ad5fe0ee55b2}{TARE\_AXIS\_ALL}},\ uint8\_t\ rotation\_vector\_basis\ =\ \mbox{\hyperlink{class_b_n_o08x_a8e2cfc25d0e34ae53a762b88cc3ac3c8}{TARE\_ROTATION\_VECTOR}});} -\DoxyCodeLine{00098\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2}{save\_tare}}();} -\DoxyCodeLine{00099\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e}{clear\_tare}}();} -\DoxyCodeLine{00100\ } -\DoxyCodeLine{00101\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86}{data\_available}}(\textcolor{keywordtype}{bool}\ ignore\_no\_reports\_enabled\ =\ \textcolor{keyword}{false});} -\DoxyCodeLine{00102\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a06bb0c70305421b5357e64f31579fdc7}{register\_cb}}(std::function<\textcolor{keywordtype}{void}()>\ cb\_fxn);} -\DoxyCodeLine{00103\ } -\DoxyCodeLine{00104\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61}{reset\_all\_data\_to\_defaults}}();} -\DoxyCodeLine{00105\ } -\DoxyCodeLine{00106\ \ \ \ \ \ \ \ \ uint32\_t\ \mbox{\hyperlink{class_b_n_o08x_ad9137777271421a58159f3fe5e05ed20}{get\_time\_stamp}}();} -\DoxyCodeLine{00107\ } -\DoxyCodeLine{00108\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb}{get\_magf}}(\textcolor{keywordtype}{float}\&\ x,\ \textcolor{keywordtype}{float}\&\ y,\ \textcolor{keywordtype}{float}\&\ z,\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\&\ accuracy);} -\DoxyCodeLine{00109\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d}{get\_magf\_X}}();} -\DoxyCodeLine{00110\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea}{get\_magf\_Y}}();} -\DoxyCodeLine{00111\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282}{get\_magf\_Z}}();} -\DoxyCodeLine{00112\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\ \mbox{\hyperlink{class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9}{get\_magf\_accuracy}}();} -\DoxyCodeLine{00113\ } -\DoxyCodeLine{00114\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a067678914e928a6691625b17c40237a0}{get\_gravity}}(\textcolor{keywordtype}{float}\&\ x,\ \textcolor{keywordtype}{float}\&\ y,\ \textcolor{keywordtype}{float}\&\ z,\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\&\ accuracy);} -\DoxyCodeLine{00115\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae}{get\_gravity\_X}}();} -\DoxyCodeLine{00116\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a8a36db7f1c932f33e05e494632059801}{get\_gravity\_Y}}();} -\DoxyCodeLine{00117\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807}{get\_gravity\_Z}}();} -\DoxyCodeLine{00118\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\ \mbox{\hyperlink{class_b_n_o08x_a77c82cece30dde944efcde81643fd62d}{get\_gravity\_accuracy}}();} -\DoxyCodeLine{00119\ } -\DoxyCodeLine{00120\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a89618eba08186ee8e679e7313907ddef}{get\_roll}}();} -\DoxyCodeLine{00121\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3}{get\_pitch}}();} -\DoxyCodeLine{00122\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17}{get\_yaw}}();} -\DoxyCodeLine{00123\ } -\DoxyCodeLine{00124\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6}{get\_roll\_deg}}();} -\DoxyCodeLine{00125\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_af50010400cbd1445e9ddfa259384b412}{get\_pitch\_deg}}();} -\DoxyCodeLine{00126\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_af80f7795656e695e036d3b1557aed94c}{get\_yaw\_deg}}();} -\DoxyCodeLine{00127\ } -\DoxyCodeLine{00128\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a}{get\_quat}}(\textcolor{keywordtype}{float}\&\ i,\ \textcolor{keywordtype}{float}\&\ j,\ \textcolor{keywordtype}{float}\&\ k,\ \textcolor{keywordtype}{float}\&\ real,\ \textcolor{keywordtype}{float}\&\ rad\_accuracy,\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\&\ accuracy);} -\DoxyCodeLine{00129\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5}{get\_quat\_I}}();} -\DoxyCodeLine{00130\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015}{get\_quat\_J}}();} -\DoxyCodeLine{00131\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8}{get\_quat\_K}}();} -\DoxyCodeLine{00132\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7}{get\_quat\_real}}();} -\DoxyCodeLine{00133\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630}{get\_quat\_radian\_accuracy}}();} -\DoxyCodeLine{00134\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\ \mbox{\hyperlink{class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654}{get\_quat\_accuracy}}();} -\DoxyCodeLine{00135\ } -\DoxyCodeLine{00136\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885}{get\_accel}}(\textcolor{keywordtype}{float}\&\ x,\ \textcolor{keywordtype}{float}\&\ y,\ \textcolor{keywordtype}{float}\&\ z,\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\&\ accuracy);} -\DoxyCodeLine{00137\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69}{get\_accel\_X}}();} -\DoxyCodeLine{00138\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1}{get\_accel\_Y}}();} -\DoxyCodeLine{00139\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1}{get\_accel\_Z}}();} -\DoxyCodeLine{00140\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\ \mbox{\hyperlink{class_b_n_o08x_a6eed9e2d3e639ec7e38dfdf092c14ea1}{get\_accel\_accuracy}}();} -\DoxyCodeLine{00141\ } -\DoxyCodeLine{00142\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46}{get\_linear\_accel}}(\textcolor{keywordtype}{float}\&\ x,\ \textcolor{keywordtype}{float}\&\ y,\ \textcolor{keywordtype}{float}\&\ z,\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\&\ accuracy);} -\DoxyCodeLine{00143\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3}{get\_linear\_accel\_X}}();} -\DoxyCodeLine{00144\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191}{get\_linear\_accel\_Y}}();} -\DoxyCodeLine{00145\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84}{get\_linear\_accel\_Z}}();} -\DoxyCodeLine{00146\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\ \mbox{\hyperlink{class_b_n_o08x_a6114ba3c8967ac8fde06233c81623c80}{get\_linear\_accel\_accuracy}}();} -\DoxyCodeLine{00147\ } -\DoxyCodeLine{00148\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_aa6bbad8c9123b4dba5007f72a8806303}{get\_raw\_mems\_accel}}(uint16\_t\&\ x,\ uint16\_t\&\ y,\ uint16\_t\&\ z);} -\DoxyCodeLine{00149\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a868b24d96cb12f614431a410bcc9e434}{get\_raw\_mems\_accel\_X}}();} -\DoxyCodeLine{00150\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_aebcbaf9c3aaf37d85a78d22dc22c614a}{get\_raw\_mems\_accel\_Y}}();} -\DoxyCodeLine{00151\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a85d1331ebe762f6823bde4bf76a33e21}{get\_raw\_mems\_accel\_Z}}();} -\DoxyCodeLine{00152\ } -\DoxyCodeLine{00153\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27}{get\_raw\_mems\_gyro}}(uint16\_t\&\ x,\ uint16\_t\&\ y,\ uint16\_t\&\ z);} -\DoxyCodeLine{00154\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a8872241c73bca2ac1698ae867f7d1913}{get\_raw\_mems\_gyro\_X}}();} -\DoxyCodeLine{00155\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a4bcc58423b5cc7c24080c2ef812d3d86}{get\_raw\_mems\_gyro\_Y}}();} -\DoxyCodeLine{00156\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_ae684dd13ef630dfdbb8de18ee5ea90bb}{get\_raw\_mems\_gyro\_Z}}();} -\DoxyCodeLine{00157\ } -\DoxyCodeLine{00158\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a929ad333f73614fb5830c186e3e03a00}{get\_raw\_mems\_magf}}(uint16\_t\&\ x,\ uint16\_t\&\ y,\ uint16\_t\&\ z);} -\DoxyCodeLine{00159\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a347444f461b2fab5ff37de346ba2a595}{get\_raw\_mems\_magf\_X}}();} -\DoxyCodeLine{00160\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_ad8a215314ae96b25b59fdc363c52261c}{get\_raw\_mems\_magf\_Y}}();} -\DoxyCodeLine{00161\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a780651af54485edb36d197f30c071615}{get\_raw\_mems\_magf\_Z}}();} -\DoxyCodeLine{00162\ } -\DoxyCodeLine{00163\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f}{get\_calibrated\_gyro\_velocity}}(\textcolor{keywordtype}{float}\&\ x,\ \textcolor{keywordtype}{float}\&\ y,\ \textcolor{keywordtype}{float}\&\ z);} -\DoxyCodeLine{00164\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889}{get\_calibrated\_gyro\_velocity\_X}}();} -\DoxyCodeLine{00165\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50}{get\_calibrated\_gyro\_velocity\_Y}}();} -\DoxyCodeLine{00166\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea}{get\_calibrated\_gyro\_velocity\_Z}}();} -\DoxyCodeLine{00167\ } -\DoxyCodeLine{00168\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104}{get\_uncalibrated\_gyro\_velocity}}(\textcolor{keywordtype}{float}\&\ x,\ \textcolor{keywordtype}{float}\&\ y,\ \textcolor{keywordtype}{float}\&\ z,\ \textcolor{keywordtype}{float}\&\ bx,\ \textcolor{keywordtype}{float}\&\ by,\ \textcolor{keywordtype}{float}\&\ bz);} -\DoxyCodeLine{00169\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486}{get\_uncalibrated\_gyro\_velocity\_X}}();} -\DoxyCodeLine{00170\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de}{get\_uncalibrated\_gyro\_velocity\_Y}}();} -\DoxyCodeLine{00171\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592}{get\_uncalibrated\_gyro\_velocity\_Z}}();} -\DoxyCodeLine{00172\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b}{get\_uncalibrated\_gyro\_bias\_X}}();} -\DoxyCodeLine{00173\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a74725517129dd548c7a3de705d5861bd}{get\_uncalibrated\_gyro\_bias\_Y}}();} -\DoxyCodeLine{00174\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7}{get\_uncalibrated\_gyro\_bias\_Z}}();} -\DoxyCodeLine{00175\ } -\DoxyCodeLine{00176\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f}{get\_integrated\_gyro\_velocity}}(\textcolor{keywordtype}{float}\&\ x,\ \textcolor{keywordtype}{float}\&\ y,\ \textcolor{keywordtype}{float}\&\ z);} -\DoxyCodeLine{00177\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff}{get\_integrated\_gyro\_velocity\_X}}();} -\DoxyCodeLine{00178\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1}{get\_integrated\_gyro\_velocity\_Y}}();} -\DoxyCodeLine{00179\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add}{get\_integrated\_gyro\_velocity\_Z}}();} -\DoxyCodeLine{00180\ } -\DoxyCodeLine{00181\ \ \ \ \ \ \ \ \ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a4797ec731de4c158716da1a7af9d1602}{get\_tap\_detector}}();} -\DoxyCodeLine{00182\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef}{get\_step\_count}}();} -\DoxyCodeLine{00183\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}{BNO08xStability}}\ \mbox{\hyperlink{class_b_n_o08x_a248544b262582d10d917a687190cb454}{get\_stability\_classifier}}();} -\DoxyCodeLine{00184\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}{BNO08xActivity}}\ \mbox{\hyperlink{class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed}{get\_activity\_classifier}}();} -\DoxyCodeLine{00185\ } -\DoxyCodeLine{00186\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ Metadata\ functions}} -\DoxyCodeLine{00187\ \ \ \ \ \ \ \ \ int16\_t\ \mbox{\hyperlink{class_b_n_o08x_a4421c43323945946ad605f8422958dcf}{get\_Q1}}(uint16\_t\ record\_ID);} -\DoxyCodeLine{00188\ \ \ \ \ \ \ \ \ int16\_t\ \mbox{\hyperlink{class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b}{get\_Q2}}(uint16\_t\ record\_ID);} -\DoxyCodeLine{00189\ \ \ \ \ \ \ \ \ int16\_t\ \mbox{\hyperlink{class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a}{get\_Q3}}(uint16\_t\ record\_ID);} -\DoxyCodeLine{00190\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372}{get\_resolution}}(uint16\_t\ record\_ID);} -\DoxyCodeLine{00191\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0}{get\_range}}(uint16\_t\ record\_ID);} -\DoxyCodeLine{00192\ \ \ \ \ \ \ \ \ uint32\_t\ \mbox{\hyperlink{class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41}{FRS\_read\_word}}(uint16\_t\ record\_ID,\ uint8\_t\ word\_number);} -\DoxyCodeLine{00193\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_adf789e709ac1667656db757c8d559af9}{FRS\_read\_request}}(uint16\_t\ record\_ID,\ uint16\_t\ read\_offset,\ uint16\_t\ block\_size);} -\DoxyCodeLine{00194\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1}{FRS\_read\_data}}(uint16\_t\ record\_ID,\ uint8\_t\ start\_location,\ uint8\_t\ words\_to\_read);} -\DoxyCodeLine{00195\ } -\DoxyCodeLine{00196\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ Record\ IDs\ from\ figure\ 29,\ page\ 29\ reference\ manual}} -\DoxyCodeLine{00197\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ These\ are\ used\ to\ read\ the\ metadata\ for\ each\ sensor\ type}} -\DoxyCodeLine{00198\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_ad7ef7d7068af5f92239c12022dbeb16d}{FRS\_RECORD\_ID\_ACCELEROMETER}}\ =} -\DoxyCodeLine{00199\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 0xE302U;\ } -\DoxyCodeLine{00200\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a35d8f641e73c308f92a5a0a772f90f48}{FRS\_RECORD\_ID\_GYROSCOPE\_CALIBRATED}}\ =} -\DoxyCodeLine{00201\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 0xE306U;\ } -\DoxyCodeLine{00202\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a0992d77f9bae0b8e3c8d9331fe84fe24}{FRS\_RECORD\_ID\_MAGNETIC\_FIELD\_CALIBRATED}}\ =} -\DoxyCodeLine{00203\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 0xE309U;\ } -\DoxyCodeLine{00204\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a9f35840b19c8ad11fd1b4622c3269250}{FRS\_RECORD\_ID\_ROTATION\_VECTOR}}\ =} -\DoxyCodeLine{00205\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 0xE30BU;\ } -\DoxyCodeLine{00206\ } -\DoxyCodeLine{00207\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a1ef13f6f330810934416ad5fe0ee55b2}{TARE\_AXIS\_ALL}}\ =\ 0x07U;\ } -\DoxyCodeLine{00208\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_aecb3e11c1ca5769fd60f42c17a105731}{TARE\_AXIS\_Z}}\ =\ 0x04U;\ \ \ } -\DoxyCodeLine{00209\ } -\DoxyCodeLine{00210\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ Which\ rotation\ vector\ to\ tare,\ BNO08x\ saves\ them\ seperately}} -\DoxyCodeLine{00211\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a8e2cfc25d0e34ae53a762b88cc3ac3c8}{TARE\_ROTATION\_VECTOR}}\ =\ 0U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00212\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_abaf1ec8bb197db1998a9ed3cec6180d5}{TARE\_GAME\_ROTATION\_VECTOR}}\ =\ 1U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00213\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a225397a04d849e5647992ca80d68febb}{TARE\_GEOMAGNETIC\_ROTATION\_VECTOR}}\ =\ 2U;\ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00214\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a9ec354d75249f06f13599abf7bedfde0}{TARE\_GYRO\_INTEGRATED\_ROTATION\_VECTOR}}\ =\ 3U;\ \ \ \ \ \ } -\DoxyCodeLine{00215\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_abff9abe904bcdde951cf88c378284b45}{TARE\_ARVR\_STABILIZED\_ROTATION\_VECTOR}}\ =\ 4U;\ \ \ \ \ \ } -\DoxyCodeLine{00216\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a68aaaab144adbe5af00597408f044d9d}{TARE\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR}}\ =\ 5U;\ } -\DoxyCodeLine{00217\ } -\DoxyCodeLine{00218\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ \mbox{\hyperlink{class_b_n_o08x_a0b19c8f2de2b2bfe033da7f93cdd2608}{ROTATION\_VECTOR\_Q1}}\ =\ 14;\ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00219\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ \mbox{\hyperlink{class_b_n_o08x_a923d65d8568cc31873ad56a3908e1939}{ROTATION\_VECTOR\_ACCURACY\_Q1}}\ =\ 12;\ } -\DoxyCodeLine{00220\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ \mbox{\hyperlink{class_b_n_o08x_a0564aaf5b20dc42b54db4fb3115ac1c7}{ACCELEROMETER\_Q1}}\ =\ 8;\ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00221\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ \mbox{\hyperlink{class_b_n_o08x_ad0d37fe07ced24f2c9afc21145a74e7b}{LINEAR\_ACCELEROMETER\_Q1}}\ =\ 8;\ \ \ \ \ \ } -\DoxyCodeLine{00222\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ \mbox{\hyperlink{class_b_n_o08x_aa3bec8effefa61cec6fa170e9d02c4dd}{GYRO\_Q1}}\ =\ 9;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00223\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ \mbox{\hyperlink{class_b_n_o08x_a9fac9b811b7c2117675a784cb4df204c}{MAGNETOMETER\_Q1}}\ =\ 4;\ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00224\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ \mbox{\hyperlink{class_b_n_o08x_aafe117561fe9138800073a04a778b4ce}{ANGULAR\_VELOCITY\_Q1}}\ =\ 10;\ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00225\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ \mbox{\hyperlink{class_b_n_o08x_ae10722334dfce9635e76519598e165a2}{GRAVITY\_Q1}}\ =\ 8;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00226\ } -\DoxyCodeLine{00227\ \ \ \ \ \textcolor{keyword}{private}:} -\DoxyCodeLine{00229\ \ \ \ \ \ \ \ \ \textcolor{keyword}{enum}\ \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638f}{channels\_t}}} -\DoxyCodeLine{00230\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00231\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fad116268ebf7fb5e5cb4795ccc27867ed}{CHANNEL\_COMMAND}},} -\DoxyCodeLine{00232\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fab1f28434b161c7ffa7b1a5c5f1a8a95b}{CHANNEL\_EXECUTABLE}},} -\DoxyCodeLine{00233\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fa5b5d133bf4a91e14741fdd8e635e897e}{CHANNEL\_CONTROL}},} -\DoxyCodeLine{00234\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fabeb0a4983bc57ad2ce9f98360742e03e}{CHANNEL\_REPORTS}},} -\DoxyCodeLine{00235\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638faefb874de7f2f90fb99b42bedf9623d21}{CHANNEL\_WAKE\_REPORTS}},} -\DoxyCodeLine{00236\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fadd3caa696e525dd901de7a8e3dbf0731}{CHANNEL\_GYRO}}} -\DoxyCodeLine{00237\ \ \ \ \ \ \ \ \ \};} -\DoxyCodeLine{00238\ } -\DoxyCodeLine{00240\ \ \ \ \ \ \ \ \ \textcolor{keyword}{typedef}\ \textcolor{keyword}{struct\ }\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\_rx\_packet\_t}}} -\DoxyCodeLine{00241\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00242\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint8\_t\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t_a667d671ccb272bd375008716e26e0b5b}{header}}[4];\ } -\DoxyCodeLine{00243\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint8\_t\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t_ab422d75e1fcd776ef412f4d623cc293e}{body}}[300];\ } -\DoxyCodeLine{00244\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t_a645adb6ba8fb2afbb99ec58fe678e205}{length}};\ \ \ } -\DoxyCodeLine{00245\ \ \ \ \ \ \ \ \ \}\ \mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}};} -\DoxyCodeLine{00246\ } -\DoxyCodeLine{00248\ \ \ \ \ \ \ \ \ \textcolor{keyword}{typedef}\ \textcolor{keyword}{struct\ }\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__tx__packet__t}{bno08x\_tx\_packet\_t}}} -\DoxyCodeLine{00249\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00250\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint8\_t\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__tx__packet__t_a4478c6cd9e87907eacc56dd06ad4a69d}{body}}[50];\ } -\DoxyCodeLine{00251\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__tx__packet__t_a73180537ea7605340c5e6b2132e2cbf5}{length}};\ \ } -\DoxyCodeLine{00252\ \ \ \ \ \ \ \ \ \}\ \mbox{\hyperlink{class_b_n_o08x_a3a1a869ac69e6ee850bd2a7f90dd8945}{bno08x\_tx\_packet\_t}};} -\DoxyCodeLine{00253\ } -\DoxyCodeLine{00254\ \ \ \ \ \ \ \ \ \textcolor{keyword}{typedef}\ \textcolor{keyword}{struct\ }\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__report__period__tracker__t}{bno08x\_report\_period\_tracker\_t}}} -\DoxyCodeLine{00255\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00256\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint8\_t\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__report__period__tracker__t_a05dd1697e0b5fda59d112af2c396295c}{report\_ID}};} -\DoxyCodeLine{00257\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint32\_t\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__report__period__tracker__t_a7fe1403bb26f5f4dd845df019bac8614}{period}};} -\DoxyCodeLine{00258\ \ \ \ \ \ \ \ \ \}\ \mbox{\hyperlink{class_b_n_o08x_ae87c0e3c6eb34e209855d8e5d48c624b}{bno08x\_report\_period\_tracker\_t}};} -\DoxyCodeLine{00259\ } -\DoxyCodeLine{00261\ \ \ \ \ \ \ \ \ \textcolor{keyword}{typedef}\ \textcolor{keyword}{struct\ }\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t}{bno08x\_init\_status\_t}}} -\DoxyCodeLine{00262\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00263\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a918d393541f260ae059614ed477887df}{gpio\_outputs}};\ \ \ } -\DoxyCodeLine{00264\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a7439c3e0e98c3c2276f8607e5a36b557}{gpio\_inputs}};\ \ \ \ } -\DoxyCodeLine{00265\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a277d28ef5596d4777476d64de3f2d905}{isr\_service}};\ \ \ \ } -\DoxyCodeLine{00266\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_aa04ab662c6a1a052944312ca79a17bc3}{isr\_handler}};\ \ \ \ } -\DoxyCodeLine{00267\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint8\_t\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a6b2d0002d0e817d6384a1064453eb84d}{task\_count}};\ \ } -\DoxyCodeLine{00268\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a04ef18c7f80f305a621b6cc3e5b6107d}{data\_proc\_task}};\ } -\DoxyCodeLine{00269\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a92f78cc3fd3161bbc1fcad08b9c6bcb5}{spi\_task}};\ \ \ \ \ \ \ } -\DoxyCodeLine{00270\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a9855844dee2cd51e734693294d5cc438}{spi\_bus}};\ \ \ \ \ \ \ \ } -\DoxyCodeLine{00271\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_aa7c583b48551710dd4f71bb5a72c029a}{spi\_device}};\ \ \ \ \ } -\DoxyCodeLine{00272\ } -\DoxyCodeLine{00273\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a26db0bb1cf4ad4272a363c9995cc6851}{bno08x\_init\_status\_t}}()} -\DoxyCodeLine{00274\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ :\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a918d393541f260ae059614ed477887df}{gpio\_outputs}}(false)} -\DoxyCodeLine{00275\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a7439c3e0e98c3c2276f8607e5a36b557}{gpio\_inputs}}(false)} -\DoxyCodeLine{00276\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a277d28ef5596d4777476d64de3f2d905}{isr\_service}}(false)} -\DoxyCodeLine{00277\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_aa04ab662c6a1a052944312ca79a17bc3}{isr\_handler}}(false)} -\DoxyCodeLine{00278\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a6b2d0002d0e817d6384a1064453eb84d}{task\_count}}(0)} -\DoxyCodeLine{00279\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a04ef18c7f80f305a621b6cc3e5b6107d}{data\_proc\_task}}(false)} -\DoxyCodeLine{00280\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a92f78cc3fd3161bbc1fcad08b9c6bcb5}{spi\_task}}(false)} -\DoxyCodeLine{00281\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a9855844dee2cd51e734693294d5cc438}{spi\_bus}}(false)} -\DoxyCodeLine{00282\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_aa7c583b48551710dd4f71bb5a72c029a}{spi\_device}}(false)} -\DoxyCodeLine{00283\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00284\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00285\ \ \ \ \ \ \ \ \ \}\ \mbox{\hyperlink{class_b_n_o08x_a200dfd32391bcaff73e8498674c7ec87}{bno08x\_init\_status\_t}};} -\DoxyCodeLine{00286\ } -\DoxyCodeLine{00287\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d}{init\_config\_args}}();} -\DoxyCodeLine{00288\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10}{init\_gpio}}();} -\DoxyCodeLine{00289\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4}{init\_gpio\_inputs}}();} -\DoxyCodeLine{00290\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64}{init\_gpio\_outputs}}();} -\DoxyCodeLine{00291\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61}{init\_hint\_isr}}();} -\DoxyCodeLine{00292\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81}{init\_spi}}();} -\DoxyCodeLine{00293\ } -\DoxyCodeLine{00294\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3}{deinit\_gpio}}();} -\DoxyCodeLine{00295\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c}{deinit\_gpio\_inputs}}();} -\DoxyCodeLine{00296\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_ab132a061bd437fd109225446aa1f6010}{deinit\_gpio\_outputs}}();} -\DoxyCodeLine{00297\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758}{deinit\_hint\_isr}}();} -\DoxyCodeLine{00298\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_a233920ce97f685fbdabecccacf471d85}{deinit\_spi}}();} -\DoxyCodeLine{00299\ } -\DoxyCodeLine{00300\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e}{wait\_for\_rx\_done}}();} -\DoxyCodeLine{00301\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773}{wait\_for\_tx\_done}}();} -\DoxyCodeLine{00302\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf}{wait\_for\_data}}();} -\DoxyCodeLine{00303\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638}{receive\_packet}}();} -\DoxyCodeLine{00304\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_acb246769719351e02bf2aff06d039475}{receive\_packet\_header}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00305\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c}{receive\_packet\_body}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00306\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a}{send\_packet}}(\mbox{\hyperlink{class_b_n_o08x_a3a1a869ac69e6ee850bd2a7f90dd8945}{bno08x\_tx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00307\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc}{flush\_rx\_packets}}(uint8\_t\ flush\_count);} -\DoxyCodeLine{00308\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca}{enable\_report}}(uint8\_t\ report\_ID,\ uint32\_t\ time\_between\_reports,\ \textcolor{keyword}{const}\ EventBits\_t\ report\_evt\_grp\_bit,\ uint32\_t\ special\_config\ =\ 0);} -\DoxyCodeLine{00309\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693}{disable\_report}}(uint8\_t\ report\_ID,\ \textcolor{keyword}{const}\ EventBits\_t\ report\_evt\_grp\_bit);} -\DoxyCodeLine{00310\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f}{queue\_packet}}(uint8\_t\ channel\_number,\ uint8\_t\ data\_length,\ uint8\_t*\ commands);} -\DoxyCodeLine{00311\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9}{queue\_command}}(uint8\_t\ command,\ uint8\_t*\ commands);} -\DoxyCodeLine{00312\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3}{queue\_feature\_command}}(uint8\_t\ report\_ID,\ uint32\_t\ time\_between\_reports,\ uint32\_t\ specific\_config\ =\ 0);} -\DoxyCodeLine{00313\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91}{queue\_calibrate\_command}}(uint8\_t\ \_to\_calibrate);} -\DoxyCodeLine{00314\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2}{queue\_tare\_command}}(uint8\_t\ command,\ uint8\_t\ axis\ =\ \mbox{\hyperlink{class_b_n_o08x_a1ef13f6f330810934416ad5fe0ee55b2}{TARE\_AXIS\_ALL}},\ uint8\_t\ rotation\_vector\_basis\ =\ \mbox{\hyperlink{class_b_n_o08x_a8e2cfc25d0e34ae53a762b88cc3ac3c8}{TARE\_ROTATION\_VECTOR}});} -\DoxyCodeLine{00315\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1}{queue\_request\_product\_id\_command}}();} -\DoxyCodeLine{00316\ } -\DoxyCodeLine{00317\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ functions\ to\ parse\ packets\ received\ from\ bno08x}} -\DoxyCodeLine{00318\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924}{parse\_packet}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet,\ \textcolor{keywordtype}{bool}\&\ notify\_users);} -\DoxyCodeLine{00319\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036}{parse\_product\_id\_report}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00320\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a51b360d795563b55559f11efb40be36a}{parse\_frs\_read\_response\_report}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00321\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981}{parse\_feature\_get\_response\_report}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00322\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d}{parse\_input\_report}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00323\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55}{parse\_input\_report\_data}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet,\ uint16\_t*\ data,\ uint16\_t\ data\_length);} -\DoxyCodeLine{00324\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d}{parse\_gyro\_integrated\_rotation\_vector\_report}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00325\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7}{parse\_command\_report}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00326\ } -\DoxyCodeLine{00327\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ functions\ to\ update\ data\ returned\ to\ user}} -\DoxyCodeLine{00328\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_afe588fbd0055193d3bc08984d7732354}{update\_accelerometer\_data}}(uint16\_t*\ data,\ uint8\_t\ status);} -\DoxyCodeLine{00329\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708}{update\_lin\_accelerometer\_data}}(uint16\_t*\ data,\ uint8\_t\ status);} -\DoxyCodeLine{00330\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab}{update\_calibrated\_gyro\_data}}(uint16\_t*\ data,\ uint8\_t\ status);} -\DoxyCodeLine{00331\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e}{update\_uncalibrated\_gyro\_data}}(uint16\_t*\ data,\ uint8\_t\ status);} -\DoxyCodeLine{00332\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88}{update\_magf\_data}}(uint16\_t*\ data,\ uint8\_t\ status);} -\DoxyCodeLine{00333\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e}{update\_gravity\_data}}(uint16\_t*\ data,\ uint8\_t\ status);} -\DoxyCodeLine{00334\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b}{update\_rotation\_vector\_data}}(uint16\_t*\ data,\ uint8\_t\ status);} -\DoxyCodeLine{00335\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f}{update\_step\_counter\_data}}(uint16\_t*\ data);} -\DoxyCodeLine{00336\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22}{update\_raw\_accelerometer\_data}}(uint16\_t*\ data);} -\DoxyCodeLine{00337\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea}{update\_raw\_gyro\_data}}(uint16\_t*\ data);} -\DoxyCodeLine{00338\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245}{update\_raw\_magf\_data}}(uint16\_t*\ data);} -\DoxyCodeLine{00339\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1}{update\_tap\_detector\_data}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00340\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a358316b883928c50dd381f024e6b0645}{update\_stability\_classifier\_data}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00341\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0}{update\_personal\_activity\_classifier\_data}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00342\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c}{update\_command\_data}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00343\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab}{update\_integrated\_gyro\_rotation\_vector\_data}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00344\ } -\DoxyCodeLine{00345\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ for\ debug}} -\DoxyCodeLine{00346\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a35856c108a47de8b3b38c4395aabb4eb}{print\_header}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00347\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49}{print\_packet}}(\mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\_rx\_packet\_t}}*\ packet);} -\DoxyCodeLine{00348\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_ae4670fed6de963a087ab58f95fda319b}{first\_boot}}\ =\ \textcolor{keyword}{true};\ } -\DoxyCodeLine{00349\ } -\DoxyCodeLine{00350\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ spi\ task}} -\DoxyCodeLine{00351\ \ \ \ \ \ \ \ \ TaskHandle\_t\ \mbox{\hyperlink{class_b_n_o08x_a615090aae15f1b0410a7e5ecb94957b5}{spi\_task\_hdl}};\ } -\DoxyCodeLine{00352\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74}{spi\_task\_trampoline}}(\textcolor{keywordtype}{void}*\ arg);} -\DoxyCodeLine{00353\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf}{spi\_task}}();} -\DoxyCodeLine{00354\ } -\DoxyCodeLine{00355\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ data\ processing\ task}} -\DoxyCodeLine{00356\ \ \ \ \ \ \ \ \ TaskHandle\_t\ \mbox{\hyperlink{class_b_n_o08x_af9b6fbf35e7cd55d517d30c6429a21a4}{data\_proc\_task\_hdl}};\ } -\DoxyCodeLine{00357\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520}{data\_proc\_task\_trampoline}}(\textcolor{keywordtype}{void}*\ arg);} -\DoxyCodeLine{00358\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8}{data\_proc\_task}}();} -\DoxyCodeLine{00359\ } -\DoxyCodeLine{00360\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ task\ control}} -\DoxyCodeLine{00361\ \ \ \ \ \ \ \ \ SemaphoreHandle\_t\ \mbox{\hyperlink{class_b_n_o08x_aa92ff86d82a097a565ed2a2b9000b571}{sem\_kill\_tasks}};\ } -\DoxyCodeLine{00362\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be}{launch\_tasks}}();} -\DoxyCodeLine{00363\ \ \ \ \ \ \ \ \ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0}{kill\_all\_tasks}}();} -\DoxyCodeLine{00364\ } -\DoxyCodeLine{00365\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64}{update\_report\_period\_trackers}}(uint8\_t\ report\_ID,\ uint32\_t\ new\_period);} -\DoxyCodeLine{00366\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa}{report\_ID\_to\_report\_period\_tracker\_idx}}(uint8\_t\ report\_ID);} -\DoxyCodeLine{00367\ } -\DoxyCodeLine{00368\ \ \ \ \ \ \ \ \ EventGroupHandle\_t} -\DoxyCodeLine{00369\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_aa2b4442b5cc63ebf0c495e6fb537c85e}{evt\_grp\_spi}};\ } -\DoxyCodeLine{00370\ \ \ \ \ \ \ \ \ EventGroupHandle\_t\ \mbox{\hyperlink{class_b_n_o08x_a63eb6c8be6f3bc943a86bb0496871275}{evt\_grp\_report\_en}};\ } -\DoxyCodeLine{00371\ \ \ \ \ \ \ \ \ EventGroupHandle\_t\ \mbox{\hyperlink{class_b_n_o08x_ac4b1fae7a1155c8b93b645b4eb6eb0f1}{evt\_grp\_task\_flow}};\ } -\DoxyCodeLine{00372\ } -\DoxyCodeLine{00373\ \ \ \ \ \ \ \ \ QueueHandle\_t\ \mbox{\hyperlink{class_b_n_o08x_a7d4661d3aae56013caa8f2bff0f67c08}{queue\_rx\_data}};\ \ \ \ \ \ \ } -\DoxyCodeLine{00374\ \ \ \ \ \ \ \ \ QueueHandle\_t\ \mbox{\hyperlink{class_b_n_o08x_a4d5c5eee87a578de9c8318cd294b3a22}{queue\_tx\_data}};\ \ \ \ \ \ \ } -\DoxyCodeLine{00375\ \ \ \ \ \ \ \ \ QueueHandle\_t\ \mbox{\hyperlink{class_b_n_o08x_a9a1c851e8fa5633e11f6abee293d7e9b}{queue\_frs\_read\_data}};\ } -\DoxyCodeLine{00376\ \ \ \ \ \ \ \ \ QueueHandle\_t\ \mbox{\hyperlink{class_b_n_o08x_a84b3639cc159262e0137adb0db5cf9aa}{queue\_reset\_reason}};\ \ } -\DoxyCodeLine{00377\ } -\DoxyCodeLine{00378\ \ \ \ \ \ \ \ \ std::vector>\ \mbox{\hyperlink{class_b_n_o08x_a6a15e3a64dd71ea61f0448afcce96409}{cb\_list}};\ \textcolor{comment}{//\ Vector\ for\ storing\ any\ call-\/back\ functions\ added\ with\ register\_cb()}} -\DoxyCodeLine{00379\ } -\DoxyCodeLine{00380\ \ \ \ \ \ \ \ \ uint32\_t\ \mbox{\hyperlink{class_b_n_o08x_a7bd032712a975e73e66bd72a3502baba}{meta\_data}}[9];\ } -\DoxyCodeLine{00381\ } -\DoxyCodeLine{00382\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{structbno08x__config__t}{bno08x\_config\_t}}\ \mbox{\hyperlink{class_b_n_o08x_aeda443e9f608fccfec0e6770edc90c82}{imu\_config}}\{\};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00383\ \ \ \ \ \ \ \ \ spi\_bus\_config\_t\ \mbox{\hyperlink{class_b_n_o08x_a982f065df42f00e53fd87c840efdb0f1}{bus\_config}}\{\};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00384\ \ \ \ \ \ \ \ \ spi\_device\_interface\_config\_t\ \mbox{\hyperlink{class_b_n_o08x_a425a1f5a9f3232aadc685caaf4c2f82e}{imu\_spi\_config}}\{\};\ } -\DoxyCodeLine{00385\ \ \ \ \ \ \ \ \ spi\_device\_handle\_t\ \mbox{\hyperlink{class_b_n_o08x_acc0ea091465fc9a5736f5e0c6a0ce8ef}{spi\_hdl}}\{\};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00386\ \ \ \ \ \ \ \ \ spi\_transaction\_t\ \mbox{\hyperlink{class_b_n_o08x_ac16adc5f00b0039c98a4921f13895026}{spi\_transaction}}\{\};\ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00387\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a200dfd32391bcaff73e8498674c7ec87}{bno08x\_init\_status\_t}}} -\DoxyCodeLine{00388\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a4520fc3e1dec6389d470945786680013}{init\_status}};\ } -\DoxyCodeLine{00389\ } -\DoxyCodeLine{00390\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ These\ are\ the\ raw\ sensor\ values\ (without\ Q\ applied)\ pulled\ from\ the\ user\ requested\ Input\ Report}} -\DoxyCodeLine{00391\ \ \ \ \ \ \ \ \ uint32\_t\ \mbox{\hyperlink{class_b_n_o08x_abc972db20affbd0040b4e6c4892dd57b}{time\_stamp}};\ } -\DoxyCodeLine{00392\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a75fb2f06c5bbe26e3f3c794934ef954c}{raw\_accel\_X}},\ \mbox{\hyperlink{class_b_n_o08x_ab56e2ba505fa293d03e955137625c562}{raw\_accel\_Y}},\ \mbox{\hyperlink{class_b_n_o08x_af254d245b368027df6952b7d7522bd35}{raw\_accel\_Z}},} -\DoxyCodeLine{00393\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a3365b7ebde01e284274e655c60343df9}{accel\_accuracy}};\ } -\DoxyCodeLine{00394\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_ae1f71a432cb15e75f522fa18f29f4d50}{raw\_lin\_accel\_X}},\ \mbox{\hyperlink{class_b_n_o08x_aff3a5590471d1c9fc485a5610433915f}{raw\_lin\_accel\_Y}},\ \mbox{\hyperlink{class_b_n_o08x_abc8add47f1babc66c812a015614143d3}{raw\_lin\_accel\_Z}},} -\DoxyCodeLine{00395\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a35e1635ef5edde8fc8640f978c6f2e3c}{accel\_lin\_accuracy}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00396\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a87faca2c8c71ff46bf2e6ad4ba271b3a}{raw\_calib\_gyro\_X}},\ \mbox{\hyperlink{class_b_n_o08x_a66c48af1d4162a9ec25c3a1c95660fe4}{raw\_calib\_gyro\_Y}},\ \mbox{\hyperlink{class_b_n_o08x_af5450d1a9c20c2a5c62c960e3df11c0e}{raw\_calib\_gyro\_Z}};\ } -\DoxyCodeLine{00397\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a69dc7e97875060213085ba964b3bd987}{raw\_quat\_I}},\ \mbox{\hyperlink{class_b_n_o08x_a61ae05dc5572b326541bf8099f0c2a54}{raw\_quat\_J}},\ \mbox{\hyperlink{class_b_n_o08x_a7720c44ed1c0f1a0663d2adc5e1a1ea1}{raw\_quat\_K}},\ \mbox{\hyperlink{class_b_n_o08x_a867354267253ae828be4fae15c062db3}{raw\_quat\_real}},\ \mbox{\hyperlink{class_b_n_o08x_a033d6cb1aa137743b69cc3e401df67b7}{raw\_quat\_radian\_accuracy}},} -\DoxyCodeLine{00398\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a36223f7124751fa71e860b2ef55dd2ac}{quat\_accuracy}};\ } -\DoxyCodeLine{00399\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a6537ed69245cf71cad6a6a44480dddaa}{integrated\_gyro\_velocity\_X}},\ \mbox{\hyperlink{class_b_n_o08x_a00b39e22ea9fe306e88aaed490ee0a51}{integrated\_gyro\_velocity\_Y}},} -\DoxyCodeLine{00400\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ad112beb64badd22a2e1d717e1ee921c8}{integrated\_gyro\_velocity\_Z}};\ } -\DoxyCodeLine{00401\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_af45016be9ea523d80be8467b2907b499}{gravity\_X}},\ \mbox{\hyperlink{class_b_n_o08x_af20dcd487a9fe8fa6243817d51e37be5}{gravity\_Y}},\ \mbox{\hyperlink{class_b_n_o08x_afa1cf5c3afbb258d97c55c5fb187f2d6}{gravity\_Z}},} -\DoxyCodeLine{00402\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ae01698d287ea999179a11e2244902022}{gravity\_accuracy}};\ } -\DoxyCodeLine{00403\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_afdc5cdb65bd0b36528b5b671b9d27053}{raw\_uncalib\_gyro\_X}},\ \mbox{\hyperlink{class_b_n_o08x_acc2c66e2985975266a286385ea855117}{raw\_uncalib\_gyro\_Y}},\ \mbox{\hyperlink{class_b_n_o08x_afac9dd4161f4c0051255293680c9082b}{raw\_uncalib\_gyro\_Z}},\ \mbox{\hyperlink{class_b_n_o08x_a8a2667f668317cee0a9fc4ef0accc3f5}{raw\_bias\_X}},\ \mbox{\hyperlink{class_b_n_o08x_ac38ff5eb93d3c3db0af2504ba02fd93c}{raw\_bias\_Y}},} -\DoxyCodeLine{00404\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a0968eaed9b3d979a2caa1aba6e6b417a}{raw\_bias\_Z}};\ } -\DoxyCodeLine{00405\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_aa5bdf740161b7c37adcac0154a410118}{raw\_magf\_X}},\ \mbox{\hyperlink{class_b_n_o08x_acd365418f24a6da61122c66d82086639}{raw\_magf\_Y}},\ \mbox{\hyperlink{class_b_n_o08x_ab4862de31d0874b44b6745678e1c905e}{raw\_magf\_Z}},} -\DoxyCodeLine{00406\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ac5d4e151690774687efa951ca41c16ae}{magf\_accuracy}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00407\ \ \ \ \ \ \ \ \ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a1171a5738a4e6831ec7fa32a29f15554}{tap\_detector}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00408\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_ad80a77973371b12d722ea39063c648be}{step\_count}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00409\ \ \ \ \ \ \ \ \ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a1b12471e92536a79d0c425d77676f2e1}{stability\_classifier}};\ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00410\ \ \ \ \ \ \ \ \ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a75cea49c1c08ca28d9fa7e5ed61c6e7b}{activity\_classifier}};\ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00411\ \ \ \ \ \ \ \ \ uint8\_t*\ \mbox{\hyperlink{class_b_n_o08x_af96e8cd070459f945ffbf01b98106e13}{activity\_confidences}}\ =\ \textcolor{keyword}{nullptr};\ } -\DoxyCodeLine{00412\ \ \ \ \ \ \ \ \ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_ad212b5028a31e857e76d251ced2724e1}{calibration\_status}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00413\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a937cbdc4edaac72c8cad041d79de5701}{mems\_raw\_accel\_X}},\ \mbox{\hyperlink{class_b_n_o08x_ad83cecb8a5d2be01db6792755b6057e9}{mems\_raw\_accel\_Y}},} -\DoxyCodeLine{00414\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a59a4d75f1302ab693b1b26e9ccaa5341}{mems\_raw\_accel\_Z}};\ } -\DoxyCodeLine{00415\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a3d6b6257462951ea023af7076c80f6dd}{mems\_raw\_gyro\_X}},\ \mbox{\hyperlink{class_b_n_o08x_ab6b142416912a096886dd63ad0beb865}{mems\_raw\_gyro\_Y}},} -\DoxyCodeLine{00416\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ac35d5b12721ab876eaeb1f714a9b3b1d}{mems\_raw\_gyro\_Z}};\ } -\DoxyCodeLine{00417\ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_ab587cdf991342b69b7fff3b33f537eb5}{mems\_raw\_magf\_X}},\ \mbox{\hyperlink{class_b_n_o08x_aad926054c81818fff611e10ed913706a}{mems\_raw\_magf\_Y}},} -\DoxyCodeLine{00418\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a90f0cdf11decc276006f76a494d42ce3}{mems\_raw\_magf\_Z}};\ } -\DoxyCodeLine{00419\ } -\DoxyCodeLine{00420\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ IRAM\_ATTR\ \mbox{\hyperlink{class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7}{hint\_handler}}(\textcolor{keywordtype}{void}*\ arg);} -\DoxyCodeLine{00421\ } -\DoxyCodeLine{00422\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a5448bffec9a90f5c388b3c22928463ae}{TASK\_CNT}}\ =\ 2U;\ } -\DoxyCodeLine{00423\ } -\DoxyCodeLine{00424\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a1a037bda37493cde56732cc6fdc7884b}{RX\_DATA\_LENGTH}}\ =\ 300U;\ \ \ \ } -\DoxyCodeLine{00425\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint16\_t\ \mbox{\hyperlink{class_b_n_o08x_a2a5b978233eab4c103ab01cfc33a1750}{MAX\_METADATA\_LENGTH}}\ =\ 9U;\ } -\DoxyCodeLine{00426\ } -\DoxyCodeLine{00427\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ TickType\_t\ \mbox{\hyperlink{class_b_n_o08x_ae51d4e3228a91ee407d5866e604804c4}{HOST\_INT\_TIMEOUT\_DEFAULT\_MS}}\ =} -\DoxyCodeLine{00428\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 3000UL\ /} -\DoxyCodeLine{00429\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ portTICK\_PERIOD\_MS;\ } -\DoxyCodeLine{00430\ } -\DoxyCodeLine{00431\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ TickType\_t\ \mbox{\hyperlink{class_b_n_o08x_aa07e329d693eb8d9270a7f9ad6f1d94b}{HARD\_RESET\_DELAY\_MS}}\ =} -\DoxyCodeLine{00432\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 100UL\ /} -\DoxyCodeLine{00433\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ portTICK\_PERIOD\_MS;\ } -\DoxyCodeLine{00434\ } -\DoxyCodeLine{00435\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ TickType\_t\ \mbox{\hyperlink{class_b_n_o08x_a38e31bdb22afdfe05372ffcd5eabfdd2}{CMD\_EXECUTION\_DELAY\_MS}}\ =} -\DoxyCodeLine{00436\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 10UL\ /} -\DoxyCodeLine{00437\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ portTICK\_PERIOD\_MS;\ } -\DoxyCodeLine{00438\ } -\DoxyCodeLine{00439\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint32\_t\ \mbox{\hyperlink{class_b_n_o08x_a031976dacd97917d9d72edccb607160c}{SCLK\_MAX\_SPEED}}\ =\ 3000000UL;\ } -\DoxyCodeLine{00440\ } -\DoxyCodeLine{00441\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ evt\_grp\_spi\ bits}} -\DoxyCodeLine{00442\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a32cffd8f78881925d22d5a7cb55f2bbc}{EVT\_GRP\_SPI\_RX\_DONE\_BIT}}\ =} -\DoxyCodeLine{00443\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 0U);\ } -\DoxyCodeLine{00444\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a96342b0182f339d5a8d6cac1214ce174}{EVT\_GRP\_SPI\_RX\_VALID\_PACKET\_BIT}}\ =} -\DoxyCodeLine{00445\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 1U);\ } -\DoxyCodeLine{00446\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a15e3f92812f8fe70b30966b73a7cb5b2}{EVT\_GRP\_SPI\_RX\_INVALID\_PACKET\_BIT}}\ =} -\DoxyCodeLine{00447\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 2U);\ } -\DoxyCodeLine{00448\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_adf2c292674e428c3b65c846cfab4deb7}{EVT\_GRP\_SPI\_TX\_DONE\_BIT}}\ =\ (1\ <<\ 3);\ } -\DoxyCodeLine{00449\ } -\DoxyCodeLine{00450\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ evt\_grp\_report\_en\ bits}} -\DoxyCodeLine{00451\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a198da2ee3cd9cfa459c3c41c4f8c44b7}{EVT\_GRP\_RPT\_ROTATION\_VECTOR\_BIT}}\ =\ (1\ <<\ 0);\ \ \ \ \ \ } -\DoxyCodeLine{00452\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a0f3f33d93b72ba6564f9d5fa93c24f98}{EVT\_GRP\_RPT\_GAME\_ROTATION\_VECTOR\_BIT}}\ =\ (1\ <<\ 1);\ } -\DoxyCodeLine{00453\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_aa9703cee46912a545b5e85e671f08e4b}{EVT\_GRP\_RPT\_ARVR\_S\_ROTATION\_VECTOR\_BIT}}\ =} -\DoxyCodeLine{00454\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 2U);\ } -\DoxyCodeLine{00455\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a79d3fff1e0f19467cad231b22edafa0f}{EVT\_GRP\_RPT\_ARVR\_S\_GAME\_ROTATION\_VECTOR\_BIT}}\ =} -\DoxyCodeLine{00456\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 3U);\ } -\DoxyCodeLine{00457\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a541155dc4544193451cf102e2a992da9}{EVT\_GRP\_RPT\_GYRO\_ROTATION\_VECTOR\_BIT}}\ =} -\DoxyCodeLine{00458\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 4U);\ } -\DoxyCodeLine{00459\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a17b19c32d4dfbc9ae2761a0cdd873314}{EVT\_GRP\_RPT\_ACCELEROMETER\_BIT}}\ =\ (1U\ <<\ 5U);\ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00460\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_ad93161968a53ff53a6bb74ab7c34fbff}{EVT\_GRP\_RPT\_LINEAR\_ACCELEROMETER\_BIT}}\ =\ (1U\ <<\ 6U);\ \ } -\DoxyCodeLine{00461\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_ab94a8f69673a3db7556ba67775c5ea93}{EVT\_GRP\_RPT\_GRAVITY\_BIT}}\ =\ (1U\ <<\ 7U);\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00462\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a3a8b12ea9b75f97191785a60d1aa962a}{EVT\_GRP\_RPT\_GYRO\_BIT}}\ =\ (1U\ <<\ 8U);\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00463\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_af86821bc0f1e7f5897de20b5e47a85bd}{EVT\_GRP\_RPT\_GYRO\_UNCALIBRATED\_BIT}}\ =\ (1U\ <<\ 9U);\ \ \ \ \ } -\DoxyCodeLine{00464\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a901af6f2d552f197ee830d0a1c06679c}{EVT\_GRP\_RPT\_MAGNETOMETER\_BIT}}\ =\ (1U\ <<\ 10U);\ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00465\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a665464f781fe891b9179478d0174af47}{EVT\_GRP\_RPT\_TAP\_DETECTOR\_BIT}}\ =\ (1U\ <<\ 11U);\ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00466\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_ab264b65a3aa5a9a74ed11b8977164a73}{EVT\_GRP\_RPT\_STEP\_COUNTER\_BIT}}\ =\ (1U\ <<\ 12U);\ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00467\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a7d6ee23222f55dbe9f70e04b36d9add2}{EVT\_GRP\_RPT\_STABILITY\_CLASSIFIER\_BIT}}\ =\ (1U\ <<\ 13U);\ } -\DoxyCodeLine{00468\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a96eb1b1bfe1266791fd424b3ce402c56}{EVT\_GRP\_RPT\_ACTIVITY\_CLASSIFIER\_BIT}}\ =\ (1U\ <<\ 14U);\ \ } -\DoxyCodeLine{00469\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a3e56d12435f7be81956d68196f1a46b4}{EVT\_GRP\_RPT\_RAW\_ACCELEROMETER\_BIT}}\ =\ (1U\ <<\ 15U);\ \ \ \ } -\DoxyCodeLine{00470\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a6be7b240e4447c2c643e706954093aa0}{EVT\_GRP\_RPT\_RAW\_GYRO\_BIT}}\ =\ (1U\ <<\ 16U);\ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00471\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_ac28553b40b82c7cb409938681afe6cec}{EVT\_GRP\_RPT\_RAW\_MAGNETOMETER\_BIT}}\ =\ (1U\ <<\ 17U);\ \ \ \ \ } -\DoxyCodeLine{00472\ } -\DoxyCodeLine{00473\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ evt\_grp\_task\_flow\ bits}} -\DoxyCodeLine{00474\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a5fc8c8969043c5d08fce80eb1d74a761}{EVT\_GRP\_TSK\_FLW\_RUNNING\_BIT}}\ =} -\DoxyCodeLine{00475\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 0U);\ } -\DoxyCodeLine{00476\ } -\DoxyCodeLine{00477\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ EventBits\_t\ \mbox{\hyperlink{class_b_n_o08x_a89399e8a68a53bc2a269ab73625a2da2}{EVT\_GRP\_RPT\_ALL\_BITS}}\ =} -\DoxyCodeLine{00478\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a198da2ee3cd9cfa459c3c41c4f8c44b7}{EVT\_GRP\_RPT\_ROTATION\_VECTOR\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a0f3f33d93b72ba6564f9d5fa93c24f98}{EVT\_GRP\_RPT\_GAME\_ROTATION\_VECTOR\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_aa9703cee46912a545b5e85e671f08e4b}{EVT\_GRP\_RPT\_ARVR\_S\_ROTATION\_VECTOR\_BIT}}\ |} -\DoxyCodeLine{00479\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a79d3fff1e0f19467cad231b22edafa0f}{EVT\_GRP\_RPT\_ARVR\_S\_GAME\_ROTATION\_VECTOR\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a541155dc4544193451cf102e2a992da9}{EVT\_GRP\_RPT\_GYRO\_ROTATION\_VECTOR\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a17b19c32d4dfbc9ae2761a0cdd873314}{EVT\_GRP\_RPT\_ACCELEROMETER\_BIT}}\ |} -\DoxyCodeLine{00480\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ad93161968a53ff53a6bb74ab7c34fbff}{EVT\_GRP\_RPT\_LINEAR\_ACCELEROMETER\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_ab94a8f69673a3db7556ba67775c5ea93}{EVT\_GRP\_RPT\_GRAVITY\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a3a8b12ea9b75f97191785a60d1aa962a}{EVT\_GRP\_RPT\_GYRO\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_af86821bc0f1e7f5897de20b5e47a85bd}{EVT\_GRP\_RPT\_GYRO\_UNCALIBRATED\_BIT}}\ |} -\DoxyCodeLine{00481\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a901af6f2d552f197ee830d0a1c06679c}{EVT\_GRP\_RPT\_MAGNETOMETER\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a665464f781fe891b9179478d0174af47}{EVT\_GRP\_RPT\_TAP\_DETECTOR\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_ab264b65a3aa5a9a74ed11b8977164a73}{EVT\_GRP\_RPT\_STEP\_COUNTER\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a7d6ee23222f55dbe9f70e04b36d9add2}{EVT\_GRP\_RPT\_STABILITY\_CLASSIFIER\_BIT}}\ |} -\DoxyCodeLine{00482\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a96eb1b1bfe1266791fd424b3ce402c56}{EVT\_GRP\_RPT\_ACTIVITY\_CLASSIFIER\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a3e56d12435f7be81956d68196f1a46b4}{EVT\_GRP\_RPT\_RAW\_ACCELEROMETER\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a6be7b240e4447c2c643e706954093aa0}{EVT\_GRP\_RPT\_RAW\_GYRO\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_ac28553b40b82c7cb409938681afe6cec}{EVT\_GRP\_RPT\_RAW\_MAGNETOMETER\_BIT}};} -\DoxyCodeLine{00483\ } -\DoxyCodeLine{00484\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ Higher\ level\ calibration\ commands,\ used\ by\ queue\_calibrate\_command}} -\DoxyCodeLine{00485\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_acd5b44d705af1f9aaa271a59a9d2d595}{CALIBRATE\_ACCEL}}\ =\ 0U;\ \ \ \ \ \ \ \ } -\DoxyCodeLine{00486\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_aeac84719a1cc0f9c8d5a9a749391d4db}{CALIBRATE\_GYRO}}\ =\ 1U;\ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00487\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_ac00e8b59ae8d710cf79956eaafa97ddb}{CALIBRATE\_MAG}}\ =\ 2U;\ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00488\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a955dcb60da150490e17367a871b3a3d2}{CALIBRATE\_PLANAR\_ACCEL}}\ =\ 3U;\ } -\DoxyCodeLine{00489\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_af53d9e99f163d97ef92fe989b1dd25cc}{CALIBRATE\_ACCEL\_GYRO\_MAG}}\ =} -\DoxyCodeLine{00490\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 4U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00491\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a584bfa04a39feb93279ee673c340db54}{CALIBRATE\_STOP}}\ =\ 5U;\ } -\DoxyCodeLine{00492\ } -\DoxyCodeLine{00493\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ Command\ IDs\ (see\ Ref.\ Manual\ 6.4)}} -\DoxyCodeLine{00494\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a384a1efc9857ad938be3bb44f871539b}{COMMAND\_ERRORS}}\ =\ 1U;} -\DoxyCodeLine{00495\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a93dd073c0cc1f3ccfde552649f6ebccc}{COMMAND\_COUNTER}}\ =\ 2U;} -\DoxyCodeLine{00496\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a0a1756bc16ba3eac45f4229b1e350107}{COMMAND\_TARE}}\ =\ 3U;\ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00497\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a30eb6d305a187d4d36546841e12176b9}{COMMAND\_INITIALIZE}}\ =\ 4U;\ \ \ \ \ \ } -\DoxyCodeLine{00498\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_af124a6c1d8b871f3181b6c85f1099cb2}{COMMAND\_DCD}}\ =\ 6U;\ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00499\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a8381dfe403ddff522f172cb16780731a}{COMMAND\_ME\_CALIBRATE}}\ =\ 7U;\ \ \ \ } -\DoxyCodeLine{00500\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a7a246989c94cd87f68166b20b7ad4c8b}{COMMAND\_DCD\_PERIOD\_SAVE}}\ =\ 9U;\ } -\DoxyCodeLine{00501\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a308c8b5307d93a67b5b9066d44494aa5}{COMMAND\_OSCILLATOR}}\ =\ 10U;\ \ \ \ \ } -\DoxyCodeLine{00502\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a4f580b3cb232a762ea7019ee7b04d419}{COMMAND\_CLEAR\_DCD}}\ =\ 11U;\ \ \ \ \ \ } -\DoxyCodeLine{00503\ } -\DoxyCodeLine{00504\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ SHTP\ channel\ 2\ control\ report\ IDs,\ used\ in\ communication\ with\ sensor\ (See\ Ref.\ Manual\ 6.2)}} -\DoxyCodeLine{00505\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a1e5b64caa514b7e4fe64ab214758b875}{SHTP\_REPORT\_COMMAND\_RESPONSE}}\ =\ 0xF1U;\ \ \ \ \ } -\DoxyCodeLine{00506\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_ab04695dd189412092254e52bd6e5a75a}{SHTP\_REPORT\_COMMAND\_REQUEST}}\ =\ 0xF2U;\ \ \ \ \ \ } -\DoxyCodeLine{00507\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_aeb760b095dcf808a413ef696f2608e43}{SHTP\_REPORT\_FRS\_READ\_RESPONSE}}\ =\ 0xF3U;\ \ \ \ } -\DoxyCodeLine{00508\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a74af7eacc35cc825940b647c2de0d368}{SHTP\_REPORT\_FRS\_READ\_REQUEST}}\ =\ 0xF4U;\ \ \ \ \ } -\DoxyCodeLine{00509\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a0177134162e116501bc9483c6e4b76c3}{SHTP\_REPORT\_PRODUCT\_ID\_RESPONSE}}\ =\ 0xF8U;\ \ } -\DoxyCodeLine{00510\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a542405639c28bd56bc4361b922763c95}{SHTP\_REPORT\_PRODUCT\_ID\_REQUEST}}\ =\ 0xF9U;\ \ \ } -\DoxyCodeLine{00511\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_ae37d6f8431c8c465bfb0c662772b5cb9}{SHTP\_REPORT\_BASE\_TIMESTAMP}}\ =\ 0xFBU;\ \ \ \ \ \ \ } -\DoxyCodeLine{00512\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a1d3bff4e20c2c3d47db322c9e34ef338}{SHTP\_REPORT\_SET\_FEATURE\_COMMAND}}\ =\ 0xFDU;\ \ } -\DoxyCodeLine{00513\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_ad09312802cf5b8b5115362c86b53858b}{SHTP\_REPORT\_GET\_FEATURE\_RESPONSE}}\ =\ 0xFCU;\ } -\DoxyCodeLine{00514\ } -\DoxyCodeLine{00515\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ Sensor\ report\ IDs,\ used\ when\ enabling\ and\ reading\ BNO08x\ reports}} -\DoxyCodeLine{00516\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a354eaff2218eb382a1851537a75badcc}{SENSOR\_REPORT\_ID\_ACCELEROMETER}}\ =\ 0x01U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00517\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a224fb8f833806dd530c5f16e7ab5bc7a}{SENSOR\_REPORT\_ID\_GYROSCOPE}}\ =\ 0x02U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00518\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a06058a84d6604054aa66ee008ac64aa9}{SENSOR\_REPORT\_ID\_MAGNETIC\_FIELD}}\ =\ 0x03U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00519\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_ace7720a02c9f4ef38e319849f6c36a0b}{SENSOR\_REPORT\_ID\_LINEAR\_ACCELERATION}}\ =\ 0x04U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00520\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a37c91f995c385556486df5fbbce8a3d5}{SENSOR\_REPORT\_ID\_ROTATION\_VECTOR}}\ =\ 0x05U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00521\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a6730acb92053d44decb690a7b7234032}{SENSOR\_REPORT\_ID\_GRAVITY}}\ =\ 0x06U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00522\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_acb8e83fbb0645d4e98a96120ce9f431c}{SENSOR\_REPORT\_ID\_UNCALIBRATED\_GYRO}}\ =\ 0x07U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00523\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_ada7dbda9f7a0bfb0894a787ce0ff9cef}{SENSOR\_REPORT\_ID\_GAME\_ROTATION\_VECTOR}}\ =\ 0x08U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00524\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_abb6d0586a5a87b7b34f4c65ae52965a4}{SENSOR\_REPORT\_ID\_GEOMAGNETIC\_ROTATION\_VECTOR}}\ =\ 0x09U;\ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00525\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_acd0fc6ffa70dd2761cba0ac0b88c234f}{SENSOR\_REPORT\_ID\_GYRO\_INTEGRATED\_ROTATION\_VECTOR}}\ =\ 0x2AU;\ \ \ \ \ \ } -\DoxyCodeLine{00526\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a8114460c50e84b0ac750293ab72868c8}{SENSOR\_REPORT\_ID\_TAP\_DETECTOR}}\ =\ 0x10U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00527\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a2a10161bb564067a07f3fcf4021e00bb}{SENSOR\_REPORT\_ID\_STEP\_COUNTER}}\ =\ 0x11U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00528\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_ab5c29f31714b4755c0edbce7156652f7}{SENSOR\_REPORT\_ID\_STABILITY\_CLASSIFIER}}\ =\ 0x13U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00529\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a80ea70c4787dea6c3eabb48f583f1916}{SENSOR\_REPORT\_ID\_RAW\_ACCELEROMETER}}\ =\ 0x14U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00530\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a03b3000424e6d966b80655443ec546bc}{SENSOR\_REPORT\_ID\_RAW\_GYROSCOPE}}\ =\ 0x15U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00531\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a9e9a7578b7584e7eb2ad562b29565fa7}{SENSOR\_REPORT\_ID\_RAW\_MAGNETOMETER}}\ =\ 0x16U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00532\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a7274f6d3bda04da0bb304386b4e8d603}{SENSOR\_REPORT\_ID\_PERSONAL\_ACTIVITY\_CLASSIFIER}}\ =\ 0x1EU;\ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00533\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a8d4b91149cfc1a3cd615f60a4ad2275e}{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_ROTATION\_VECTOR}}\ =\ 0x28U;\ \ \ \ \ \ } -\DoxyCodeLine{00534\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_aeb51ebb6c82158cd7e23bd682c08c4e0}{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR}}\ =\ 0x29U;\ } -\DoxyCodeLine{00535\ } -\DoxyCodeLine{00536\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ Tare\ commands\ used\ by\ queue\_tare\_command}} -\DoxyCodeLine{00537\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a27df630f3e52b35552d2c1f2cf3496b0}{TARE\_NOW}}\ =\ 0U;\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00538\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a115aef7b38ec0dec2085f6917d832912}{TARE\_PERSIST}}\ =\ 1U;\ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00539\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a59cde7dd301c94a20b84735c5d49008e}{TARE\_SET\_REORIENTATION}}\ =\ 2U;\ } -\DoxyCodeLine{00540\ } -\DoxyCodeLine{00541\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_a9658c821658ab51fe6831a83d8903a53}{REPORT\_CNT}}\ =\ 19;\ } -\DoxyCodeLine{00542\ } -\DoxyCodeLine{00543\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__report__period__tracker__t}{bno08x\_report\_period\_tracker\_t}}\ \mbox{\hyperlink{class_b_n_o08x_ae3750acb4578ccdd7fcf20abcd8e0904}{report\_period\_trackers}}[\mbox{\hyperlink{class_b_n_o08x_a9658c821658ab51fe6831a83d8903a53}{REPORT\_CNT}}]\ =\ \{\{\mbox{\hyperlink{class_b_n_o08x_a354eaff2218eb382a1851537a75badcc}{SENSOR\_REPORT\_ID\_ACCELEROMETER}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_a224fb8f833806dd530c5f16e7ab5bc7a}{SENSOR\_REPORT\_ID\_GYROSCOPE}},\ 0\},} -\DoxyCodeLine{00544\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_a06058a84d6604054aa66ee008ac64aa9}{SENSOR\_REPORT\_ID\_MAGNETIC\_FIELD}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_ace7720a02c9f4ef38e319849f6c36a0b}{SENSOR\_REPORT\_ID\_LINEAR\_ACCELERATION}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_a37c91f995c385556486df5fbbce8a3d5}{SENSOR\_REPORT\_ID\_ROTATION\_VECTOR}},\ 0\},} -\DoxyCodeLine{00545\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_a6730acb92053d44decb690a7b7234032}{SENSOR\_REPORT\_ID\_GRAVITY}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_acb8e83fbb0645d4e98a96120ce9f431c}{SENSOR\_REPORT\_ID\_UNCALIBRATED\_GYRO}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_ada7dbda9f7a0bfb0894a787ce0ff9cef}{SENSOR\_REPORT\_ID\_GAME\_ROTATION\_VECTOR}},\ 0\},} -\DoxyCodeLine{00546\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_abb6d0586a5a87b7b34f4c65ae52965a4}{SENSOR\_REPORT\_ID\_GEOMAGNETIC\_ROTATION\_VECTOR}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_acd0fc6ffa70dd2761cba0ac0b88c234f}{SENSOR\_REPORT\_ID\_GYRO\_INTEGRATED\_ROTATION\_VECTOR}},\ 0\},} -\DoxyCodeLine{00547\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_a8114460c50e84b0ac750293ab72868c8}{SENSOR\_REPORT\_ID\_TAP\_DETECTOR}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_a2a10161bb564067a07f3fcf4021e00bb}{SENSOR\_REPORT\_ID\_STEP\_COUNTER}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_ab5c29f31714b4755c0edbce7156652f7}{SENSOR\_REPORT\_ID\_STABILITY\_CLASSIFIER}},\ 0\},} -\DoxyCodeLine{00548\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_a80ea70c4787dea6c3eabb48f583f1916}{SENSOR\_REPORT\_ID\_RAW\_ACCELEROMETER}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_a03b3000424e6d966b80655443ec546bc}{SENSOR\_REPORT\_ID\_RAW\_GYROSCOPE}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_a9e9a7578b7584e7eb2ad562b29565fa7}{SENSOR\_REPORT\_ID\_RAW\_MAGNETOMETER}},\ 0\},} -\DoxyCodeLine{00549\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_a7274f6d3bda04da0bb304386b4e8d603}{SENSOR\_REPORT\_ID\_PERSONAL\_ACTIVITY\_CLASSIFIER}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_a8d4b91149cfc1a3cd615f60a4ad2275e}{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_ROTATION\_VECTOR}},\ 0\},} -\DoxyCodeLine{00550\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_aeb51ebb6c82158cd7e23bd682c08c4e0}{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR}},} -\DoxyCodeLine{00551\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 0\}\};\ } -\DoxyCodeLine{00552\ } -\DoxyCodeLine{00553\ \ \ \ \ \ \ \ \ uint32\_t\ \mbox{\hyperlink{class_b_n_o08x_a7ffc2875b3dff21a827052e4faf273b7}{largest\_sample\_period\_us}}\ =} -\DoxyCodeLine{00554\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 0;\ } -\DoxyCodeLine{00555\ \ \ \ \ \ \ \ \ uint8\_t\ \mbox{\hyperlink{class_b_n_o08x_ae2e8382b5ff8d0ca3375a10b6e273f0c}{current\_slowest\_report\_ID}};\ } -\DoxyCodeLine{00556\ } -\DoxyCodeLine{00557\ \ \ \ \ \ \ \ \ TickType\_t\ \mbox{\hyperlink{class_b_n_o08x_ab0c1b4ef4dbcc05a2a6cf37ee039ba0e}{host\_int\_timeout\_ms}}\ =} -\DoxyCodeLine{00558\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ae51d4e3228a91ee407d5866e604804c4}{HOST\_INT\_TIMEOUT\_DEFAULT\_MS}};\ } -\DoxyCodeLine{00559\ } -\DoxyCodeLine{00560\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ \textcolor{keywordtype}{char}*\ \mbox{\hyperlink{class_b_n_o08x_a2c98d5f2c406a3efd0b48c5666fa8c46}{TAG}}\ =\ \textcolor{stringliteral}{"{}BNO08x"{}};\ } -\DoxyCodeLine{00561\ } -\DoxyCodeLine{00562\ \ \ \ \ \ \ \ \ \textcolor{keyword}{friend}\ \textcolor{keyword}{class\ }\mbox{\hyperlink{class_b_n_o08x_test_helper}{BNO08xTestHelper}};\ \textcolor{comment}{//\ allow\ test\ helper\ to\ access\ private\ members\ for\ unit\ tests}} -\DoxyCodeLine{00563\ \};} - -\end{DoxyCode} diff --git a/documentation/latex/_b_n_o08x__global__types_8hpp.tex b/documentation/latex/_b_n_o08x__global__types_8hpp.tex deleted file mode 100644 index 2f0d76e..0000000 --- a/documentation/latex/_b_n_o08x__global__types_8hpp.tex +++ /dev/null @@ -1,328 +0,0 @@ -\doxysection{BNO08x\+\_\+global\+\_\+types.\+hpp File Reference} -\hypertarget{_b_n_o08x__global__types_8hpp}{}\label{_b_n_o08x__global__types_8hpp}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}} -{\ttfamily \#include $<$driver/gpio.\+h$>$}\newline -{\ttfamily \#include $<$driver/spi\+\_\+common.\+h$>$}\newline -{\ttfamily \#include $<$driver/spi\+\_\+master.\+h$>$}\newline -Include dependency graph for BNO08x\+\_\+global\+\_\+types.\+hpp\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_b_n_o08x__global__types_8hpp__incl} -\end{center} -\end{figure} -This graph shows which files directly or indirectly include this file\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_b_n_o08x__global__types_8hpp__dep__incl} -\end{center} -\end{figure} -\doxysubsubsection*{Classes} -\begin{DoxyCompactItemize} -\item -struct \mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}} -\begin{DoxyCompactList}\small\item\em IMU configuration settings passed into constructor. \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Typedefs} -\begin{DoxyCompactItemize} -\item -using \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a03fbbd71180a19088ce30d57ab050a22}{IMUAccuracy}} = \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} -\item -using \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aeee029e15be2a7d6d8134cabcc7c752b}{IMUReset\+Reason}} = \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147}{BNO08x\+Reset\+Reason}} -\item -typedef struct bno08x\+\_\+config\+\_\+t \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a648bbdbf22731476890dd8da977d7503}{bno08x\+\_\+config\+\_\+t}} -\begin{DoxyCompactList}\small\item\em IMU configuration settings passed into constructor. \end{DoxyCompactList}\item -typedef \mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}} \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aae502b3d91ddf903bba797646fd28d00}{imu\+\_\+config\+\_\+t}} -\end{DoxyCompactItemize} -\doxysubsubsection*{Enumerations} -\begin{DoxyCompactItemize} -\item -enum class \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \{ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88}{LOW}} = 1 -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c}{MED}} -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c}{HIGH}} -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}{UNDEFINED}} - \} -\begin{DoxyCompactList}\small\item\em Sensor accuracy returned during sensor calibration. \end{DoxyCompactList}\item -enum class \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147}{BNO08x\+Reset\+Reason}} \{ \newline -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a0db45d2a4141101bdfe48e3314cfbca3}{UNDEFINED}} -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92}{POR}} -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f}{INT\+\_\+\+RST}} -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36}{WTD}} -, \newline -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5}{EXT\+\_\+\+RST}} -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb}{OTHER}} - \} -\begin{DoxyCompactList}\small\item\em Reason for previous IMU reset (returned by get\+\_\+reset\+\_\+reason()) \end{DoxyCompactList}\item -enum class \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0f}{BNO08x\+Activity\+Enable}} \{ \newline -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3}{UNKNOWN}} = (1U \texorpdfstring{$<$}{<}\texorpdfstring{$<$}{<} 0U) -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4}{IN\+\_\+\+VEHICLE}} = (1U \texorpdfstring{$<$}{<}\texorpdfstring{$<$}{<} 1U) -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4}{ON\+\_\+\+BICYCLE}} = (1U \texorpdfstring{$<$}{<}\texorpdfstring{$<$}{<} 2U) -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58}{ON\+\_\+\+FOOT}} = (1U \texorpdfstring{$<$}{<}\texorpdfstring{$<$}{<} 3U) -, \newline -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6}{STILL}} = (1U \texorpdfstring{$<$}{<}\texorpdfstring{$<$}{<} 4U) -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c}{TILTING}} = (1U \texorpdfstring{$<$}{<}\texorpdfstring{$<$}{<} 5U) -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3}{WALKING}} = (1U \texorpdfstring{$<$}{<}\texorpdfstring{$<$}{<} 6U) -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd}{RUNNING}} = (1U \texorpdfstring{$<$}{<}\texorpdfstring{$<$}{<} 7U) -, \newline -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515}{ON\+\_\+\+STAIRS}} = (1U \texorpdfstring{$<$}{<}\texorpdfstring{$<$}{<} 8U) -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d}{ALL}} = 0x1\+FU - \} -\begin{DoxyCompactList}\small\item\em BNO08x\+Activity Classifier enable bits passed to enable\+\_\+activity\+\_\+classifier() \end{DoxyCompactList}\item -enum class \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}{BNO08x\+Activity}} \{ \newline -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3}{UNKNOWN}} = 0 -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4}{IN\+\_\+\+VEHICLE}} = 1 -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4}{ON\+\_\+\+BICYCLE}} = 2 -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58}{ON\+\_\+\+FOOT}} = 3 -, \newline -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6}{STILL}} = 4 -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c}{TILTING}} = 5 -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3}{WALKING}} = 6 -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd}{RUNNING}} = 7 -, \newline -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515}{ON\+\_\+\+STAIRS}} = 8 -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3}{UNDEFINED}} = 9 - \} -\begin{DoxyCompactList}\small\item\em BNO08x\+Activity states returned from get\+\_\+activity\+\_\+classifier() \end{DoxyCompactList}\item -enum class \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}{BNO08x\+Stability}} \{ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3}{UNKNOWN}} = 0 -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a}{ON\+\_\+\+TABLE}} = 1 -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146}{STATIONARY}} = 2 -, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3}{UNDEFINED}} = 3 - \} -\begin{DoxyCompactList}\small\item\em BNO08x\+Stability states returned from get\+\_\+stability\+\_\+classifier() \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -\begin{DoxyAuthor}{Author} -Myles Parfeniuk -\end{DoxyAuthor} - - -\doxysubsection{Typedef Documentation} -\Hypertarget{_b_n_o08x__global__types_8hpp_a648bbdbf22731476890dd8da977d7503}\label{_b_n_o08x__global__types_8hpp_a648bbdbf22731476890dd8da977d7503} -\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!bno08x\_config\_t@{bno08x\_config\_t}} -\index{bno08x\_config\_t@{bno08x\_config\_t}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}} -\doxysubsubsection{\texorpdfstring{bno08x\_config\_t}{bno08x\_config\_t}} -{\footnotesize\ttfamily typedef struct bno08x\+\_\+config\+\_\+t bno08x\+\_\+config\+\_\+t} - - - -IMU configuration settings passed into constructor. - -\Hypertarget{_b_n_o08x__global__types_8hpp_aae502b3d91ddf903bba797646fd28d00}\label{_b_n_o08x__global__types_8hpp_aae502b3d91ddf903bba797646fd28d00} -\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!imu\_config\_t@{imu\_config\_t}} -\index{imu\_config\_t@{imu\_config\_t}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}} -\doxysubsubsection{\texorpdfstring{imu\_config\_t}{imu\_config\_t}} -{\footnotesize\ttfamily typedef \mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}} \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aae502b3d91ddf903bba797646fd28d00}{imu\+\_\+config\+\_\+t}}} - -\Hypertarget{_b_n_o08x__global__types_8hpp_a03fbbd71180a19088ce30d57ab050a22}\label{_b_n_o08x__global__types_8hpp_a03fbbd71180a19088ce30d57ab050a22} -\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!IMUAccuracy@{IMUAccuracy}} -\index{IMUAccuracy@{IMUAccuracy}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}} -\doxysubsubsection{\texorpdfstring{IMUAccuracy}{IMUAccuracy}} -{\footnotesize\ttfamily using \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{IMUAccuracy}} = \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}}} - -\Hypertarget{_b_n_o08x__global__types_8hpp_aeee029e15be2a7d6d8134cabcc7c752b}\label{_b_n_o08x__global__types_8hpp_aeee029e15be2a7d6d8134cabcc7c752b} -\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!IMUResetReason@{IMUResetReason}} -\index{IMUResetReason@{IMUResetReason}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}} -\doxysubsubsection{\texorpdfstring{IMUResetReason}{IMUResetReason}} -{\footnotesize\ttfamily using \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147}{IMUReset\+Reason}} = \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147}{BNO08x\+Reset\+Reason}}} - - - -\doxysubsection{Enumeration Type Documentation} -\Hypertarget{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}\label{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0} -\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!BNO08xAccuracy@{BNO08xAccuracy}} -\index{BNO08xAccuracy@{BNO08xAccuracy}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}} -\doxysubsubsection{\texorpdfstring{BNO08xAccuracy}{BNO08xAccuracy}} -{\footnotesize\ttfamily enum class \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}}\hspace{0.3cm}{\ttfamily [strong]}} - - - -Sensor accuracy returned during sensor calibration. - -\begin{DoxyEnumFields}{Enumerator} -\raisebox{\heightof{T}}[0pt][0pt]{\index{LOW@{LOW}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!LOW@{LOW}}}\Hypertarget{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88}\label{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88} -LOW&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{MED@{MED}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!MED@{MED}}}\Hypertarget{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c}\label{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c} -MED&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{HIGH@{HIGH}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!HIGH@{HIGH}}}\Hypertarget{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c}\label{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c} -HIGH&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{UNDEFINED@{UNDEFINED}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!UNDEFINED@{UNDEFINED}}}\Hypertarget{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}\label{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3} -UNDEFINED&\\ -\hline - -\end{DoxyEnumFields} -\Hypertarget{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}\label{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187} -\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!BNO08xActivity@{BNO08xActivity}} -\index{BNO08xActivity@{BNO08xActivity}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}} -\doxysubsubsection{\texorpdfstring{BNO08xActivity}{BNO08xActivity}} -{\footnotesize\ttfamily enum class \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}{BNO08x\+Activity}}\hspace{0.3cm}{\ttfamily [strong]}} - - - -BNO08x\+Activity states returned from get\+\_\+activity\+\_\+classifier() - -\begin{DoxyEnumFields}{Enumerator} -\raisebox{\heightof{T}}[0pt][0pt]{\index{UNKNOWN@{UNKNOWN}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!UNKNOWN@{UNKNOWN}}}\Hypertarget{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3}\label{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3} -UNKNOWN&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{IN\_VEHICLE@{IN\_VEHICLE}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!IN\_VEHICLE@{IN\_VEHICLE}}}\Hypertarget{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4}\label{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4} -IN\+\_\+\+VEHICLE&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{ON\_BICYCLE@{ON\_BICYCLE}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!ON\_BICYCLE@{ON\_BICYCLE}}}\Hypertarget{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4}\label{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4} -ON\+\_\+\+BICYCLE&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{ON\_FOOT@{ON\_FOOT}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!ON\_FOOT@{ON\_FOOT}}}\Hypertarget{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58}\label{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58} -ON\+\_\+\+FOOT&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{STILL@{STILL}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!STILL@{STILL}}}\Hypertarget{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6}\label{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6} -STILL&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{TILTING@{TILTING}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!TILTING@{TILTING}}}\Hypertarget{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c}\label{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c} -TILTING&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{WALKING@{WALKING}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!WALKING@{WALKING}}}\Hypertarget{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3}\label{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3} -WALKING&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{RUNNING@{RUNNING}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!RUNNING@{RUNNING}}}\Hypertarget{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd}\label{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd} -RUNNING&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{ON\_STAIRS@{ON\_STAIRS}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!ON\_STAIRS@{ON\_STAIRS}}}\Hypertarget{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515}\label{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515} -ON\+\_\+\+STAIRS&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{UNDEFINED@{UNDEFINED}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!UNDEFINED@{UNDEFINED}}}\Hypertarget{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3}\label{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3} -UNDEFINED&\\ -\hline - -\end{DoxyEnumFields} -\Hypertarget{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0f}\label{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0f} -\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!BNO08xActivityEnable@{BNO08xActivityEnable}} -\index{BNO08xActivityEnable@{BNO08xActivityEnable}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}} -\doxysubsubsection{\texorpdfstring{BNO08xActivityEnable}{BNO08xActivityEnable}} -{\footnotesize\ttfamily enum class \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0f}{BNO08x\+Activity\+Enable}}\hspace{0.3cm}{\ttfamily [strong]}} - - - -BNO08x\+Activity Classifier enable bits passed to enable\+\_\+activity\+\_\+classifier() - -\begin{DoxyEnumFields}{Enumerator} -\raisebox{\heightof{T}}[0pt][0pt]{\index{UNKNOWN@{UNKNOWN}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!UNKNOWN@{UNKNOWN}}}\Hypertarget{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3}\label{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3} -UNKNOWN&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{IN\_VEHICLE@{IN\_VEHICLE}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!IN\_VEHICLE@{IN\_VEHICLE}}}\Hypertarget{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4}\label{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4} -IN\+\_\+\+VEHICLE&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{ON\_BICYCLE@{ON\_BICYCLE}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!ON\_BICYCLE@{ON\_BICYCLE}}}\Hypertarget{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4}\label{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4} -ON\+\_\+\+BICYCLE&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{ON\_FOOT@{ON\_FOOT}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!ON\_FOOT@{ON\_FOOT}}}\Hypertarget{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58}\label{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58} -ON\+\_\+\+FOOT&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{STILL@{STILL}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!STILL@{STILL}}}\Hypertarget{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6}\label{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6} -STILL&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{TILTING@{TILTING}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!TILTING@{TILTING}}}\Hypertarget{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c}\label{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c} -TILTING&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{WALKING@{WALKING}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!WALKING@{WALKING}}}\Hypertarget{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3}\label{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3} -WALKING&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{RUNNING@{RUNNING}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!RUNNING@{RUNNING}}}\Hypertarget{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd}\label{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd} -RUNNING&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{ON\_STAIRS@{ON\_STAIRS}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!ON\_STAIRS@{ON\_STAIRS}}}\Hypertarget{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515}\label{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515} -ON\+\_\+\+STAIRS&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{ALL@{ALL}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!ALL@{ALL}}}\Hypertarget{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d}\label{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d} -ALL&\\ -\hline - -\end{DoxyEnumFields} -\Hypertarget{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147}\label{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147} -\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!BNO08xResetReason@{BNO08xResetReason}} -\index{BNO08xResetReason@{BNO08xResetReason}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}} -\doxysubsubsection{\texorpdfstring{BNO08xResetReason}{BNO08xResetReason}} -{\footnotesize\ttfamily enum class \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147}{BNO08x\+Reset\+Reason}}\hspace{0.3cm}{\ttfamily [strong]}} - - - -Reason for previous IMU reset (returned by get\+\_\+reset\+\_\+reason()) - -\begin{DoxyEnumFields}{Enumerator} -\raisebox{\heightof{T}}[0pt][0pt]{\index{UNDEFINED@{UNDEFINED}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!UNDEFINED@{UNDEFINED}}}\Hypertarget{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a0db45d2a4141101bdfe48e3314cfbca3}\label{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a0db45d2a4141101bdfe48e3314cfbca3} -UNDEFINED&Undefined reset reason, this should never occur and is an error. \\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{POR@{POR}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!POR@{POR}}}\Hypertarget{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92}\label{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92} -POR&Previous reset was due to power on reset. \\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{INT\_RST@{INT\_RST}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!INT\_RST@{INT\_RST}}}\Hypertarget{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f}\label{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f} -INT\+\_\+\+RST&Previous reset was due to internal reset. \\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{WTD@{WTD}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!WTD@{WTD}}}\Hypertarget{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36}\label{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36} -WTD&Previous reset was due to watchdog timer. \\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{EXT\_RST@{EXT\_RST}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!EXT\_RST@{EXT\_RST}}}\Hypertarget{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5}\label{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5} -EXT\+\_\+\+RST&Previous reset was due to external reset. \\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{OTHER@{OTHER}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!OTHER@{OTHER}}}\Hypertarget{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb}\label{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb} -OTHER&Previous reset was due to power other reason. \\ -\hline - -\end{DoxyEnumFields} -\Hypertarget{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}\label{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5} -\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!BNO08xStability@{BNO08xStability}} -\index{BNO08xStability@{BNO08xStability}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}} -\doxysubsubsection{\texorpdfstring{BNO08xStability}{BNO08xStability}} -{\footnotesize\ttfamily enum class \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}{BNO08x\+Stability}}\hspace{0.3cm}{\ttfamily [strong]}} - - - -BNO08x\+Stability states returned from get\+\_\+stability\+\_\+classifier() - -\begin{DoxyEnumFields}{Enumerator} -\raisebox{\heightof{T}}[0pt][0pt]{\index{UNKNOWN@{UNKNOWN}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!UNKNOWN@{UNKNOWN}}}\Hypertarget{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3}\label{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3} -UNKNOWN&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{ON\_TABLE@{ON\_TABLE}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!ON\_TABLE@{ON\_TABLE}}}\Hypertarget{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a}\label{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a} -ON\+\_\+\+TABLE&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{STATIONARY@{STATIONARY}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!STATIONARY@{STATIONARY}}}\Hypertarget{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146}\label{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146} -STATIONARY&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{UNDEFINED@{UNDEFINED}!BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}!UNDEFINED@{UNDEFINED}}}\Hypertarget{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3}\label{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3} -UNDEFINED&\\ -\hline - -\end{DoxyEnumFields} diff --git a/documentation/latex/_b_n_o08x__global__types_8hpp__dep__incl.md5 b/documentation/latex/_b_n_o08x__global__types_8hpp__dep__incl.md5 deleted file mode 100644 index 0282822..0000000 --- a/documentation/latex/_b_n_o08x__global__types_8hpp__dep__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -9a4faacd0b3d1a2e9de63df2c0076800 \ No newline at end of file diff --git a/documentation/latex/_b_n_o08x__global__types_8hpp__dep__incl.pdf b/documentation/latex/_b_n_o08x__global__types_8hpp__dep__incl.pdf deleted file mode 100644 index e7e97ed..0000000 Binary files a/documentation/latex/_b_n_o08x__global__types_8hpp__dep__incl.pdf and /dev/null differ diff --git a/documentation/latex/_b_n_o08x__global__types_8hpp__incl.md5 b/documentation/latex/_b_n_o08x__global__types_8hpp__incl.md5 deleted file mode 100644 index b39c46a..0000000 --- a/documentation/latex/_b_n_o08x__global__types_8hpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -5fdaf3185e1c9040cdb8126d6b61288c \ No newline at end of file diff --git a/documentation/latex/_b_n_o08x__global__types_8hpp__incl.pdf b/documentation/latex/_b_n_o08x__global__types_8hpp__incl.pdf deleted file mode 100644 index 19bacf9..0000000 Binary files a/documentation/latex/_b_n_o08x__global__types_8hpp__incl.pdf and /dev/null differ diff --git a/documentation/latex/_b_n_o08x__global__types_8hpp_source.tex b/documentation/latex/_b_n_o08x__global__types_8hpp_source.tex deleted file mode 100644 index 7372140..0000000 --- a/documentation/latex/_b_n_o08x__global__types_8hpp_source.tex +++ /dev/null @@ -1,114 +0,0 @@ -\doxysection{BNO08x\+\_\+global\+\_\+types.\+hpp} -\hypertarget{_b_n_o08x__global__types_8hpp_source}{}\label{_b_n_o08x__global__types_8hpp_source}\index{BNO08x\_global\_types.hpp@{BNO08x\_global\_types.hpp}} -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp}{Go to the documentation of this file.}} -\begin{DoxyCode}{0} -\DoxyCodeLine{00001\ } -\DoxyCodeLine{00005\ \textcolor{preprocessor}{\#pragma\ once}} -\DoxyCodeLine{00006\ } -\DoxyCodeLine{00007\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00008\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00009\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00010\ } -\DoxyCodeLine{00012\ \textcolor{keyword}{enum\ class}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}} -\DoxyCodeLine{00013\ \{} -\DoxyCodeLine{00014\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88}{LOW}}\ =\ 1,} -\DoxyCodeLine{00015\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c}{MED}},} -\DoxyCodeLine{00016\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c}{HIGH}},} -\DoxyCodeLine{00017\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}{UNDEFINED}}} -\DoxyCodeLine{00018\ \};} -\DoxyCodeLine{00019\ \textcolor{keyword}{using\ }\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{IMUAccuracy}}\ =\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}};\ \textcolor{comment}{//\ legacy\ version\ compatibility}} -\DoxyCodeLine{00020\ } -\DoxyCodeLine{00022\ \textcolor{keyword}{enum\ class}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147}{BNO08xResetReason}}} -\DoxyCodeLine{00023\ \{} -\DoxyCodeLine{00024\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}{UNDEFINED}},\ } -\DoxyCodeLine{00025\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92}{POR}},\ \ \ \ \ \ \ } -\DoxyCodeLine{00026\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f}{INT\_RST}},\ \ \ } -\DoxyCodeLine{00027\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36}{WTD}},\ \ \ \ \ \ \ } -\DoxyCodeLine{00028\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5}{EXT\_RST}},\ \ \ } -\DoxyCodeLine{00029\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb}{OTHER}}\ \ \ \ \ \ } -\DoxyCodeLine{00030\ \};} -\DoxyCodeLine{00031\ \textcolor{keyword}{using\ }\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147}{IMUResetReason}}\ =\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147}{BNO08xResetReason}};\ \textcolor{comment}{//\ legacy\ version\ compatibility}} -\DoxyCodeLine{00032\ } -\DoxyCodeLine{00034\ \textcolor{keyword}{enum\ class}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0f}{BNO08xActivityEnable}}} -\DoxyCodeLine{00035\ \{} -\DoxyCodeLine{00036\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3}{UNKNOWN}}\ =\ (1U\ <<\ 0U),} -\DoxyCodeLine{00037\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4}{IN\_VEHICLE}}\ =\ (1U\ <<\ 1U),} -\DoxyCodeLine{00038\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4}{ON\_BICYCLE}}\ =\ (1U\ <<\ 2U),} -\DoxyCodeLine{00039\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58}{ON\_FOOT}}\ =\ (1U\ <<\ 3U),} -\DoxyCodeLine{00040\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6}{STILL}}\ =\ (1U\ <<\ 4U),} -\DoxyCodeLine{00041\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c}{TILTING}}\ =\ (1U\ <<\ 5U),} -\DoxyCodeLine{00042\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3}{WALKING}}\ =\ (1U\ <<\ 6U),} -\DoxyCodeLine{00043\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd}{RUNNING}}\ =\ (1U\ <<\ 7U),} -\DoxyCodeLine{00044\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515}{ON\_STAIRS}}\ =\ (1U\ <<\ 8U),} -\DoxyCodeLine{00045\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d}{ALL}}\ =\ 0x1FU} -\DoxyCodeLine{00046\ \};} -\DoxyCodeLine{00047\ } -\DoxyCodeLine{00049\ \textcolor{keyword}{enum\ class}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}{BNO08xActivity}}} -\DoxyCodeLine{00050\ \{} -\DoxyCodeLine{00051\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3}{UNKNOWN}}\ =\ 0,\ \ \ \ \textcolor{comment}{//\ 0\ =\ unknown}} -\DoxyCodeLine{00052\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4}{IN\_VEHICLE}}\ =\ 1,\ \textcolor{comment}{//\ 1\ =\ in\ vehicle}} -\DoxyCodeLine{00053\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4}{ON\_BICYCLE}}\ =\ 2,\ \textcolor{comment}{//\ 2\ =\ on\ bicycle}} -\DoxyCodeLine{00054\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58}{ON\_FOOT}}\ =\ 3,\ \ \ \ \textcolor{comment}{//\ 3\ =\ on\ foot}} -\DoxyCodeLine{00055\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6}{STILL}}\ =\ 4,\ \ \ \ \ \ \textcolor{comment}{//\ 4\ =\ still}} -\DoxyCodeLine{00056\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c}{TILTING}}\ =\ 5,\ \ \ \ \textcolor{comment}{//\ 5\ =\ tilting}} -\DoxyCodeLine{00057\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3}{WALKING}}\ =\ 6,\ \ \ \ \textcolor{comment}{//\ 6\ =\ walking}} -\DoxyCodeLine{00058\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd}{RUNNING}}\ =\ 7,\ \ \ \ \textcolor{comment}{//\ 7\ =\ running}} -\DoxyCodeLine{00059\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515}{ON\_STAIRS}}\ =\ 8,\ \ \textcolor{comment}{//\ 8\ =\ on\ stairs}} -\DoxyCodeLine{00060\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}{UNDEFINED}}\ =\ 9\ \ \ \textcolor{comment}{//\ used\ for\ unit\ tests}} -\DoxyCodeLine{00061\ \};} -\DoxyCodeLine{00062\ } -\DoxyCodeLine{00064\ \textcolor{keyword}{enum\ class}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}{BNO08xStability}}} -\DoxyCodeLine{00065\ \{} -\DoxyCodeLine{00066\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3}{UNKNOWN}}\ =\ 0,\ \ \ \ \textcolor{comment}{//\ 0\ =\ unknown}} -\DoxyCodeLine{00067\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a}{ON\_TABLE}}\ =\ 1,\ \ \ \textcolor{comment}{//\ 1\ =\ on\ table}} -\DoxyCodeLine{00068\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146}{STATIONARY}}\ =\ 2,\ \textcolor{comment}{//\ 2\ =\ stationary}} -\DoxyCodeLine{00069\ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}{UNDEFINED}}\ =\ 3\ \ \ \textcolor{comment}{//\ used\ for\ unit\ tests}} -\DoxyCodeLine{00070\ \};} -\DoxyCodeLine{00071\ } -\DoxyCodeLine{00073\ \textcolor{keyword}{typedef}\ \textcolor{keyword}{struct\ }\mbox{\hyperlink{structbno08x__config__t}{bno08x\_config\_t}}} -\DoxyCodeLine{00074\ \{} -\DoxyCodeLine{00075\ \ \ \ \ \ \ \ \ spi\_host\_device\_t\ \mbox{\hyperlink{structbno08x__config__t_a020d2343750bb7debc2a108ae038c9ec}{spi\_peripheral}};\ } -\DoxyCodeLine{00076\ \ \ \ \ \ \ \ \ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_a79023fd80039e41a22b7f73ccd5fc861}{io\_mosi}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00077\ \ \ \ \ \ \ \ \ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_a9468180a773892977db39cc5ed9368e3}{io\_miso}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00078\ \ \ \ \ \ \ \ \ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_a639685b91ae3198909d722316495246a}{io\_sclk}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00079\ \ \ \ \ \ \ \ \ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_ab1b5351b63da0c172c942463d0dc2505}{io\_cs}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00080\ \ \ \ \ \ \ \ \ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_a3cfe965659cfbc6b0c5269bd0211975f}{io\_int}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00081\ \ \ \ \ \ \ \ \ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_a62745c761219139f66ecd173b51577fc}{io\_rst}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00082\ \ \ \ \ \ \ \ \ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_a90ad7f316dc443874d19dc7e723a0ce0}{io\_wake}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00083\ \ \ \ \ \ \ \ \ uint32\_t\ \mbox{\hyperlink{structbno08x__config__t_a231614c3b20888360def2ce9db83f52a}{sclk\_speed}};\ \ \ \ \ \ \ \ \ \ \ \ \ \ } -\DoxyCodeLine{00084\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{structbno08x__config__t_a0f629aaef6756aa80fec96b34476c627}{install\_isr\_service}};\ } -\DoxyCodeLine{00085\ } -\DoxyCodeLine{00089\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{structbno08x__config__t_a68e051212415a62e64c23678e7b40552}{bno08x\_config\_t}}(\textcolor{keywordtype}{bool}\ \mbox{\hyperlink{structbno08x__config__t_a0f629aaef6756aa80fec96b34476c627}{install\_isr\_service}}\ =\ \textcolor{keyword}{true})} -\DoxyCodeLine{00090\ \ \ \ \ \ \ \ \ \ \ \ \ :\ \mbox{\hyperlink{structbno08x__config__t_a020d2343750bb7debc2a108ae038c9ec}{spi\_peripheral}}((spi\_host\_device\_t)\ CONFIG\_ESP32\_BNO08x\_SPI\_HOST)} -\DoxyCodeLine{00091\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a79023fd80039e41a22b7f73ccd5fc861}{io\_mosi}}(static\_cast(CONFIG\_ESP32\_BNO08X\_GPIO\_DI))\ \ \ \ \ \ \ \textcolor{comment}{//\ default:\ 23}} -\DoxyCodeLine{00092\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a9468180a773892977db39cc5ed9368e3}{io\_miso}}(static\_cast(CONFIG\_ESP32\_BNO08X\_GPIO\_SDA))\ \ \ \ \ \ \textcolor{comment}{//\ default:\ 19}} -\DoxyCodeLine{00093\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a639685b91ae3198909d722316495246a}{io\_sclk}}(static\_cast(CONFIG\_ESP32\_BNO08X\_GPIO\_SCL))\ \ \ \ \ \ \textcolor{comment}{//\ default:\ 18}} -\DoxyCodeLine{00094\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_ab1b5351b63da0c172c942463d0dc2505}{io\_cs}}(static\_cast(CONFIG\_ESP32\_BNO08X\_GPIO\_CS))\ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ default:\ 33}} -\DoxyCodeLine{00095\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a3cfe965659cfbc6b0c5269bd0211975f}{io\_int}}(static\_cast(CONFIG\_ESP32\_BNO08X\_GPIO\_HINT))\ \ \ \ \ \ \textcolor{comment}{//\ default:\ 26}} -\DoxyCodeLine{00096\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a62745c761219139f66ecd173b51577fc}{io\_rst}}(static\_cast(CONFIG\_ESP32\_BNO08X\_GPIO\_RST))\ \ \ \ \ \ \ \textcolor{comment}{//\ default:\ 32}} -\DoxyCodeLine{00097\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a90ad7f316dc443874d19dc7e723a0ce0}{io\_wake}}(static\_cast(CONFIG\_ESP32\_BNO08X\_GPIO\_WAKE))\ \ \ \ \ \textcolor{comment}{//\ default:\ -\/1\ (unused)}} -\DoxyCodeLine{00098\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a231614c3b20888360def2ce9db83f52a}{sclk\_speed}}(static\_cast(CONFIG\_ESP32\_BNO08X\_SCL\_SPEED\_HZ))\ \textcolor{comment}{//\ default:\ 2MHz}} -\DoxyCodeLine{00099\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a0f629aaef6756aa80fec96b34476c627}{install\_isr\_service}}(\mbox{\hyperlink{structbno08x__config__t_a0f629aaef6756aa80fec96b34476c627}{install\_isr\_service}})\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ default:\ true}} -\DoxyCodeLine{00100\ } -\DoxyCodeLine{00101\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00102\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00103\ } -\DoxyCodeLine{00105\ \ \ \ \ \ \ \ \ \mbox{\hyperlink{structbno08x__config__t_a3a4ef8ef437403592278110a73cafe70}{bno08x\_config\_t}}(spi\_host\_device\_t\ \mbox{\hyperlink{structbno08x__config__t_a020d2343750bb7debc2a108ae038c9ec}{spi\_peripheral}},\ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_a79023fd80039e41a22b7f73ccd5fc861}{io\_mosi}},\ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_a9468180a773892977db39cc5ed9368e3}{io\_miso}},\ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_a639685b91ae3198909d722316495246a}{io\_sclk}},\ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_ab1b5351b63da0c172c942463d0dc2505}{io\_cs}},} -\DoxyCodeLine{00106\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_a3cfe965659cfbc6b0c5269bd0211975f}{io\_int}},\ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_a62745c761219139f66ecd173b51577fc}{io\_rst}},\ gpio\_num\_t\ \mbox{\hyperlink{structbno08x__config__t_a90ad7f316dc443874d19dc7e723a0ce0}{io\_wake}},\ uint32\_t\ \mbox{\hyperlink{structbno08x__config__t_a231614c3b20888360def2ce9db83f52a}{sclk\_speed}},\ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{structbno08x__config__t_a0f629aaef6756aa80fec96b34476c627}{install\_isr\_service}}\ =\ \textcolor{keyword}{true})} -\DoxyCodeLine{00107\ \ \ \ \ \ \ \ \ \ \ \ \ :\ \mbox{\hyperlink{structbno08x__config__t_a020d2343750bb7debc2a108ae038c9ec}{spi\_peripheral}}(\mbox{\hyperlink{structbno08x__config__t_a020d2343750bb7debc2a108ae038c9ec}{spi\_peripheral}})} -\DoxyCodeLine{00108\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a79023fd80039e41a22b7f73ccd5fc861}{io\_mosi}}(\mbox{\hyperlink{structbno08x__config__t_a79023fd80039e41a22b7f73ccd5fc861}{io\_mosi}})} -\DoxyCodeLine{00109\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a9468180a773892977db39cc5ed9368e3}{io\_miso}}(\mbox{\hyperlink{structbno08x__config__t_a9468180a773892977db39cc5ed9368e3}{io\_miso}})} -\DoxyCodeLine{00110\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a639685b91ae3198909d722316495246a}{io\_sclk}}(\mbox{\hyperlink{structbno08x__config__t_a639685b91ae3198909d722316495246a}{io\_sclk}})} -\DoxyCodeLine{00111\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_ab1b5351b63da0c172c942463d0dc2505}{io\_cs}}(\mbox{\hyperlink{structbno08x__config__t_ab1b5351b63da0c172c942463d0dc2505}{io\_cs}})} -\DoxyCodeLine{00112\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a3cfe965659cfbc6b0c5269bd0211975f}{io\_int}}(\mbox{\hyperlink{structbno08x__config__t_a3cfe965659cfbc6b0c5269bd0211975f}{io\_int}})} -\DoxyCodeLine{00113\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a62745c761219139f66ecd173b51577fc}{io\_rst}}(\mbox{\hyperlink{structbno08x__config__t_a62745c761219139f66ecd173b51577fc}{io\_rst}})} -\DoxyCodeLine{00114\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a90ad7f316dc443874d19dc7e723a0ce0}{io\_wake}}(\mbox{\hyperlink{structbno08x__config__t_a90ad7f316dc443874d19dc7e723a0ce0}{io\_wake}})} -\DoxyCodeLine{00115\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a231614c3b20888360def2ce9db83f52a}{sclk\_speed}}(\mbox{\hyperlink{structbno08x__config__t_a231614c3b20888360def2ce9db83f52a}{sclk\_speed}})} -\DoxyCodeLine{00116\ \ \ \ \ \ \ \ \ \ \ \ \ ,\ \mbox{\hyperlink{structbno08x__config__t_a0f629aaef6756aa80fec96b34476c627}{install\_isr\_service}}(\mbox{\hyperlink{structbno08x__config__t_a0f629aaef6756aa80fec96b34476c627}{install\_isr\_service}})} -\DoxyCodeLine{00117\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00118\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00119\ \}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a648bbdbf22731476890dd8da977d7503}{bno08x\_config\_t}};} -\DoxyCodeLine{00120\ } -\DoxyCodeLine{00121\ \textcolor{keyword}{typedef}\ \mbox{\hyperlink{structbno08x__config__t}{bno08x\_config\_t}}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aae502b3d91ddf903bba797646fd28d00}{imu\_config\_t}};\ \textcolor{comment}{//\ legacy\ version\ compatibility}} - -\end{DoxyCode} diff --git a/documentation/latex/_b_n_o08x__macros_8hpp.tex b/documentation/latex/_b_n_o08x__macros_8hpp.tex deleted file mode 100644 index e8f4be8..0000000 --- a/documentation/latex/_b_n_o08x__macros_8hpp.tex +++ /dev/null @@ -1,738 +0,0 @@ -\doxysection{BNO08x\+\_\+macros.\+hpp File Reference} -\hypertarget{_b_n_o08x__macros_8hpp}{}\label{_b_n_o08x__macros_8hpp}\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -{\ttfamily \#include $<$inttypes.\+h$>$}\newline -{\ttfamily \#include $<$freertos/\+Free\+RTOS.\+h$>$}\newline -{\ttfamily \#include $<$freertos/event\+\_\+groups.\+h$>$}\newline -Include dependency graph for BNO08x\+\_\+macros.\+hpp\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_b_n_o08x__macros_8hpp__incl} -\end{center} -\end{figure} -This graph shows which files directly or indirectly include this file\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=189pt]{_b_n_o08x__macros_8hpp__dep__incl} -\end{center} -\end{figure} -\doxysubsubsection*{Macros} -\begin{DoxyCompactItemize} -\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a59dd17f0673fdd60f6a65bba104a6f80}{CHECK\+\_\+\+TASKS\+\_\+\+RUNNING}}(evt\+\_\+grp\+\_\+task\+\_\+flow, running\+\_\+bit)~((x\+Event\+Group\+Get\+Bits(evt\+\_\+grp\+\_\+task\+\_\+flow) \& (running\+\_\+bit)) != 0) -\begin{DoxyCompactList}\small\item\em Clears the most significant byte of a 16-\/bit value. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(val\+\_\+16bit)~((val\+\_\+16bit) \& 0x00\+FFU) -\begin{DoxyCompactList}\small\item\em Clears the most significant byte of a 16-\/bit value. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(val\+\_\+16bit)~((val\+\_\+16bit) \& 0x\+FF00U) -\begin{DoxyCompactList}\small\item\em Clears the least significant byte of a 16-\/bit value. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a7de5c0b84ba545981105e1216925d8e9}{UINT32\+\_\+\+CLR\+\_\+\+BYTE}}(val\+\_\+32bit, byte2clear)~((val\+\_\+32bit) \& \texorpdfstring{$\sim$}{\string~}(0x\+FFUL $<$$<$ (byte2clear \texorpdfstring{$\ast$}{*} 8UL))) -\begin{DoxyCompactList}\small\item\em Clears a specified byte in a 32-\/bit value. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(val\+\_\+32bit, byte2mask)~((val\+\_\+32bit) \& (0x\+FFUL $<$$<$ (byte2mask \texorpdfstring{$\ast$}{*} 8UL))) -\begin{DoxyCompactList}\small\item\em Masks a specified byte in a 32-\/bit value. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a432e15325e64ab36d5a3b30b65a71bf1}{PARSE\+\_\+\+PACKET\+\_\+\+LENGTH}}(packet\+\_\+ptr)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet\+\_\+ptr-\/$>$header\mbox{[}1\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet\+\_\+ptr-\/$>$header\mbox{[}0\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse length from SHTP packet header. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_afa3b6d75bbe499250e69043547a39208}{PARSE\+\_\+\+PACKET\+\_\+\+TIMESTAMP}}(packet\+\_\+ptr) -\begin{DoxyCompactList}\small\item\em Parse timestamp from SHTP packet. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a4c1a6f80fc6ab0ab5d6f803bc175b3e1}{PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+RESET\+\_\+\+REASON}}(packet\+\_\+ptr)~\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(static\+\_\+cast$<$uint32\+\_\+t$>$(packet\+\_\+ptr-\/$>$body\mbox{[}1\mbox{]}), 0\+UL) -\begin{DoxyCompactList}\small\item\em Parse reset reason from SHTP packet containing product ID report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a5e6be52a05421d50c4b3600c35868540}{PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+SW\+\_\+\+PART\+\_\+\+NO}}(packet\+\_\+ptr) -\begin{DoxyCompactList}\small\item\em Parse sw part number from SHTP packet containing product ID report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a24ff2498d4883f329d70fb2a6f10e04a}{PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+SW\+\_\+\+BUILD\+\_\+\+NO}}(packet\+\_\+ptr) -\begin{DoxyCompactList}\small\item\em Parse sw build number from SHTP packet containing product ID report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a23baa3c8a71f3b3021f135bef27a8ed9}{PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+SW\+\_\+\+VERSION\+\_\+\+PATCH}}(packet\+\_\+ptr)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(static\+\_\+cast$<$uint32\+\_\+t$>$(packet-\/$>$body\mbox{[}13\mbox{]}) $<$$<$ 8UL, 1UL) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(static\+\_\+cast$<$uint32\+\_\+t$>$(packet-\/$>$body\mbox{[}12\mbox{]}), 0\+UL)) -\begin{DoxyCompactList}\small\item\em Parse sw version patch from SHTP packet containing product ID report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a37c86278c2de384fe3b9304b8d2d3370}{PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+PRODUCT\+\_\+\+ID}}(packet\+\_\+ptr)~\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(static\+\_\+cast$<$uint32\+\_\+t$>$(packet-\/$>$body\mbox{[}0\mbox{]}), 0\+UL) -\begin{DoxyCompactList}\small\item\em Parse product ID SHTP packet containing product ID report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_af59b362a169fe8c11a0b679ca99383ee}{PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+SW\+\_\+\+VERSION\+\_\+\+MAJOR}}(packet\+\_\+ptr)~\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(static\+\_\+cast$<$uint32\+\_\+t$>$(packet-\/$>$body\mbox{[}2\mbox{]}), 0\+UL) -\begin{DoxyCompactList}\small\item\em Parse product sw version major containing product ID report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad9773ac824ab751df0e331a7c16080a1}{PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+SW\+\_\+\+VERSION\+\_\+\+MINOR}}(packet\+\_\+ptr)~\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(static\+\_\+cast$<$uint32\+\_\+t$>$(packet-\/$>$body\mbox{[}3\mbox{]}), 0\+UL) -\begin{DoxyCompactList}\small\item\em Parse product sw version minor containing product ID report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a1f20ab3d051d5acb254e5a5e7b4505de}{PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+QUAT\+\_\+I}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}1\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}0\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse quat I data from integrated gyro rotation vector report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_afe721365113756a8b38a5db255f9d061}{PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+QUAT\+\_\+J}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}3\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}2\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse quat J data from integrated gyro rotation vector report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a3ae7fd4e8febc54026e59e1ac544db84}{PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+QUAT\+\_\+K}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}4\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse quat K data from integrated gyro rotation vector report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a73d50f6a746370f614161ee6b9b08424}{PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+QUAT\+\_\+\+REAL}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}7\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}6\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse quat real data from integrated gyro rotation vector report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a7aed5272074b2ee03da81b6fb7222813}{PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+GYRO\+\_\+\+VEL\+\_\+X}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}9\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}8\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse x axis velocity data from integrated gyro rotation vector report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a823d8c92faf40d07f5b0bb324f2a51bd}{PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+GYRO\+\_\+\+VEL\+\_\+Y}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}11\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}10\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse y axis velocity data from integrated gyro rotation vector report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_afcc41ef70ba1860c3178072e13ccf512}{PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+GYRO\+\_\+\+VEL\+\_\+Z}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}13\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}12\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse z axis velocity data from integrated gyro rotation vector report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac4cad93c425c38fd5cd90d0982897611}{PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+STATUS\+\_\+\+BITS}}(packet)~(packet-\/$>$body\mbox{[}5 + 2\mbox{]} \& 0x03U) -\begin{DoxyCompactList}\small\item\em Parse status bits from input report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a5be1d9a953a0657a4b8df88681b211bc}{PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+REPORT\+\_\+\+ID}}(packet)~\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5\mbox{]})) -\begin{DoxyCompactList}\small\item\em Parse report ID from input report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a4664b5298e0059c173f71bb73a87d239}{PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+DATA\+\_\+1}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 5\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 4\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse first data block from input report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a455a8649345748be2d5f35036052f78a}{PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+DATA\+\_\+2}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 7\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 6\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse second data block from input report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a7d38fbfe154c526c822748fc812e7d52}{PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+DATA\+\_\+3}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 9\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 8\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse third data block from input report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a3d6971a39ce4858314247bdbbb754b33}{PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+DATA\+\_\+4}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 11\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 10\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse fourth data block from input report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_afd61b5f28723a3f20874097b1bd46e1a}{PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+DATA\+\_\+5}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 13\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 12\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse fifth data block from input report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ae66870a6ac704d1ee582f4f7bd2ba6a7}{PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+DATA\+\_\+6}}(packet)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 15\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 14\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse sixth data block from input report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a84602d112b6000375ad608904de5b0e3}{IS\+\_\+\+ROTATION\+\_\+\+VECTOR\+\_\+\+REPORT}}(packet) -\begin{DoxyCompactList}\small\item\em Checks if packet containing input report is a rotation vector report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_aa23c7c4d9748ce5551fcc0e5734e0a40}{PARSE\+\_\+\+FRS\+\_\+\+READ\+\_\+\+RESPONSE\+\_\+\+REPORT\+\_\+\+RECORD\+\_\+\+ID}}(packet\+\_\+body)~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet\+\_\+body\mbox{[}13\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet\+\_\+body\mbox{[}12\mbox{]}))) -\begin{DoxyCompactList}\small\item\em Parse FRS record ID from FRS read response report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac70cde2db98355de4f0e56c8650556fe}{PARSE\+\_\+\+FRS\+\_\+\+READ\+\_\+\+RESPONSE\+\_\+\+REPORT\+\_\+\+DATA\+\_\+1}}(packet\+\_\+body) -\begin{DoxyCompactList}\small\item\em Parse data block 1 from FRS read response report. \end{DoxyCompactList}\item -\#define \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a2fcd254e9531069d6982795f575cb17a}{PARSE\+\_\+\+FRS\+\_\+\+READ\+\_\+\+RESPONSE\+\_\+\+REPORT\+\_\+\+DATA\+\_\+2}}(packet\+\_\+body) -\begin{DoxyCompactList}\small\item\em Parse data block 2 from FRS read response report. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -\begin{DoxyAuthor}{Author} -Myles Parfeniuk -\end{DoxyAuthor} - - -\doxysubsection{Macro Definition Documentation} -\Hypertarget{_b_n_o08x__macros_8hpp_a59dd17f0673fdd60f6a65bba104a6f80}\label{_b_n_o08x__macros_8hpp_a59dd17f0673fdd60f6a65bba104a6f80} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!CHECK\_TASKS\_RUNNING@{CHECK\_TASKS\_RUNNING}} -\index{CHECK\_TASKS\_RUNNING@{CHECK\_TASKS\_RUNNING}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{CHECK\_TASKS\_RUNNING}{CHECK\_TASKS\_RUNNING}} -{\footnotesize\ttfamily \#define CHECK\+\_\+\+TASKS\+\_\+\+RUNNING(\begin{DoxyParamCaption}\item[{}]{evt\+\_\+grp\+\_\+task\+\_\+flow, }\item[{}]{running\+\_\+bit }\end{DoxyParamCaption})~((x\+Event\+Group\+Get\+Bits(evt\+\_\+grp\+\_\+task\+\_\+flow) \& (running\+\_\+bit)) != 0)} - - - -Clears the most significant byte of a 16-\/bit value. - - -\begin{DoxyParams}{Parameters} -{\em evt\+\_\+grp\+\_\+task\+\_\+flow} & Task flow event group handle. \\ -\hline -{\em running\+\_\+bit} & EVT\+\_\+\+GRP\+\_\+\+TSK\+\_\+\+FLW\+\_\+\+RUNNING\+\_\+\+BIT\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The value with the MSB cleared. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a84602d112b6000375ad608904de5b0e3}\label{_b_n_o08x__macros_8hpp_a84602d112b6000375ad608904de5b0e3} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!IS\_ROTATION\_VECTOR\_REPORT@{IS\_ROTATION\_VECTOR\_REPORT}} -\index{IS\_ROTATION\_VECTOR\_REPORT@{IS\_ROTATION\_VECTOR\_REPORT}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{IS\_ROTATION\_VECTOR\_REPORT}{IS\_ROTATION\_VECTOR\_REPORT}} -{\footnotesize\ttfamily \#define IS\+\_\+\+ROTATION\+\_\+\+VECTOR\+\_\+\+REPORT(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})} - -{\bfseries Value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{\ \ \ \ ((packet)-\/>body[5]\ ==\ SENSOR\_REPORT\_ID\_ROTATION\_VECTOR\ ||\ (packet)-\/>body[5]\ ==\ SENSOR\_REPORT\_ID\_GAME\_ROTATION\_VECTOR\ ||\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ (packet)-\/>body[5]\ ==\ SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_ROTATION\_VECTOR\ ||\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ (packet)-\/>body[5]\ ==\ SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR)} - -\end{DoxyCode} - - -Checks if packet containing input report is a rotation vector report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if contained input report is rotation vector report. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_ac70cde2db98355de4f0e56c8650556fe}\label{_b_n_o08x__macros_8hpp_ac70cde2db98355de4f0e56c8650556fe} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_1@{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_1}} -\index{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_1@{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_1}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_1}{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_1}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+FRS\+\_\+\+READ\+\_\+\+RESPONSE\+\_\+\+REPORT\+\_\+\+DATA\+\_\+1(\begin{DoxyParamCaption}\item[{}]{packet\+\_\+body }\end{DoxyParamCaption})} - -{\bfseries Value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{\ \ \ \ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet\_body[7])\ <<\ 24UL,\ 3UL)\ |\ \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet\_body[6])\ <<\ 16UL,\ 2UL)\ |\ \ \ \ \ \(\backslash\)} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet\_body[5])\ <<\ 8UL,\ 1UL)\ |\ \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet\_body[4]),\ 0UL))} - -\end{DoxyCode} - - -Parse data block 1 from FRS read response report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -FRS read response data block 1. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a2fcd254e9531069d6982795f575cb17a}\label{_b_n_o08x__macros_8hpp_a2fcd254e9531069d6982795f575cb17a} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_2@{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_2}} -\index{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_2@{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_2}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_2}{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_2}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+FRS\+\_\+\+READ\+\_\+\+RESPONSE\+\_\+\+REPORT\+\_\+\+DATA\+\_\+2(\begin{DoxyParamCaption}\item[{}]{packet\+\_\+body }\end{DoxyParamCaption})} - -{\bfseries Value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{\ \ \ \ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet\_body[11])\ <<\ 24UL,\ 3UL)\ |\ \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet\_body[10])\ <<\ 16UL,\ 2UL)\ |\ \ \ \(\backslash\)} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet\_body[9])\ <<\ 8UL,\ 1UL)\ |\ \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet\_body[8]),\ 0UL))} - -\end{DoxyCode} - - -Parse data block 2 from FRS read response report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -FRS read response data block 2. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_aa23c7c4d9748ce5551fcc0e5734e0a40}\label{_b_n_o08x__macros_8hpp_aa23c7c4d9748ce5551fcc0e5734e0a40} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_FRS\_READ\_RESPONSE\_REPORT\_RECORD\_ID@{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_RECORD\_ID}} -\index{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_RECORD\_ID@{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_RECORD\_ID}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_RECORD\_ID}{PARSE\_FRS\_READ\_RESPONSE\_REPORT\_RECORD\_ID}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+FRS\+\_\+\+READ\+\_\+\+RESPONSE\+\_\+\+REPORT\+\_\+\+RECORD\+\_\+\+ID(\begin{DoxyParamCaption}\item[{}]{packet\+\_\+body }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet\+\_\+body\mbox{[}13\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet\+\_\+body\mbox{[}12\mbox{]})))} - - - -Parse FRS record ID from FRS read response report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -FRS record ID. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a7aed5272074b2ee03da81b6fb7222813}\label{_b_n_o08x__macros_8hpp_a7aed5272074b2ee03da81b6fb7222813} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_X@{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_X}} -\index{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_X@{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_X}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_X}{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_X}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+GYRO\+\_\+\+VEL\+\_\+X(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}9\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}8\mbox{]})))} - - - -Parse x axis velocity data from integrated gyro rotation vector report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -x velocity data. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a823d8c92faf40d07f5b0bb324f2a51bd}\label{_b_n_o08x__macros_8hpp_a823d8c92faf40d07f5b0bb324f2a51bd} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Y@{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Y}} -\index{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Y@{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Y}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Y}{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Y}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+GYRO\+\_\+\+VEL\+\_\+Y(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}11\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}10\mbox{]})))} - - - -Parse y axis velocity data from integrated gyro rotation vector report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -y velocity data. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_afcc41ef70ba1860c3178072e13ccf512}\label{_b_n_o08x__macros_8hpp_afcc41ef70ba1860c3178072e13ccf512} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Z@{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Z}} -\index{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Z@{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Z}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Z}{PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Z}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+GYRO\+\_\+\+VEL\+\_\+Z(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}13\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}12\mbox{]})))} - - - -Parse z axis velocity data from integrated gyro rotation vector report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -z velocity data. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a1f20ab3d051d5acb254e5a5e7b4505de}\label{_b_n_o08x__macros_8hpp_a1f20ab3d051d5acb254e5a5e7b4505de} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_GYRO\_REPORT\_RAW\_QUAT\_I@{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_I}} -\index{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_I@{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_I}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_I}{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_I}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+QUAT\+\_\+I(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}1\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}0\mbox{]})))} - - - -Parse quat I data from integrated gyro rotation vector report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Quat I data. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_afe721365113756a8b38a5db255f9d061}\label{_b_n_o08x__macros_8hpp_afe721365113756a8b38a5db255f9d061} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_GYRO\_REPORT\_RAW\_QUAT\_J@{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_J}} -\index{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_J@{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_J}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_J}{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_J}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+QUAT\+\_\+J(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}3\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}2\mbox{]})))} - - - -Parse quat J data from integrated gyro rotation vector report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Quat J data. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a3ae7fd4e8febc54026e59e1ac544db84}\label{_b_n_o08x__macros_8hpp_a3ae7fd4e8febc54026e59e1ac544db84} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_GYRO\_REPORT\_RAW\_QUAT\_K@{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_K}} -\index{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_K@{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_K}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_K}{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_K}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+QUAT\+\_\+K(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}4\mbox{]})))} - - - -Parse quat K data from integrated gyro rotation vector report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Quat K data. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a73d50f6a746370f614161ee6b9b08424}\label{_b_n_o08x__macros_8hpp_a73d50f6a746370f614161ee6b9b08424} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_GYRO\_REPORT\_RAW\_QUAT\_REAL@{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_REAL}} -\index{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_REAL@{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_REAL}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_REAL}{PARSE\_GYRO\_REPORT\_RAW\_QUAT\_REAL}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+GYRO\+\_\+\+REPORT\+\_\+\+RAW\+\_\+\+QUAT\+\_\+\+REAL(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}7\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}6\mbox{]})))} - - - -Parse quat real data from integrated gyro rotation vector report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Quat real data. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a4664b5298e0059c173f71bb73a87d239}\label{_b_n_o08x__macros_8hpp_a4664b5298e0059c173f71bb73a87d239} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_INPUT\_REPORT\_DATA\_1@{PARSE\_INPUT\_REPORT\_DATA\_1}} -\index{PARSE\_INPUT\_REPORT\_DATA\_1@{PARSE\_INPUT\_REPORT\_DATA\_1}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_INPUT\_REPORT\_DATA\_1}{PARSE\_INPUT\_REPORT\_DATA\_1}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+DATA\+\_\+1(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 5\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 4\mbox{]})))} - - - -Parse first data block from input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -First data block of input report. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a455a8649345748be2d5f35036052f78a}\label{_b_n_o08x__macros_8hpp_a455a8649345748be2d5f35036052f78a} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_INPUT\_REPORT\_DATA\_2@{PARSE\_INPUT\_REPORT\_DATA\_2}} -\index{PARSE\_INPUT\_REPORT\_DATA\_2@{PARSE\_INPUT\_REPORT\_DATA\_2}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_INPUT\_REPORT\_DATA\_2}{PARSE\_INPUT\_REPORT\_DATA\_2}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+DATA\+\_\+2(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 7\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 6\mbox{]})))} - - - -Parse second data block from input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Second data block of input report. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a7d38fbfe154c526c822748fc812e7d52}\label{_b_n_o08x__macros_8hpp_a7d38fbfe154c526c822748fc812e7d52} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_INPUT\_REPORT\_DATA\_3@{PARSE\_INPUT\_REPORT\_DATA\_3}} -\index{PARSE\_INPUT\_REPORT\_DATA\_3@{PARSE\_INPUT\_REPORT\_DATA\_3}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_INPUT\_REPORT\_DATA\_3}{PARSE\_INPUT\_REPORT\_DATA\_3}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+DATA\+\_\+3(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 9\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 8\mbox{]})))} - - - -Parse third data block from input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -third data block of input report. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a3d6971a39ce4858314247bdbbb754b33}\label{_b_n_o08x__macros_8hpp_a3d6971a39ce4858314247bdbbb754b33} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_INPUT\_REPORT\_DATA\_4@{PARSE\_INPUT\_REPORT\_DATA\_4}} -\index{PARSE\_INPUT\_REPORT\_DATA\_4@{PARSE\_INPUT\_REPORT\_DATA\_4}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_INPUT\_REPORT\_DATA\_4}{PARSE\_INPUT\_REPORT\_DATA\_4}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+DATA\+\_\+4(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 11\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 10\mbox{]})))} - - - -Parse fourth data block from input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -fourth data block of input report. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_afd61b5f28723a3f20874097b1bd46e1a}\label{_b_n_o08x__macros_8hpp_afd61b5f28723a3f20874097b1bd46e1a} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_INPUT\_REPORT\_DATA\_5@{PARSE\_INPUT\_REPORT\_DATA\_5}} -\index{PARSE\_INPUT\_REPORT\_DATA\_5@{PARSE\_INPUT\_REPORT\_DATA\_5}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_INPUT\_REPORT\_DATA\_5}{PARSE\_INPUT\_REPORT\_DATA\_5}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+DATA\+\_\+5(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 13\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 12\mbox{]})))} - - - -Parse fifth data block from input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -fifth data block of input report. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_ae66870a6ac704d1ee582f4f7bd2ba6a7}\label{_b_n_o08x__macros_8hpp_ae66870a6ac704d1ee582f4f7bd2ba6a7} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_INPUT\_REPORT\_DATA\_6@{PARSE\_INPUT\_REPORT\_DATA\_6}} -\index{PARSE\_INPUT\_REPORT\_DATA\_6@{PARSE\_INPUT\_REPORT\_DATA\_6}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_INPUT\_REPORT\_DATA\_6}{PARSE\_INPUT\_REPORT\_DATA\_6}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+DATA\+\_\+6(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 15\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5 + 14\mbox{]})))} - - - -Parse sixth data block from input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -sixth data block of input report. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a5be1d9a953a0657a4b8df88681b211bc}\label{_b_n_o08x__macros_8hpp_a5be1d9a953a0657a4b8df88681b211bc} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_INPUT\_REPORT\_REPORT\_ID@{PARSE\_INPUT\_REPORT\_REPORT\_ID}} -\index{PARSE\_INPUT\_REPORT\_REPORT\_ID@{PARSE\_INPUT\_REPORT\_REPORT\_ID}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_INPUT\_REPORT\_REPORT\_ID}{PARSE\_INPUT\_REPORT\_REPORT\_ID}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+REPORT\+\_\+\+ID(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet-\/$>$body\mbox{[}5\mbox{]}))} - - - -Parse report ID from input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Report ID. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_ac4cad93c425c38fd5cd90d0982897611}\label{_b_n_o08x__macros_8hpp_ac4cad93c425c38fd5cd90d0982897611} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_INPUT\_REPORT\_STATUS\_BITS@{PARSE\_INPUT\_REPORT\_STATUS\_BITS}} -\index{PARSE\_INPUT\_REPORT\_STATUS\_BITS@{PARSE\_INPUT\_REPORT\_STATUS\_BITS}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_INPUT\_REPORT\_STATUS\_BITS}{PARSE\_INPUT\_REPORT\_STATUS\_BITS}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+INPUT\+\_\+\+REPORT\+\_\+\+STATUS\+\_\+\+BITS(\begin{DoxyParamCaption}\item[{}]{packet }\end{DoxyParamCaption})~(packet-\/$>$body\mbox{[}5 + 2\mbox{]} \& 0x03U)} - - - -Parse status bits from input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Input report status bits. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a432e15325e64ab36d5a3b30b65a71bf1}\label{_b_n_o08x__macros_8hpp_a432e15325e64ab36d5a3b30b65a71bf1} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_PACKET\_LENGTH@{PARSE\_PACKET\_LENGTH}} -\index{PARSE\_PACKET\_LENGTH@{PARSE\_PACKET\_LENGTH}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_PACKET\_LENGTH}{PARSE\_PACKET\_LENGTH}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+PACKET\+\_\+\+LENGTH(\begin{DoxyParamCaption}\item[{}]{packet\+\_\+ptr }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}{UINT16\+\_\+\+CLR\+\_\+\+LSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet\+\_\+ptr-\/$>$header\mbox{[}1\mbox{]}) $<$$<$ 8U) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}{UINT16\+\_\+\+CLR\+\_\+\+MSB}}(static\+\_\+cast$<$uint16\+\_\+t$>$(packet\+\_\+ptr-\/$>$header\mbox{[}0\mbox{]})))} - - - -Parse length from SHTP packet header. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Length of SHTP packet. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_afa3b6d75bbe499250e69043547a39208}\label{_b_n_o08x__macros_8hpp_afa3b6d75bbe499250e69043547a39208} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_PACKET\_TIMESTAMP@{PARSE\_PACKET\_TIMESTAMP}} -\index{PARSE\_PACKET\_TIMESTAMP@{PARSE\_PACKET\_TIMESTAMP}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_PACKET\_TIMESTAMP}{PARSE\_PACKET\_TIMESTAMP}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+PACKET\+\_\+\+TIMESTAMP(\begin{DoxyParamCaption}\item[{}]{packet\+\_\+ptr }\end{DoxyParamCaption})} - -{\bfseries Value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{\ \ \ \ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet-\/>body[4])\ <<\ 24UL,\ 3UL)\ |\ \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet-\/>body[3])\ <<\ 16UL,\ 2UL)\ |\ \ \ \(\backslash\)} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet-\/>body[2])\ <<\ 8UL,\ 1UL)\ |\ \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet-\/>body[1]),\ 0UL))} - -\end{DoxyCode} - - -Parse timestamp from SHTP packet. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Packet timestamp. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a37c86278c2de384fe3b9304b8d2d3370}\label{_b_n_o08x__macros_8hpp_a37c86278c2de384fe3b9304b8d2d3370} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_PRODUCT\_ID\_REPORT\_PRODUCT\_ID@{PARSE\_PRODUCT\_ID\_REPORT\_PRODUCT\_ID}} -\index{PARSE\_PRODUCT\_ID\_REPORT\_PRODUCT\_ID@{PARSE\_PRODUCT\_ID\_REPORT\_PRODUCT\_ID}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_PRODUCT\_ID\_REPORT\_PRODUCT\_ID}{PARSE\_PRODUCT\_ID\_REPORT\_PRODUCT\_ID}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+PRODUCT\+\_\+\+ID(\begin{DoxyParamCaption}\item[{}]{packet\+\_\+ptr }\end{DoxyParamCaption})~\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(static\+\_\+cast$<$uint32\+\_\+t$>$(packet-\/$>$body\mbox{[}0\mbox{]}), 0\+UL)} - - - -Parse product ID SHTP packet containing product ID report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Product ID. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a4c1a6f80fc6ab0ab5d6f803bc175b3e1}\label{_b_n_o08x__macros_8hpp_a4c1a6f80fc6ab0ab5d6f803bc175b3e1} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_PRODUCT\_ID\_REPORT\_RESET\_REASON@{PARSE\_PRODUCT\_ID\_REPORT\_RESET\_REASON}} -\index{PARSE\_PRODUCT\_ID\_REPORT\_RESET\_REASON@{PARSE\_PRODUCT\_ID\_REPORT\_RESET\_REASON}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_PRODUCT\_ID\_REPORT\_RESET\_REASON}{PARSE\_PRODUCT\_ID\_REPORT\_RESET\_REASON}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+RESET\+\_\+\+REASON(\begin{DoxyParamCaption}\item[{}]{packet\+\_\+ptr }\end{DoxyParamCaption})~\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(static\+\_\+cast$<$uint32\+\_\+t$>$(packet\+\_\+ptr-\/$>$body\mbox{[}1\mbox{]}), 0\+UL)} - - - -Parse reset reason from SHTP packet containing product ID report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Reset reason. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a24ff2498d4883f329d70fb2a6f10e04a}\label{_b_n_o08x__macros_8hpp_a24ff2498d4883f329d70fb2a6f10e04a} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_PRODUCT\_ID\_REPORT\_SW\_BUILD\_NO@{PARSE\_PRODUCT\_ID\_REPORT\_SW\_BUILD\_NO}} -\index{PARSE\_PRODUCT\_ID\_REPORT\_SW\_BUILD\_NO@{PARSE\_PRODUCT\_ID\_REPORT\_SW\_BUILD\_NO}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_PRODUCT\_ID\_REPORT\_SW\_BUILD\_NO}{PARSE\_PRODUCT\_ID\_REPORT\_SW\_BUILD\_NO}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+SW\+\_\+\+BUILD\+\_\+\+NO(\begin{DoxyParamCaption}\item[{}]{packet\+\_\+ptr }\end{DoxyParamCaption})} - -{\bfseries Value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{\ \ \ \ \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet-\/>body[11])\ <<\ 24UL,\ 3UL)\ |\ \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet-\/>body[10])\ <<\ 16UL,\ 2UL)\ |\ \ \(\backslash\)} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet-\/>body[9])\ <<\ 8UL,\ 1UL)\ |\ \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet-\/>body[8]),\ 0UL)} - -\end{DoxyCode} - - -Parse sw build number from SHTP packet containing product ID report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -sw build number. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a5e6be52a05421d50c4b3600c35868540}\label{_b_n_o08x__macros_8hpp_a5e6be52a05421d50c4b3600c35868540} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_PRODUCT\_ID\_REPORT\_SW\_PART\_NO@{PARSE\_PRODUCT\_ID\_REPORT\_SW\_PART\_NO}} -\index{PARSE\_PRODUCT\_ID\_REPORT\_SW\_PART\_NO@{PARSE\_PRODUCT\_ID\_REPORT\_SW\_PART\_NO}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_PRODUCT\_ID\_REPORT\_SW\_PART\_NO}{PARSE\_PRODUCT\_ID\_REPORT\_SW\_PART\_NO}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+SW\+\_\+\+PART\+\_\+\+NO(\begin{DoxyParamCaption}\item[{}]{packet\+\_\+ptr }\end{DoxyParamCaption})} - -{\bfseries Value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{\ \ \ \ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\_MSK\_BYTE}}(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet\_ptr-\/>body[7])\ <<\ 24UL,\ 3UL)\ |\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet\_ptr-\/>body[6])\ <<\ 16UL,\ 2UL)\ |\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet\_ptr-\/>body[5])\ <<\ 8UL,\ 1UL)\ |\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(\textcolor{keyword}{static\_cast<}uint32\_t\textcolor{keyword}{>}(packet\_ptr-\/>body[4]),\ 0UL))} - -\end{DoxyCode} - - -Parse sw part number from SHTP packet containing product ID report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -sw part number. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_af59b362a169fe8c11a0b679ca99383ee}\label{_b_n_o08x__macros_8hpp_af59b362a169fe8c11a0b679ca99383ee} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MAJOR@{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MAJOR}} -\index{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MAJOR@{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MAJOR}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MAJOR}{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MAJOR}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+SW\+\_\+\+VERSION\+\_\+\+MAJOR(\begin{DoxyParamCaption}\item[{}]{packet\+\_\+ptr }\end{DoxyParamCaption})~\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(static\+\_\+cast$<$uint32\+\_\+t$>$(packet-\/$>$body\mbox{[}2\mbox{]}), 0\+UL)} - - - -Parse product sw version major containing product ID report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -sw version major. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_ad9773ac824ab751df0e331a7c16080a1}\label{_b_n_o08x__macros_8hpp_ad9773ac824ab751df0e331a7c16080a1} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MINOR@{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MINOR}} -\index{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MINOR@{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MINOR}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MINOR}{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MINOR}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+SW\+\_\+\+VERSION\+\_\+\+MINOR(\begin{DoxyParamCaption}\item[{}]{packet\+\_\+ptr }\end{DoxyParamCaption})~\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(static\+\_\+cast$<$uint32\+\_\+t$>$(packet-\/$>$body\mbox{[}3\mbox{]}), 0\+UL)} - - - -Parse product sw version minor containing product ID report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -sw version minor. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a23baa3c8a71f3b3021f135bef27a8ed9}\label{_b_n_o08x__macros_8hpp_a23baa3c8a71f3b3021f135bef27a8ed9} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_PATCH@{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_PATCH}} -\index{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_PATCH@{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_PATCH}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_PATCH}{PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_PATCH}} -{\footnotesize\ttfamily \#define PARSE\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REPORT\+\_\+\+SW\+\_\+\+VERSION\+\_\+\+PATCH(\begin{DoxyParamCaption}\item[{}]{packet\+\_\+ptr }\end{DoxyParamCaption})~ (\mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(static\+\_\+cast$<$uint32\+\_\+t$>$(packet-\/$>$body\mbox{[}13\mbox{]}) $<$$<$ 8UL, 1UL) \texorpdfstring{$\vert$}{|} \mbox{\hyperlink{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}{UINT32\+\_\+\+MSK\+\_\+\+BYTE}}(static\+\_\+cast$<$uint32\+\_\+t$>$(packet-\/$>$body\mbox{[}12\mbox{]}), 0\+UL))} - - - -Parse sw version patch from SHTP packet containing product ID report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to bno08x\+\_\+rx\+\_\+packet\+\_\+t containing data. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -sw version patch. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b}\label{_b_n_o08x__macros_8hpp_ac89a0ae0c3d3067f02e9fa275521606b} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!UINT16\_CLR\_LSB@{UINT16\_CLR\_LSB}} -\index{UINT16\_CLR\_LSB@{UINT16\_CLR\_LSB}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{UINT16\_CLR\_LSB}{UINT16\_CLR\_LSB}} -{\footnotesize\ttfamily \#define UINT16\+\_\+\+CLR\+\_\+\+LSB(\begin{DoxyParamCaption}\item[{}]{val\+\_\+16bit }\end{DoxyParamCaption})~((val\+\_\+16bit) \& 0x\+FF00U)} - - - -Clears the least significant byte of a 16-\/bit value. - - -\begin{DoxyParams}{Parameters} -{\em val\+\_\+16bit} & The 16-\/bit value to modify. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The value with the MSB cleared. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40}\label{_b_n_o08x__macros_8hpp_ad98f2fa811436866ff297a8288e34f40} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!UINT16\_CLR\_MSB@{UINT16\_CLR\_MSB}} -\index{UINT16\_CLR\_MSB@{UINT16\_CLR\_MSB}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{UINT16\_CLR\_MSB}{UINT16\_CLR\_MSB}} -{\footnotesize\ttfamily \#define UINT16\+\_\+\+CLR\+\_\+\+MSB(\begin{DoxyParamCaption}\item[{}]{val\+\_\+16bit }\end{DoxyParamCaption})~((val\+\_\+16bit) \& 0x00\+FFU)} - - - -Clears the most significant byte of a 16-\/bit value. - - -\begin{DoxyParams}{Parameters} -{\em val\+\_\+16bit} & The 16-\/bit value to modify. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The value with the MSB cleared. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a7de5c0b84ba545981105e1216925d8e9}\label{_b_n_o08x__macros_8hpp_a7de5c0b84ba545981105e1216925d8e9} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!UINT32\_CLR\_BYTE@{UINT32\_CLR\_BYTE}} -\index{UINT32\_CLR\_BYTE@{UINT32\_CLR\_BYTE}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{UINT32\_CLR\_BYTE}{UINT32\_CLR\_BYTE}} -{\footnotesize\ttfamily \#define UINT32\+\_\+\+CLR\+\_\+\+BYTE(\begin{DoxyParamCaption}\item[{}]{val\+\_\+32bit, }\item[{}]{byte2clear }\end{DoxyParamCaption})~((val\+\_\+32bit) \& \texorpdfstring{$\sim$}{\string~}(0x\+FFUL $<$$<$ (byte2clear \texorpdfstring{$\ast$}{*} 8UL)))} - - - -Clears a specified byte in a 32-\/bit value. - - -\begin{DoxyParams}{Parameters} -{\em val\+\_\+32bit} & The 32-\/bit value to modify. \\ -\hline -{\em byte2clear} & The byte index to clear (0 = LSB, 3 = MSB). \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The value with the specified byte cleared. -\end{DoxyReturn} -\Hypertarget{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8}\label{_b_n_o08x__macros_8hpp_a6f459cc2cce1722c63d22a9556f06bc8} -\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}!UINT32\_MSK\_BYTE@{UINT32\_MSK\_BYTE}} -\index{UINT32\_MSK\_BYTE@{UINT32\_MSK\_BYTE}!BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\doxysubsubsection{\texorpdfstring{UINT32\_MSK\_BYTE}{UINT32\_MSK\_BYTE}} -{\footnotesize\ttfamily \#define UINT32\+\_\+\+MSK\+\_\+\+BYTE(\begin{DoxyParamCaption}\item[{}]{val\+\_\+32bit, }\item[{}]{byte2mask }\end{DoxyParamCaption})~((val\+\_\+32bit) \& (0x\+FFUL $<$$<$ (byte2mask \texorpdfstring{$\ast$}{*} 8UL)))} - - - -Masks a specified byte in a 32-\/bit value. - - -\begin{DoxyParams}{Parameters} -{\em val\+\_\+32bit} & The 32-\/bit value to modify. \\ -\hline -{\em byte2mask} & The byte index to mask (0 = LSB, 3 = MSB). \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The value with the specified byte masked. -\end{DoxyReturn} diff --git a/documentation/latex/_b_n_o08x__macros_8hpp__dep__incl.md5 b/documentation/latex/_b_n_o08x__macros_8hpp__dep__incl.md5 deleted file mode 100644 index 2a2b356..0000000 --- a/documentation/latex/_b_n_o08x__macros_8hpp__dep__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -a1b5e8bb84e41583bd410e0c74c3e783 \ No newline at end of file diff --git a/documentation/latex/_b_n_o08x__macros_8hpp__dep__incl.pdf b/documentation/latex/_b_n_o08x__macros_8hpp__dep__incl.pdf deleted file mode 100644 index b79a2ba..0000000 Binary files a/documentation/latex/_b_n_o08x__macros_8hpp__dep__incl.pdf and /dev/null differ diff --git a/documentation/latex/_b_n_o08x__macros_8hpp__incl.md5 b/documentation/latex/_b_n_o08x__macros_8hpp__incl.md5 deleted file mode 100644 index e2e01b9..0000000 --- a/documentation/latex/_b_n_o08x__macros_8hpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -7017798d99a29cbc38df831d110700ec \ No newline at end of file diff --git a/documentation/latex/_b_n_o08x__macros_8hpp__incl.pdf b/documentation/latex/_b_n_o08x__macros_8hpp__incl.pdf deleted file mode 100644 index cb2dc99..0000000 Binary files a/documentation/latex/_b_n_o08x__macros_8hpp__incl.pdf and /dev/null differ diff --git a/documentation/latex/_b_n_o08x__macros_8hpp_source.tex b/documentation/latex/_b_n_o08x__macros_8hpp_source.tex deleted file mode 100644 index f53b1e5..0000000 --- a/documentation/latex/_b_n_o08x__macros_8hpp_source.tex +++ /dev/null @@ -1,124 +0,0 @@ -\doxysection{BNO08x\+\_\+macros.\+hpp} -\hypertarget{_b_n_o08x__macros_8hpp_source}{}\label{_b_n_o08x__macros_8hpp_source}\index{BNO08x\_macros.hpp@{BNO08x\_macros.hpp}} -\mbox{\hyperlink{_b_n_o08x__macros_8hpp}{Go to the documentation of this file.}} -\begin{DoxyCode}{0} -\DoxyCodeLine{00001\ } -\DoxyCodeLine{00005\ \textcolor{preprocessor}{\#pragma\ once}} -\DoxyCodeLine{00006\ } -\DoxyCodeLine{00007\ \textcolor{comment}{//\ standard\ library\ includes}} -\DoxyCodeLine{00008\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00009\ } -\DoxyCodeLine{00010\ \textcolor{comment}{//\ esp-\/idf\ includes}} -\DoxyCodeLine{00011\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00012\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00013\ } -\DoxyCodeLine{00022\ \textcolor{preprocessor}{\#define\ CHECK\_TASKS\_RUNNING(evt\_grp\_task\_flow,\ running\_bit)\ ((xEventGroupGetBits(evt\_grp\_task\_flow)\ \&\ (running\_bit))\ !=\ 0)}} -\DoxyCodeLine{00023\ } -\DoxyCodeLine{00024\ \textcolor{comment}{//\ packet\ parsing\ macros}} -\DoxyCodeLine{00025\ } -\DoxyCodeLine{00032\ \textcolor{preprocessor}{\#define\ UINT16\_CLR\_MSB(val\_16bit)\ ((val\_16bit)\ \&\ 0x00FFU)}} -\DoxyCodeLine{00033\ } -\DoxyCodeLine{00040\ \textcolor{preprocessor}{\#define\ UINT16\_CLR\_LSB(val\_16bit)\ ((val\_16bit)\ \&\ 0xFF00U)}} -\DoxyCodeLine{00041\ } -\DoxyCodeLine{00049\ \textcolor{preprocessor}{\#define\ UINT32\_CLR\_BYTE(val\_32bit,\ byte2clear)\ ((val\_32bit)\ \&\ \string~(0xFFUL\ <<\ (byte2clear\ *\ 8UL)))}} -\DoxyCodeLine{00050\ } -\DoxyCodeLine{00058\ \textcolor{preprocessor}{\#define\ UINT32\_MSK\_BYTE(val\_32bit,\ byte2mask)\ ((val\_32bit)\ \&\ (0xFFUL\ <<\ (byte2mask\ *\ 8UL)))}} -\DoxyCodeLine{00059\ } -\DoxyCodeLine{00060\ \textcolor{comment}{//\ parsing\ universal\ to\ any\ packet}} -\DoxyCodeLine{00061\ } -\DoxyCodeLine{00068\ \textcolor{preprocessor}{\#define\ PARSE\_PACKET\_LENGTH(packet\_ptr)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00069\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet\_ptr-\/>header[1])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet\_ptr-\/>header[0])))}} -\DoxyCodeLine{00070\ } -\DoxyCodeLine{00077\ \textcolor{preprocessor}{\#define\ PARSE\_PACKET\_TIMESTAMP(packet\_ptr)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00078\ \textcolor{preprocessor}{\ \ \ \ (UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[4])\ <<\ 24UL,\ 3UL)\ |\ UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[3])\ <<\ 16UL,\ 2UL)\ |\ \ \ \(\backslash\)}} -\DoxyCodeLine{00079\ \textcolor{preprocessor}{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[2])\ <<\ 8UL,\ 1UL)\ |\ UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[1]),\ 0UL))}} -\DoxyCodeLine{00080\ } -\DoxyCodeLine{00081\ \textcolor{comment}{//\ product\ id\ report\ parsing}} -\DoxyCodeLine{00082\ } -\DoxyCodeLine{00089\ \textcolor{preprocessor}{\#define\ PARSE\_PRODUCT\_ID\_REPORT\_RESET\_REASON(packet\_ptr)\ UINT32\_MSK\_BYTE(static\_cast(packet\_ptr-\/>body[1]),\ 0UL)}} -\DoxyCodeLine{00090\ } -\DoxyCodeLine{00097\ \textcolor{preprocessor}{\#define\ PARSE\_PRODUCT\_ID\_REPORT\_SW\_PART\_NO(packet\_ptr)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00098\ \textcolor{preprocessor}{\ \ \ \ (UINT32\_MSK\_BYTE(static\_cast(packet\_ptr-\/>body[7])\ <<\ 24UL,\ 3UL)\ |\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00099\ \textcolor{preprocessor}{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(static\_cast(packet\_ptr-\/>body[6])\ <<\ 16UL,\ 2UL)\ |\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00100\ \textcolor{preprocessor}{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(static\_cast(packet\_ptr-\/>body[5])\ <<\ 8UL,\ 1UL)\ |\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00101\ \textcolor{preprocessor}{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(static\_cast(packet\_ptr-\/>body[4]),\ 0UL))}} -\DoxyCodeLine{00102\ } -\DoxyCodeLine{00109\ \textcolor{preprocessor}{\#define\ PARSE\_PRODUCT\_ID\_REPORT\_SW\_BUILD\_NO(packet\_ptr)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00110\ \textcolor{preprocessor}{\ \ \ \ UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[11])\ <<\ 24UL,\ 3UL)\ |\ UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[10])\ <<\ 16UL,\ 2UL)\ |\ \ \(\backslash\)}} -\DoxyCodeLine{00111\ \textcolor{preprocessor}{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[9])\ <<\ 8UL,\ 1UL)\ |\ UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[8]),\ 0UL)}} -\DoxyCodeLine{00112\ } -\DoxyCodeLine{00119\ \textcolor{preprocessor}{\#define\ PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_PATCH(packet\_ptr)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00120\ \textcolor{preprocessor}{\ \ \ \ (UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[13])\ <<\ 8UL,\ 1UL)\ |\ UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[12]),\ 0UL))}} -\DoxyCodeLine{00121\ } -\DoxyCodeLine{00128\ \textcolor{preprocessor}{\#define\ PARSE\_PRODUCT\_ID\_REPORT\_PRODUCT\_ID(packet\_ptr)\ UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[0]),\ 0UL)}} -\DoxyCodeLine{00129\ } -\DoxyCodeLine{00136\ \textcolor{preprocessor}{\#define\ PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MAJOR(packet\_ptr)\ UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[2]),\ 0UL)}} -\DoxyCodeLine{00137\ } -\DoxyCodeLine{00144\ \textcolor{preprocessor}{\#define\ PARSE\_PRODUCT\_ID\_REPORT\_SW\_VERSION\_MINOR(packet\_ptr)\ UINT32\_MSK\_BYTE(static\_cast(packet-\/>body[3]),\ 0UL)}} -\DoxyCodeLine{00145\ } -\DoxyCodeLine{00146\ \textcolor{comment}{//\ gyro\ report\ parsing}} -\DoxyCodeLine{00147\ } -\DoxyCodeLine{00154\ \textcolor{preprocessor}{\#define\ PARSE\_GYRO\_REPORT\_RAW\_QUAT\_I(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00155\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[1])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[0])))}} -\DoxyCodeLine{00156\ } -\DoxyCodeLine{00163\ \textcolor{preprocessor}{\#define\ PARSE\_GYRO\_REPORT\_RAW\_QUAT\_J(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00164\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[3])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[2])))}} -\DoxyCodeLine{00165\ } -\DoxyCodeLine{00172\ \textcolor{preprocessor}{\#define\ PARSE\_GYRO\_REPORT\_RAW\_QUAT\_K(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00173\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[5])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[4])))}} -\DoxyCodeLine{00174\ } -\DoxyCodeLine{00181\ \textcolor{preprocessor}{\#define\ PARSE\_GYRO\_REPORT\_RAW\_QUAT\_REAL(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00182\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[7])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[6])))}} -\DoxyCodeLine{00183\ } -\DoxyCodeLine{00190\ \textcolor{preprocessor}{\#define\ PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_X(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00191\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[9])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[8])))}} -\DoxyCodeLine{00192\ } -\DoxyCodeLine{00199\ \textcolor{preprocessor}{\#define\ PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Y(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00200\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[11])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[10])))}} -\DoxyCodeLine{00201\ } -\DoxyCodeLine{00208\ \textcolor{preprocessor}{\#define\ PARSE\_GYRO\_REPORT\_RAW\_GYRO\_VEL\_Z(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00209\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[13])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[12])))}} -\DoxyCodeLine{00210\ } -\DoxyCodeLine{00211\ \textcolor{comment}{//\ input\ report\ parsing}} -\DoxyCodeLine{00212\ } -\DoxyCodeLine{00219\ \textcolor{preprocessor}{\#define\ PARSE\_INPUT\_REPORT\_STATUS\_BITS(packet)\ (packet-\/>body[5\ +\ 2]\ \&\ 0x03U)}} -\DoxyCodeLine{00220\ } -\DoxyCodeLine{00227\ \textcolor{preprocessor}{\#define\ PARSE\_INPUT\_REPORT\_REPORT\_ID(packet)\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[5]))}} -\DoxyCodeLine{00228\ } -\DoxyCodeLine{00235\ \textcolor{preprocessor}{\#define\ PARSE\_INPUT\_REPORT\_DATA\_1(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00236\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[5\ +\ 5])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[5\ +\ 4])))}} -\DoxyCodeLine{00237\ } -\DoxyCodeLine{00244\ \textcolor{preprocessor}{\#define\ PARSE\_INPUT\_REPORT\_DATA\_2(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00245\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[5\ +\ 7])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[5\ +\ 6])))}} -\DoxyCodeLine{00246\ } -\DoxyCodeLine{00253\ \textcolor{preprocessor}{\#define\ PARSE\_INPUT\_REPORT\_DATA\_3(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00254\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[5\ +\ 9])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[5\ +\ 8])))}} -\DoxyCodeLine{00255\ } -\DoxyCodeLine{00262\ \textcolor{preprocessor}{\#define\ PARSE\_INPUT\_REPORT\_DATA\_4(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00263\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[5\ +\ 11])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[5\ +\ 10])))}} -\DoxyCodeLine{00264\ } -\DoxyCodeLine{00271\ \textcolor{preprocessor}{\#define\ PARSE\_INPUT\_REPORT\_DATA\_5(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00272\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[5\ +\ 13])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[5\ +\ 12])))}} -\DoxyCodeLine{00273\ } -\DoxyCodeLine{00280\ \textcolor{preprocessor}{\#define\ PARSE\_INPUT\_REPORT\_DATA\_6(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00281\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet-\/>body[5\ +\ 15])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet-\/>body[5\ +\ 14])))}} -\DoxyCodeLine{00282\ } -\DoxyCodeLine{00289\ \textcolor{preprocessor}{\#define\ IS\_ROTATION\_VECTOR\_REPORT(packet)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00290\ \textcolor{preprocessor}{\ \ \ \ ((packet)-\/>body[5]\ ==\ SENSOR\_REPORT\_ID\_ROTATION\_VECTOR\ ||\ (packet)-\/>body[5]\ ==\ SENSOR\_REPORT\_ID\_GAME\_ROTATION\_VECTOR\ ||\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00291\ \textcolor{preprocessor}{\ \ \ \ \ \ \ \ \ \ \ \ (packet)-\/>body[5]\ ==\ SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_ROTATION\_VECTOR\ ||\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00292\ \textcolor{preprocessor}{\ \ \ \ \ \ \ \ \ \ \ \ (packet)-\/>body[5]\ ==\ SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR)}} -\DoxyCodeLine{00293\ } -\DoxyCodeLine{00294\ \textcolor{comment}{//\ frs\ read\ response\ report\ parsing}} -\DoxyCodeLine{00295\ } -\DoxyCodeLine{00302\ \textcolor{preprocessor}{\#define\ PARSE\_FRS\_READ\_RESPONSE\_REPORT\_RECORD\_ID(packet\_body)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00303\ \textcolor{preprocessor}{\ \ \ \ (UINT16\_CLR\_LSB(static\_cast(packet\_body[13])\ <<\ 8U)\ |\ UINT16\_CLR\_MSB(static\_cast(packet\_body[12])))}} -\DoxyCodeLine{00304\ } -\DoxyCodeLine{00311\ \textcolor{preprocessor}{\#define\ PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_1(packet\_body)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00312\ \textcolor{preprocessor}{\ \ \ \ (UINT32\_MSK\_BYTE(static\_cast(packet\_body[7])\ <<\ 24UL,\ 3UL)\ |\ UINT32\_MSK\_BYTE(static\_cast(packet\_body[6])\ <<\ 16UL,\ 2UL)\ |\ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00313\ \textcolor{preprocessor}{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(static\_cast(packet\_body[5])\ <<\ 8UL,\ 1UL)\ |\ UINT32\_MSK\_BYTE(static\_cast(packet\_body[4]),\ 0UL))}} -\DoxyCodeLine{00314\ } -\DoxyCodeLine{00321\ \textcolor{preprocessor}{\#define\ PARSE\_FRS\_READ\_RESPONSE\_REPORT\_DATA\_2(packet\_body)\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \(\backslash\)}} -\DoxyCodeLine{00322\ \textcolor{preprocessor}{\ \ \ \ (UINT32\_MSK\_BYTE(static\_cast(packet\_body[11])\ <<\ 24UL,\ 3UL)\ |\ UINT32\_MSK\_BYTE(static\_cast(packet\_body[10])\ <<\ 16UL,\ 2UL)\ |\ \ \ \(\backslash\)}} -\DoxyCodeLine{00323\ \textcolor{preprocessor}{\ \ \ \ \ \ \ \ \ \ \ \ UINT32\_MSK\_BYTE(static\_cast(packet\_body[9])\ <<\ 8UL,\ 1UL)\ |\ UINT32\_MSK\_BYTE(static\_cast(packet\_body[8]),\ 0UL))}} - -\end{DoxyCode} diff --git a/documentation/latex/_b_n_o08x_test_helper_8hpp.tex b/documentation/latex/_b_n_o08x_test_helper_8hpp.tex deleted file mode 100644 index ee96b6b..0000000 --- a/documentation/latex/_b_n_o08x_test_helper_8hpp.tex +++ /dev/null @@ -1,33 +0,0 @@ -\doxysection{BNO08x\+Test\+Helper.\+hpp File Reference} -\hypertarget{_b_n_o08x_test_helper_8hpp}{}\label{_b_n_o08x_test_helper_8hpp}\index{BNO08xTestHelper.hpp@{BNO08xTestHelper.hpp}} -{\ttfamily \#include "{}stdio.\+h"{}}\newline -{\ttfamily \#include "{}BNO08x.\+hpp"{}}\newline -Include dependency graph for BNO08x\+Test\+Helper.\+hpp\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_b_n_o08x_test_helper_8hpp__incl} -\end{center} -\end{figure} -This graph shows which files directly or indirectly include this file\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_b_n_o08x_test_helper_8hpp__dep__incl} -\end{center} -\end{figure} -\doxysubsubsection*{Classes} -\begin{DoxyCompactItemize} -\item -class \mbox{\hyperlink{class_b_n_o08x_test_helper}{BNO08x\+Test\+Helper}} -\begin{DoxyCompactList}\small\item\em \doxylink{class_b_n_o08x}{BNO08x} unit test helper class. \end{DoxyCompactList}\item -struct \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t}} -\begin{DoxyCompactList}\small\item\em IMU configuration settings passed into constructor. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -\begin{DoxyAuthor}{Author} -Myles Parfeniuk -\end{DoxyAuthor} diff --git a/documentation/latex/_b_n_o08x_test_helper_8hpp__dep__incl.md5 b/documentation/latex/_b_n_o08x_test_helper_8hpp__dep__incl.md5 deleted file mode 100644 index ae21a8f..0000000 --- a/documentation/latex/_b_n_o08x_test_helper_8hpp__dep__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -7f734b0100a6ade061be8acb0901f08e \ No newline at end of file diff --git a/documentation/latex/_b_n_o08x_test_helper_8hpp__dep__incl.pdf b/documentation/latex/_b_n_o08x_test_helper_8hpp__dep__incl.pdf deleted file mode 100644 index bd9310d..0000000 Binary files a/documentation/latex/_b_n_o08x_test_helper_8hpp__dep__incl.pdf and /dev/null differ diff --git a/documentation/latex/_b_n_o08x_test_helper_8hpp__incl.md5 b/documentation/latex/_b_n_o08x_test_helper_8hpp__incl.md5 deleted file mode 100644 index 3136a73..0000000 --- a/documentation/latex/_b_n_o08x_test_helper_8hpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -160b51f2467e03a4621a4058d64f4f06 \ No newline at end of file diff --git a/documentation/latex/_b_n_o08x_test_helper_8hpp__incl.pdf b/documentation/latex/_b_n_o08x_test_helper_8hpp__incl.pdf deleted file mode 100644 index d7f8c33..0000000 Binary files a/documentation/latex/_b_n_o08x_test_helper_8hpp__incl.pdf and /dev/null differ diff --git a/documentation/latex/_b_n_o08x_test_helper_8hpp_source.tex b/documentation/latex/_b_n_o08x_test_helper_8hpp_source.tex deleted file mode 100644 index 6034be0..0000000 --- a/documentation/latex/_b_n_o08x_test_helper_8hpp_source.tex +++ /dev/null @@ -1,511 +0,0 @@ -\doxysection{BNO08x\+Test\+Helper.\+hpp} -\hypertarget{_b_n_o08x_test_helper_8hpp_source}{}\label{_b_n_o08x_test_helper_8hpp_source}\index{BNO08xTestHelper.hpp@{BNO08xTestHelper.hpp}} -\mbox{\hyperlink{_b_n_o08x_test_helper_8hpp}{Go to the documentation of this file.}} -\begin{DoxyCode}{0} -\DoxyCodeLine{00001\ } -\DoxyCodeLine{00005\ \textcolor{preprocessor}{\#pragma\ once}} -\DoxyCodeLine{00006\ } -\DoxyCodeLine{00007\ \textcolor{preprocessor}{\#include\ "{}stdio.h"{}}} -\DoxyCodeLine{00008\ \textcolor{preprocessor}{\#include\ "{}\mbox{\hyperlink{_b_n_o08x_8hpp}{BNO08x.hpp}}"{}}} -\DoxyCodeLine{00009\ } -\DoxyCodeLine{00015\ \textcolor{keyword}{class\ }\mbox{\hyperlink{class_b_n_o08x_test_helper}{BNO08xTestHelper}}} -\DoxyCodeLine{00016\ \{} -\DoxyCodeLine{00017\ \ \ \ \ \textcolor{keyword}{private}:} -\DoxyCodeLine{00018\ \ \ \ \ \ \ \ \ \textcolor{keyword}{inline}\ \textcolor{keyword}{static}\ \mbox{\hyperlink{class_b_n_o08x}{BNO08x}}*\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}\ =\ \textcolor{keyword}{nullptr};} -\DoxyCodeLine{00019\ \ \ \ \ \ \ \ \ \textcolor{keyword}{inline}\ \textcolor{keyword}{static}\ \mbox{\hyperlink{structbno08x__config__t}{bno08x\_config\_t}}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a008b268f705b9d2925230cb8193c9f28}{imu\_cfg}};} -\DoxyCodeLine{00020\ } -\DoxyCodeLine{00021\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ \textcolor{keywordtype}{char}*\ \mbox{\hyperlink{class_b_n_o08x_test_helper_aa09d388a5da3a925ac25125b9c5c3a90}{TAG}}\ =\ \textcolor{stringliteral}{"{}BNO08xTestHelper"{}};} -\DoxyCodeLine{00022\ } -\DoxyCodeLine{00023\ \ \ \ \ \textcolor{keyword}{public}:} -\DoxyCodeLine{00025\ \ \ \ \ \ \ \ \ \textcolor{keyword}{typedef}\ \textcolor{keyword}{struct\ }\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}} -\DoxyCodeLine{00026\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00027\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint32\_t\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae5e8705ad014ed3f70e5de527cb2cb66}{time\_stamp}};} -\DoxyCodeLine{00028\ } -\DoxyCodeLine{00029\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8d2c3cd33943cb1b4fd0e800f822607e}{quat\_I}};} -\DoxyCodeLine{00030\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a20a09d197d5128aae64b7449df576c27}{quat\_J}};} -\DoxyCodeLine{00031\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3c74d4c93fc4390f52b75e6ff2bea95b}{quat\_K}};} -\DoxyCodeLine{00032\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a80525c4943154f825a62539b10337976}{quat\_real}};} -\DoxyCodeLine{00033\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae0a8fef0227dd4304d08466c43d901a5}{quat\_radian\_accuracy}};} -\DoxyCodeLine{00034\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_aac84ad10b65403ae1ee21dab5cdc77db}{quat\_accuracy}};} -\DoxyCodeLine{00035\ } -\DoxyCodeLine{00036\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a077a94b4de0b5c280d69611325208cf7}{integrated\_gyro\_vel\_x}};} -\DoxyCodeLine{00037\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af4b75b320bc390c90656905711f1c791}{integrated\_gyro\_vel\_y}};} -\DoxyCodeLine{00038\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a1aa67da9c3c6449dfce361a528c418d3}{integrated\_gyro\_vel\_z}};} -\DoxyCodeLine{00039\ } -\DoxyCodeLine{00040\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5c01b349cc9e4e45c78c576882d633fd}{accel\_x}};} -\DoxyCodeLine{00041\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a7e594d0a1e86fb575f72c6f330c8983c}{accel\_y}};} -\DoxyCodeLine{00042\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af134cb789c29120033d81916e0c100d4}{accel\_z}};} -\DoxyCodeLine{00043\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac5d393de0f15176ba81bc63a80b49ca3}{accel\_accuracy}};} -\DoxyCodeLine{00044\ } -\DoxyCodeLine{00045\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3a62ed280657cd409d723e64f0c313b5}{lin\_accel\_x}};} -\DoxyCodeLine{00046\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a553942aa784c35c833543ecc9a05f606}{lin\_accel\_y}};} -\DoxyCodeLine{00047\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5bf43fc0daf3a86954924e066cad3a9b}{lin\_accel\_z}};} -\DoxyCodeLine{00048\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a48a249994c27f59ca4167b56bdda311a}{lin\_accel\_accuracy}};} -\DoxyCodeLine{00049\ } -\DoxyCodeLine{00050\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ad2c17ea111250ebc1a4a763dae3c072a}{grav\_x}};} -\DoxyCodeLine{00051\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a19fc4af8a26c10a027cbd859d67dba4a}{grav\_y}};} -\DoxyCodeLine{00052\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af1887bdfef4fc2c683fe2134cb5cfb50}{grav\_z}};} -\DoxyCodeLine{00053\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a735d099f3dd0ead4b8d986fd139af43d}{grav\_accuracy}};} -\DoxyCodeLine{00054\ } -\DoxyCodeLine{00055\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a89b427579a281440ab94a340c0ec8443}{calib\_gyro\_vel\_x}};} -\DoxyCodeLine{00056\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af9e11fd749123f5723b2e281c8d2fd16}{calib\_gyro\_vel\_y}};} -\DoxyCodeLine{00057\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a769ddae74a6c89a2d319c28f95ed6479}{calib\_gyro\_vel\_z}};} -\DoxyCodeLine{00058\ } -\DoxyCodeLine{00059\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a292b1c36fed6a9c9742edf730299c4f4}{uncalib\_gyro\_vel\_x}};} -\DoxyCodeLine{00060\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_adfd6bf2e2264cf25bd02814446600ab4}{uncalib\_gyro\_vel\_y}};} -\DoxyCodeLine{00061\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ab39fd6f409288bb35fb1542ff4b9cbe4}{uncalib\_gyro\_vel\_z}};} -\DoxyCodeLine{00062\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac70a65027c3e740eca2b1f172b7cefa3}{uncalib\_gyro\_drift\_x}};} -\DoxyCodeLine{00063\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a29d5ae3e0ed3463cb9297f9cdc0e8472}{uncalib\_gyro\_drift\_y}};} -\DoxyCodeLine{00064\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a27b52e2d96cb948c4257de4553053f72}{uncalib\_gyro\_drift\_z}};} -\DoxyCodeLine{00065\ } -\DoxyCodeLine{00066\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0e72f6dde1411e4aa1c616cedcc556c1}{magf\_x}};} -\DoxyCodeLine{00067\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8738f60a2b9bd49d2b8dd0487db7ac97}{magf\_y}};} -\DoxyCodeLine{00068\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a55187ebe06fa77def93681bcdf62595c}{magf\_z}};} -\DoxyCodeLine{00069\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0c962609a3bf7927204542521e9c5113}{magf\_accuracy}};} -\DoxyCodeLine{00070\ } -\DoxyCodeLine{00071\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a94befe7132d3a6a6ce2a7890e96ec091}{raw\_mems\_gyro\_x}};} -\DoxyCodeLine{00072\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a7e9cd7e43d70932c5f84e3cfadf8bb47}{raw\_mems\_gyro\_y}};} -\DoxyCodeLine{00073\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a9df84179bd44a7febfa1058afe3dad6c}{raw\_mems\_gyro\_z}};} -\DoxyCodeLine{00074\ } -\DoxyCodeLine{00075\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ uint16\_t\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae8435a931eac7f4376a94acfcbf6a784}{step\_count}};} -\DoxyCodeLine{00076\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}{BNO08xStability}}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a86473c2bd8cbe2c76276393ee20d568b}{stability\_classifier}};} -\DoxyCodeLine{00077\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}{BNO08xActivity}}\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0455033deba9570f248e8059cf6a3ce1}{activity\_classifier}};} -\DoxyCodeLine{00078\ } -\DoxyCodeLine{00079\ \ \ \ \ \ \ \ \ \}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a0b3d9379e670b0c532ba76801cfb7580}{imu\_report\_data\_t}};} -\DoxyCodeLine{00080\ } -\DoxyCodeLine{00088\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885}{print\_test\_start\_banner}}(\textcolor{keyword}{const}\ \textcolor{keywordtype}{char}*\ TEST\_TAG)} -\DoxyCodeLine{00089\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00090\ \ \ \ \ \ \ \ \ \ \ \ \ printf(\textcolor{stringliteral}{"{}-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/\ BEGIN\ TEST:\ \%s\ -\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/\(\backslash\)n\(\backslash\)r"{}},\ TEST\_TAG);} -\DoxyCodeLine{00091\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00092\ } -\DoxyCodeLine{00100\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919}{print\_test\_end\_banner}}(\textcolor{keyword}{const}\ \textcolor{keywordtype}{char}*\ TEST\_TAG)} -\DoxyCodeLine{00101\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00102\ \ \ \ \ \ \ \ \ \ \ \ \ printf(\textcolor{stringliteral}{"{}-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/\ END\ TEST:\ \%s\ -\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/-\/\(\backslash\)n\(\backslash\)r"{}},\ TEST\_TAG);} -\DoxyCodeLine{00103\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00104\ } -\DoxyCodeLine{00113\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002}{print\_test\_msg}}(\textcolor{keyword}{const}\ \textcolor{keywordtype}{char}*\ TEST\_TAG,\ \textcolor{keyword}{const}\ \textcolor{keywordtype}{char}*\ msg)} -\DoxyCodeLine{00114\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00115\ \ \ \ \ \ \ \ \ \ \ \ \ printf(\textcolor{stringliteral}{"{}\%s:\ \%s:\ \%s\(\backslash\)n\(\backslash\)r"{}},\ \mbox{\hyperlink{class_b_n_o08x_test_helper_aa09d388a5da3a925ac25125b9c5c3a90}{TAG}},\ TEST\_TAG,\ msg);} -\DoxyCodeLine{00116\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00117\ } -\DoxyCodeLine{00125\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a9e2f9bf13f28f1a6ba87e86bc5947cf1}{set\_test\_imu\_cfg}}(\mbox{\hyperlink{structbno08x__config__t}{bno08x\_config\_t}}\ cfg)} -\DoxyCodeLine{00126\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00127\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a008b268f705b9d2925230cb8193c9f28}{imu\_cfg}}\ =\ cfg;} -\DoxyCodeLine{00128\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00129\ } -\DoxyCodeLine{00135\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518}{create\_test\_imu}}()} -\DoxyCodeLine{00136\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00137\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}\ !=\ \textcolor{keyword}{nullptr})} -\DoxyCodeLine{00138\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40}{destroy\_test\_imu}}();} -\DoxyCodeLine{00139\ } -\DoxyCodeLine{00140\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}\ =\ \textcolor{keyword}{new}\ \mbox{\hyperlink{class_b_n_o08x}{BNO08x}}();} -\DoxyCodeLine{00141\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00142\ } -\DoxyCodeLine{00148\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40}{destroy\_test\_imu}}()} -\DoxyCodeLine{00149\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00150\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}\ !=\ \textcolor{keyword}{nullptr})} -\DoxyCodeLine{00151\ \ \ \ \ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00152\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keyword}{delete}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}};} -\DoxyCodeLine{00153\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}\ =\ \textcolor{keyword}{nullptr};} -\DoxyCodeLine{00154\ \ \ \ \ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00155\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00156\ } -\DoxyCodeLine{00162\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \mbox{\hyperlink{class_b_n_o08x}{BNO08x}}*\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b}{get\_test\_imu}}()} -\DoxyCodeLine{00163\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00164\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}};} -\DoxyCodeLine{00165\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00166\ } -\DoxyCodeLine{00172\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d}{call\_init\_config\_args}}()} -\DoxyCodeLine{00173\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00174\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}\ ==\ \textcolor{keyword}{nullptr})} -\DoxyCodeLine{00175\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ ESP\_FAIL;} -\DoxyCodeLine{00176\ } -\DoxyCodeLine{00177\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d}{init\_config\_args}}();} -\DoxyCodeLine{00178\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00179\ } -\DoxyCodeLine{00185\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161}{call\_init\_gpio}}()} -\DoxyCodeLine{00186\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00187\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}\ ==\ \textcolor{keyword}{nullptr})} -\DoxyCodeLine{00188\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ ESP\_FAIL;} -\DoxyCodeLine{00189\ } -\DoxyCodeLine{00190\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10}{init\_gpio}}();} -\DoxyCodeLine{00191\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00192\ } -\DoxyCodeLine{00198\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15}{call\_init\_hint\_isr}}()} -\DoxyCodeLine{00199\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00200\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}\ ==\ \textcolor{keyword}{nullptr})} -\DoxyCodeLine{00201\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ ESP\_FAIL;} -\DoxyCodeLine{00202\ } -\DoxyCodeLine{00203\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61}{init\_hint\_isr}}();} -\DoxyCodeLine{00204\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00205\ } -\DoxyCodeLine{00211\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5}{call\_init\_spi}}()} -\DoxyCodeLine{00212\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00213\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}\ ==\ \textcolor{keyword}{nullptr})} -\DoxyCodeLine{00214\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ ESP\_FAIL;} -\DoxyCodeLine{00215\ } -\DoxyCodeLine{00216\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81}{init\_spi}}();} -\DoxyCodeLine{00217\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00218\ } -\DoxyCodeLine{00224\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ esp\_err\_t\ \mbox{\hyperlink{class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a}{call\_launch\_tasks}}()} -\DoxyCodeLine{00225\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00226\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}\ ==\ \textcolor{keyword}{nullptr})} -\DoxyCodeLine{00227\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ ESP\_FAIL;} -\DoxyCodeLine{00228\ } -\DoxyCodeLine{00229\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be}{launch\_tasks}}();} -\DoxyCodeLine{00230\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00231\ } -\DoxyCodeLine{00240\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd}{rotation\_vector\_data\_is\_new}}(\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}},\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ default\_report\_data)} -\DoxyCodeLine{00241\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00242\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{false};} -\DoxyCodeLine{00243\ } -\DoxyCodeLine{00244\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ prev\ report\ should\ always\ contain\ the\ default\ test\ values\ as\ per\ test\ structure}} -\DoxyCodeLine{00245\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8d2c3cd33943cb1b4fd0e800f822607e}{quat\_I}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8d2c3cd33943cb1b4fd0e800f822607e}{quat\_I}})} -\DoxyCodeLine{00246\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00247\ } -\DoxyCodeLine{00248\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a20a09d197d5128aae64b7449df576c27}{quat\_J}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a20a09d197d5128aae64b7449df576c27}{quat\_J}})} -\DoxyCodeLine{00249\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00250\ } -\DoxyCodeLine{00251\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3c74d4c93fc4390f52b75e6ff2bea95b}{quat\_K}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3c74d4c93fc4390f52b75e6ff2bea95b}{quat\_K}})} -\DoxyCodeLine{00252\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00253\ } -\DoxyCodeLine{00254\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a80525c4943154f825a62539b10337976}{quat\_real}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a80525c4943154f825a62539b10337976}{quat\_real}})} -\DoxyCodeLine{00255\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00256\ } -\DoxyCodeLine{00257\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_aac84ad10b65403ae1ee21dab5cdc77db}{quat\_accuracy}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_aac84ad10b65403ae1ee21dab5cdc77db}{quat\_accuracy}})} -\DoxyCodeLine{00258\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00259\ } -\DoxyCodeLine{00260\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae0a8fef0227dd4304d08466c43d901a5}{quat\_radian\_accuracy}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae0a8fef0227dd4304d08466c43d901a5}{quat\_radian\_accuracy}})} -\DoxyCodeLine{00261\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00262\ } -\DoxyCodeLine{00263\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}};} -\DoxyCodeLine{00264\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00265\ } -\DoxyCodeLine{00274\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6}{gyro\_integrated\_rotation\_vector\_data\_is\_new}}(\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}},\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ default\_report\_data)} -\DoxyCodeLine{00275\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00276\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{false};} -\DoxyCodeLine{00277\ } -\DoxyCodeLine{00278\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8d2c3cd33943cb1b4fd0e800f822607e}{quat\_I}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8d2c3cd33943cb1b4fd0e800f822607e}{quat\_I}})} -\DoxyCodeLine{00279\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00280\ } -\DoxyCodeLine{00281\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a20a09d197d5128aae64b7449df576c27}{quat\_J}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a20a09d197d5128aae64b7449df576c27}{quat\_J}})} -\DoxyCodeLine{00282\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00283\ } -\DoxyCodeLine{00284\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3c74d4c93fc4390f52b75e6ff2bea95b}{quat\_K}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3c74d4c93fc4390f52b75e6ff2bea95b}{quat\_K}})} -\DoxyCodeLine{00285\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00286\ } -\DoxyCodeLine{00287\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a80525c4943154f825a62539b10337976}{quat\_real}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a80525c4943154f825a62539b10337976}{quat\_real}})} -\DoxyCodeLine{00288\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00289\ } -\DoxyCodeLine{00290\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a077a94b4de0b5c280d69611325208cf7}{integrated\_gyro\_vel\_x}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a077a94b4de0b5c280d69611325208cf7}{integrated\_gyro\_vel\_x}})} -\DoxyCodeLine{00291\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00292\ } -\DoxyCodeLine{00293\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af4b75b320bc390c90656905711f1c791}{integrated\_gyro\_vel\_y}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af4b75b320bc390c90656905711f1c791}{integrated\_gyro\_vel\_y}})} -\DoxyCodeLine{00294\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00295\ } -\DoxyCodeLine{00296\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a1aa67da9c3c6449dfce361a528c418d3}{integrated\_gyro\_vel\_z}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a1aa67da9c3c6449dfce361a528c418d3}{integrated\_gyro\_vel\_z}})} -\DoxyCodeLine{00297\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00298\ } -\DoxyCodeLine{00299\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}};} -\DoxyCodeLine{00300\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00301\ } -\DoxyCodeLine{00310\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2}{uncalibrated\_gyro\_data\_is\_new}}(\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}},\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ default\_report\_data)} -\DoxyCodeLine{00311\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00312\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{false};} -\DoxyCodeLine{00313\ } -\DoxyCodeLine{00314\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a292b1c36fed6a9c9742edf730299c4f4}{uncalib\_gyro\_vel\_x}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a292b1c36fed6a9c9742edf730299c4f4}{uncalib\_gyro\_vel\_x}})} -\DoxyCodeLine{00315\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00316\ } -\DoxyCodeLine{00317\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_adfd6bf2e2264cf25bd02814446600ab4}{uncalib\_gyro\_vel\_y}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_adfd6bf2e2264cf25bd02814446600ab4}{uncalib\_gyro\_vel\_y}})} -\DoxyCodeLine{00318\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00319\ } -\DoxyCodeLine{00320\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ab39fd6f409288bb35fb1542ff4b9cbe4}{uncalib\_gyro\_vel\_z}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ab39fd6f409288bb35fb1542ff4b9cbe4}{uncalib\_gyro\_vel\_z}})} -\DoxyCodeLine{00321\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00322\ } -\DoxyCodeLine{00323\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac70a65027c3e740eca2b1f172b7cefa3}{uncalib\_gyro\_drift\_x}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac70a65027c3e740eca2b1f172b7cefa3}{uncalib\_gyro\_drift\_x}})} -\DoxyCodeLine{00324\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00325\ } -\DoxyCodeLine{00326\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a29d5ae3e0ed3463cb9297f9cdc0e8472}{uncalib\_gyro\_drift\_y}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a29d5ae3e0ed3463cb9297f9cdc0e8472}{uncalib\_gyro\_drift\_y}})} -\DoxyCodeLine{00327\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00328\ } -\DoxyCodeLine{00329\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a27b52e2d96cb948c4257de4553053f72}{uncalib\_gyro\_drift\_z}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a27b52e2d96cb948c4257de4553053f72}{uncalib\_gyro\_drift\_z}})} -\DoxyCodeLine{00330\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00331\ } -\DoxyCodeLine{00332\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}};} -\DoxyCodeLine{00333\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00334\ } -\DoxyCodeLine{00343\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9}{calibrated\_gyro\_data\_is\_new}}(\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}},\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ default\_report\_data)} -\DoxyCodeLine{00344\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00345\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{false};} -\DoxyCodeLine{00346\ } -\DoxyCodeLine{00347\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a89b427579a281440ab94a340c0ec8443}{calib\_gyro\_vel\_x}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a89b427579a281440ab94a340c0ec8443}{calib\_gyro\_vel\_x}})} -\DoxyCodeLine{00348\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00349\ } -\DoxyCodeLine{00350\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af9e11fd749123f5723b2e281c8d2fd16}{calib\_gyro\_vel\_y}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af9e11fd749123f5723b2e281c8d2fd16}{calib\_gyro\_vel\_y}})} -\DoxyCodeLine{00351\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00352\ } -\DoxyCodeLine{00353\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a769ddae74a6c89a2d319c28f95ed6479}{calib\_gyro\_vel\_z}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a769ddae74a6c89a2d319c28f95ed6479}{calib\_gyro\_vel\_z}})} -\DoxyCodeLine{00354\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00355\ } -\DoxyCodeLine{00356\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}};} -\DoxyCodeLine{00357\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00358\ } -\DoxyCodeLine{00367\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea}{accelerometer\_data\_is\_new}}(\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}},\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ default\_report\_data)} -\DoxyCodeLine{00368\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00369\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{false};} -\DoxyCodeLine{00370\ } -\DoxyCodeLine{00371\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5c01b349cc9e4e45c78c576882d633fd}{accel\_x}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5c01b349cc9e4e45c78c576882d633fd}{accel\_x}})} -\DoxyCodeLine{00372\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00373\ } -\DoxyCodeLine{00374\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a7e594d0a1e86fb575f72c6f330c8983c}{accel\_y}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a7e594d0a1e86fb575f72c6f330c8983c}{accel\_y}})} -\DoxyCodeLine{00375\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00376\ } -\DoxyCodeLine{00377\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af134cb789c29120033d81916e0c100d4}{accel\_z}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af134cb789c29120033d81916e0c100d4}{accel\_z}})} -\DoxyCodeLine{00378\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00379\ } -\DoxyCodeLine{00380\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac5d393de0f15176ba81bc63a80b49ca3}{accel\_accuracy}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac5d393de0f15176ba81bc63a80b49ca3}{accel\_accuracy}})} -\DoxyCodeLine{00381\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00382\ } -\DoxyCodeLine{00383\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}};} -\DoxyCodeLine{00384\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00385\ } -\DoxyCodeLine{00394\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590}{linear\_accelerometer\_data\_is\_new}}(\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}},\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ default\_report\_data)} -\DoxyCodeLine{00395\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00396\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{false};} -\DoxyCodeLine{00397\ } -\DoxyCodeLine{00398\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3a62ed280657cd409d723e64f0c313b5}{lin\_accel\_x}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3a62ed280657cd409d723e64f0c313b5}{lin\_accel\_x}})} -\DoxyCodeLine{00399\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00400\ } -\DoxyCodeLine{00401\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a553942aa784c35c833543ecc9a05f606}{lin\_accel\_y}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a553942aa784c35c833543ecc9a05f606}{lin\_accel\_y}})} -\DoxyCodeLine{00402\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00403\ } -\DoxyCodeLine{00404\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5bf43fc0daf3a86954924e066cad3a9b}{lin\_accel\_z}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5bf43fc0daf3a86954924e066cad3a9b}{lin\_accel\_z}})} -\DoxyCodeLine{00405\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00406\ } -\DoxyCodeLine{00407\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a48a249994c27f59ca4167b56bdda311a}{lin\_accel\_accuracy}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a48a249994c27f59ca4167b56bdda311a}{lin\_accel\_accuracy}})} -\DoxyCodeLine{00408\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00409\ } -\DoxyCodeLine{00410\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}};} -\DoxyCodeLine{00411\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00412\ } -\DoxyCodeLine{00421\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a}{gravity\_data\_is\_new}}(\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}},\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ default\_report\_data)} -\DoxyCodeLine{00422\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00423\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{false};} -\DoxyCodeLine{00424\ } -\DoxyCodeLine{00425\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ad2c17ea111250ebc1a4a763dae3c072a}{grav\_x}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ad2c17ea111250ebc1a4a763dae3c072a}{grav\_x}})} -\DoxyCodeLine{00426\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00427\ } -\DoxyCodeLine{00428\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a19fc4af8a26c10a027cbd859d67dba4a}{grav\_y}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a19fc4af8a26c10a027cbd859d67dba4a}{grav\_y}})} -\DoxyCodeLine{00429\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00430\ } -\DoxyCodeLine{00431\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af1887bdfef4fc2c683fe2134cb5cfb50}{grav\_z}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af1887bdfef4fc2c683fe2134cb5cfb50}{grav\_z}})} -\DoxyCodeLine{00432\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00433\ } -\DoxyCodeLine{00434\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a735d099f3dd0ead4b8d986fd139af43d}{grav\_accuracy}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a735d099f3dd0ead4b8d986fd139af43d}{grav\_accuracy}})} -\DoxyCodeLine{00435\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00436\ } -\DoxyCodeLine{00437\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}};} -\DoxyCodeLine{00438\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00439\ } -\DoxyCodeLine{00448\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5}{magnetometer\_data\_is\_new}}(\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}},\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ default\_report\_data)} -\DoxyCodeLine{00449\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00450\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{false};} -\DoxyCodeLine{00451\ } -\DoxyCodeLine{00452\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0e72f6dde1411e4aa1c616cedcc556c1}{magf\_x}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0e72f6dde1411e4aa1c616cedcc556c1}{magf\_x}})} -\DoxyCodeLine{00453\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00454\ } -\DoxyCodeLine{00455\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8738f60a2b9bd49d2b8dd0487db7ac97}{magf\_y}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8738f60a2b9bd49d2b8dd0487db7ac97}{magf\_y}})} -\DoxyCodeLine{00456\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00457\ } -\DoxyCodeLine{00458\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a55187ebe06fa77def93681bcdf62595c}{magf\_z}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a55187ebe06fa77def93681bcdf62595c}{magf\_z}})} -\DoxyCodeLine{00459\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00460\ } -\DoxyCodeLine{00461\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0c962609a3bf7927204542521e9c5113}{magf\_accuracy}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0c962609a3bf7927204542521e9c5113}{magf\_accuracy}})} -\DoxyCodeLine{00462\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00463\ } -\DoxyCodeLine{00464\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}};} -\DoxyCodeLine{00465\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00466\ } -\DoxyCodeLine{00475\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782}{step\_counter\_data\_is\_new}}(\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}},\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ default\_report\_data)} -\DoxyCodeLine{00476\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00477\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{false};} -\DoxyCodeLine{00478\ } -\DoxyCodeLine{00479\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae8435a931eac7f4376a94acfcbf6a784}{step\_count}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae8435a931eac7f4376a94acfcbf6a784}{step\_count}})} -\DoxyCodeLine{00480\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00481\ } -\DoxyCodeLine{00482\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}};} -\DoxyCodeLine{00483\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00484\ } -\DoxyCodeLine{00493\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3}{stability\_classifier\_data\_is\_new}}(\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}},\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ default\_report\_data)} -\DoxyCodeLine{00494\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00495\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{false};} -\DoxyCodeLine{00496\ } -\DoxyCodeLine{00497\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a86473c2bd8cbe2c76276393ee20d568b}{stability\_classifier}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a86473c2bd8cbe2c76276393ee20d568b}{stability\_classifier}})} -\DoxyCodeLine{00498\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00499\ } -\DoxyCodeLine{00500\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}};} -\DoxyCodeLine{00501\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00502\ } -\DoxyCodeLine{00511\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9}{activity\_classifier\_data\_is\_new}}(\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}},\ \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ default\_report\_data)} -\DoxyCodeLine{00512\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00513\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{false};} -\DoxyCodeLine{00514\ } -\DoxyCodeLine{00515\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0455033deba9570f248e8059cf6a3ce1}{activity\_classifier}}\ !=\ default\_report\_data-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0455033deba9570f248e8059cf6a3ce1}{activity\_classifier}})} -\DoxyCodeLine{00516\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}}\ =\ \textcolor{keyword}{true};} -\DoxyCodeLine{00517\ } -\DoxyCodeLine{00518\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\_data}};} -\DoxyCodeLine{00519\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00520\ } -\DoxyCodeLine{00528\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2}{update\_report\_data}}(\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\_report\_data\_t}}*\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}})} -\DoxyCodeLine{00529\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00530\ } -\DoxyCodeLine{00531\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a}{get\_quat}}(\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8d2c3cd33943cb1b4fd0e800f822607e}{quat\_I}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a20a09d197d5128aae64b7449df576c27}{quat\_J}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3c74d4c93fc4390f52b75e6ff2bea95b}{quat\_K}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a80525c4943154f825a62539b10337976}{quat\_real}},} -\DoxyCodeLine{00532\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae0a8fef0227dd4304d08466c43d901a5}{quat\_radian\_accuracy}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_aac84ad10b65403ae1ee21dab5cdc77db}{quat\_accuracy}});} -\DoxyCodeLine{00533\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f}{get\_integrated\_gyro\_velocity}}(} -\DoxyCodeLine{00534\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a077a94b4de0b5c280d69611325208cf7}{integrated\_gyro\_vel\_x}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af4b75b320bc390c90656905711f1c791}{integrated\_gyro\_vel\_y}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a1aa67da9c3c6449dfce361a528c418d3}{integrated\_gyro\_vel\_z}});} -\DoxyCodeLine{00535\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885}{get\_accel}}(\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5c01b349cc9e4e45c78c576882d633fd}{accel\_x}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a7e594d0a1e86fb575f72c6f330c8983c}{accel\_y}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af134cb789c29120033d81916e0c100d4}{accel\_z}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac5d393de0f15176ba81bc63a80b49ca3}{accel\_accuracy}});} -\DoxyCodeLine{00536\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46}{get\_linear\_accel}}(\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3a62ed280657cd409d723e64f0c313b5}{lin\_accel\_x}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a553942aa784c35c833543ecc9a05f606}{lin\_accel\_y}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5bf43fc0daf3a86954924e066cad3a9b}{lin\_accel\_z}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a48a249994c27f59ca4167b56bdda311a}{lin\_accel\_accuracy}});} -\DoxyCodeLine{00537\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a067678914e928a6691625b17c40237a0}{get\_gravity}}(\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ad2c17ea111250ebc1a4a763dae3c072a}{grav\_x}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a19fc4af8a26c10a027cbd859d67dba4a}{grav\_y}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af1887bdfef4fc2c683fe2134cb5cfb50}{grav\_z}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a735d099f3dd0ead4b8d986fd139af43d}{grav\_accuracy}});} -\DoxyCodeLine{00538\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f}{get\_calibrated\_gyro\_velocity}}(\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a89b427579a281440ab94a340c0ec8443}{calib\_gyro\_vel\_x}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af9e11fd749123f5723b2e281c8d2fd16}{calib\_gyro\_vel\_y}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a769ddae74a6c89a2d319c28f95ed6479}{calib\_gyro\_vel\_z}});} -\DoxyCodeLine{00539\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104}{get\_uncalibrated\_gyro\_velocity}}(\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a292b1c36fed6a9c9742edf730299c4f4}{uncalib\_gyro\_vel\_x}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_adfd6bf2e2264cf25bd02814446600ab4}{uncalib\_gyro\_vel\_y}},} -\DoxyCodeLine{00540\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ab39fd6f409288bb35fb1542ff4b9cbe4}{uncalib\_gyro\_vel\_z}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac70a65027c3e740eca2b1f172b7cefa3}{uncalib\_gyro\_drift\_x}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a29d5ae3e0ed3463cb9297f9cdc0e8472}{uncalib\_gyro\_drift\_y}},} -\DoxyCodeLine{00541\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a27b52e2d96cb948c4257de4553053f72}{uncalib\_gyro\_drift\_z}});} -\DoxyCodeLine{00542\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb}{get\_magf}}(\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0e72f6dde1411e4aa1c616cedcc556c1}{magf\_x}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8738f60a2b9bd49d2b8dd0487db7ac97}{magf\_y}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a55187ebe06fa77def93681bcdf62595c}{magf\_z}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0c962609a3bf7927204542521e9c5113}{magf\_accuracy}});} -\DoxyCodeLine{00543\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27}{get\_raw\_mems\_gyro}}(\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a94befe7132d3a6a6ce2a7890e96ec091}{raw\_mems\_gyro\_x}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a7e9cd7e43d70932c5f84e3cfadf8bb47}{raw\_mems\_gyro\_y}},\ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a9df84179bd44a7febfa1058afe3dad6c}{raw\_mems\_gyro\_z}});} -\DoxyCodeLine{00544\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae8435a931eac7f4376a94acfcbf6a784}{step\_count}}\ =\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef}{get\_step\_count}}();} -\DoxyCodeLine{00545\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a86473c2bd8cbe2c76276393ee20d568b}{stability\_classifier}}\ =\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a248544b262582d10d917a687190cb454}{get\_stability\_classifier}}();} -\DoxyCodeLine{00546\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\_data}}-\/>\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0455033deba9570f248e8059cf6a3ce1}{activity\_classifier}}\ =\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed}{get\_activity\_classifier}}();} -\DoxyCodeLine{00547\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00548\ } -\DoxyCodeLine{00554\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528}{reset\_all\_imu\_data\_to\_test\_defaults}}()} -\DoxyCodeLine{00555\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00556\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint16\_t\ TEST\_VAL\_UINT16\ =\ 65535U;} -\DoxyCodeLine{00557\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint16\_t\ TEST\_VAL\_UINT8\ =\ 255;} -\DoxyCodeLine{00558\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_abc972db20affbd0040b4e6c4892dd57b}{time\_stamp}}\ =\ 0UL;} -\DoxyCodeLine{00559\ } -\DoxyCodeLine{00560\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a75fb2f06c5bbe26e3f3c794934ef954c}{raw\_accel\_X}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00561\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ab56e2ba505fa293d03e955137625c562}{raw\_accel\_Y}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00562\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_af254d245b368027df6952b7d7522bd35}{raw\_accel\_Z}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00563\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a3365b7ebde01e284274e655c60343df9}{accel\_accuracy}}\ =\ \textcolor{keyword}{static\_cast<}uint16\_t\textcolor{keyword}{>}(\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}{BNO08xAccuracy::UNDEFINED}});} -\DoxyCodeLine{00564\ } -\DoxyCodeLine{00565\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ae1f71a432cb15e75f522fa18f29f4d50}{raw\_lin\_accel\_X}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00566\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_aff3a5590471d1c9fc485a5610433915f}{raw\_lin\_accel\_Y}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00567\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_abc8add47f1babc66c812a015614143d3}{raw\_lin\_accel\_Z}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00568\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a35e1635ef5edde8fc8640f978c6f2e3c}{accel\_lin\_accuracy}}\ =\ \textcolor{keyword}{static\_cast<}uint16\_t\textcolor{keyword}{>}(\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}{BNO08xAccuracy::UNDEFINED}});} -\DoxyCodeLine{00569\ } -\DoxyCodeLine{00570\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a87faca2c8c71ff46bf2e6ad4ba271b3a}{raw\_calib\_gyro\_X}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00571\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a66c48af1d4162a9ec25c3a1c95660fe4}{raw\_calib\_gyro\_Y}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00572\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_af5450d1a9c20c2a5c62c960e3df11c0e}{raw\_calib\_gyro\_Z}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00573\ } -\DoxyCodeLine{00574\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ reset\ quaternion\ to\ nan}} -\DoxyCodeLine{00575\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a69dc7e97875060213085ba964b3bd987}{raw\_quat\_I}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00576\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a61ae05dc5572b326541bf8099f0c2a54}{raw\_quat\_J}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00577\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a7720c44ed1c0f1a0663d2adc5e1a1ea1}{raw\_quat\_K}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00578\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a867354267253ae828be4fae15c062db3}{raw\_quat\_real}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00579\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a033d6cb1aa137743b69cc3e401df67b7}{raw\_quat\_radian\_accuracy}}\ =\ \textcolor{keyword}{static\_cast<}uint16\_t\textcolor{keyword}{>}(\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}{BNO08xAccuracy::UNDEFINED}});} -\DoxyCodeLine{00580\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a36223f7124751fa71e860b2ef55dd2ac}{quat\_accuracy}}\ =\ \textcolor{keyword}{static\_cast<}uint16\_t\textcolor{keyword}{>}(\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}{BNO08xAccuracy::UNDEFINED}});} -\DoxyCodeLine{00581\ } -\DoxyCodeLine{00582\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a6537ed69245cf71cad6a6a44480dddaa}{integrated\_gyro\_velocity\_X}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00583\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a00b39e22ea9fe306e88aaed490ee0a51}{integrated\_gyro\_velocity\_Y}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00584\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ad112beb64badd22a2e1d717e1ee921c8}{integrated\_gyro\_velocity\_Z}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00585\ } -\DoxyCodeLine{00586\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_af45016be9ea523d80be8467b2907b499}{gravity\_X}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00587\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_af20dcd487a9fe8fa6243817d51e37be5}{gravity\_Y}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00588\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_afa1cf5c3afbb258d97c55c5fb187f2d6}{gravity\_Z}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00589\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ae01698d287ea999179a11e2244902022}{gravity\_accuracy}}\ =\ \textcolor{keyword}{static\_cast<}uint16\_t\textcolor{keyword}{>}(\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}{BNO08xAccuracy::UNDEFINED}});} -\DoxyCodeLine{00590\ } -\DoxyCodeLine{00591\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_afdc5cdb65bd0b36528b5b671b9d27053}{raw\_uncalib\_gyro\_X}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00592\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_acc2c66e2985975266a286385ea855117}{raw\_uncalib\_gyro\_Y}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00593\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_afac9dd4161f4c0051255293680c9082b}{raw\_uncalib\_gyro\_Z}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00594\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a8a2667f668317cee0a9fc4ef0accc3f5}{raw\_bias\_X}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00595\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ac38ff5eb93d3c3db0af2504ba02fd93c}{raw\_bias\_Y}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00596\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a0968eaed9b3d979a2caa1aba6e6b417a}{raw\_bias\_Z}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00597\ } -\DoxyCodeLine{00598\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_aa5bdf740161b7c37adcac0154a410118}{raw\_magf\_X}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00599\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_acd365418f24a6da61122c66d82086639}{raw\_magf\_Y}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00600\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ab4862de31d0874b44b6745678e1c905e}{raw\_magf\_Z}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00601\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ac5d4e151690774687efa951ca41c16ae}{magf\_accuracy}}\ =\ \textcolor{keyword}{static\_cast<}uint16\_t\textcolor{keyword}{>}(\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}{BNO08xAccuracy::UNDEFINED}});} -\DoxyCodeLine{00602\ } -\DoxyCodeLine{00603\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a1171a5738a4e6831ec7fa32a29f15554}{tap\_detector}}\ =\ TEST\_VAL\_UINT8;} -\DoxyCodeLine{00604\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ad80a77973371b12d722ea39063c648be}{step\_count}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00605\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a1b12471e92536a79d0c425d77676f2e1}{stability\_classifier}}\ =\ \textcolor{keyword}{static\_cast<}uint16\_t\textcolor{keyword}{>}(\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3}{BNO08xStability::UNDEFINED}});} -\DoxyCodeLine{00606\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a75cea49c1c08ca28d9fa7e5ed61c6e7b}{activity\_classifier}}\ =\ \textcolor{keyword}{static\_cast<}uint16\_t\textcolor{keyword}{>}(\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3}{BNO08xActivity::UNDEFINED}});} -\DoxyCodeLine{00607\ } -\DoxyCodeLine{00608\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a937cbdc4edaac72c8cad041d79de5701}{mems\_raw\_accel\_X}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00609\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ad83cecb8a5d2be01db6792755b6057e9}{mems\_raw\_accel\_Y}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00610\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a59a4d75f1302ab693b1b26e9ccaa5341}{mems\_raw\_accel\_Z}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00611\ } -\DoxyCodeLine{00612\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a3d6b6257462951ea023af7076c80f6dd}{mems\_raw\_gyro\_X}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00613\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ab6b142416912a096886dd63ad0beb865}{mems\_raw\_gyro\_Y}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00614\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ac35d5b12721ab876eaeb1f714a9b3b1d}{mems\_raw\_gyro\_Z}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00615\ } -\DoxyCodeLine{00616\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_ab587cdf991342b69b7fff3b33f537eb5}{mems\_raw\_magf\_X}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00617\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_aad926054c81818fff611e10ed913706a}{mems\_raw\_magf\_Y}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00618\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\_imu}}-\/>\mbox{\hyperlink{class_b_n_o08x_a90f0cdf11decc276006f76a494d42ce3}{mems\_raw\_magf\_Z}}\ =\ TEST\_VAL\_UINT16;} -\DoxyCodeLine{00619\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00620\ } -\DoxyCodeLine{00628\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keywordtype}{char}*\ \mbox{\hyperlink{class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3}{BNO08xAccuracy\_to\_str}}(\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08xAccuracy}}\ accuracy)} -\DoxyCodeLine{00629\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00630\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{switch}\ (accuracy)} -\DoxyCodeLine{00631\ \ \ \ \ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00632\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88}{BNO08xAccuracy::LOW}}:} -\DoxyCodeLine{00633\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}LOW"{}};} -\DoxyCodeLine{00634\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c}{BNO08xAccuracy::MED}}:} -\DoxyCodeLine{00635\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}MED"{}};} -\DoxyCodeLine{00636\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c}{BNO08xAccuracy::HIGH}}:} -\DoxyCodeLine{00637\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}HIGH"{}};} -\DoxyCodeLine{00638\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3}{BNO08xAccuracy::UNDEFINED}}:} -\DoxyCodeLine{00639\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}UNDEFINED"{}};} -\DoxyCodeLine{00640\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{default}:} -\DoxyCodeLine{00641\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}INVALID"{}};} -\DoxyCodeLine{00642\ \ \ \ \ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00643\ \ \ \ \ \ \ \ \ \};} -\DoxyCodeLine{00644\ } -\DoxyCodeLine{00652\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keywordtype}{char}*\ \mbox{\hyperlink{class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059}{BNO08xStability\_to\_str}}(\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}{BNO08xStability}}\ stability)} -\DoxyCodeLine{00653\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00654\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{switch}\ (stability)} -\DoxyCodeLine{00655\ \ \ \ \ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00656\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3}{BNO08xStability::UNKNOWN}}:} -\DoxyCodeLine{00657\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}UNKNOWN"{}};} -\DoxyCodeLine{00658\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a}{BNO08xStability::ON\_TABLE}}:} -\DoxyCodeLine{00659\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}ON\ TABLE"{}};} -\DoxyCodeLine{00660\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146}{BNO08xStability::STATIONARY}}:} -\DoxyCodeLine{00661\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}STATIONARY"{}};} -\DoxyCodeLine{00662\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3}{BNO08xStability::UNDEFINED}}:} -\DoxyCodeLine{00663\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}UNDEFINED"{}};} -\DoxyCodeLine{00664\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{default}:} -\DoxyCodeLine{00665\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}INVALID"{}};} -\DoxyCodeLine{00666\ \ \ \ \ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00667\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00668\ } -\DoxyCodeLine{00676\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keywordtype}{char}*\ \mbox{\hyperlink{class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750}{BNO08xActivity\_to\_str}}(\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}{BNO08xActivity}}\ activity)} -\DoxyCodeLine{00677\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00678\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{switch}\ (activity)} -\DoxyCodeLine{00679\ \ \ \ \ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00680\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3}{BNO08xActivity::UNKNOWN}}:} -\DoxyCodeLine{00681\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}UNKNOWN"{}};} -\DoxyCodeLine{00682\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4}{BNO08xActivity::IN\_VEHICLE}}:} -\DoxyCodeLine{00683\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}IN\ VEHICLE"{}};} -\DoxyCodeLine{00684\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4}{BNO08xActivity::ON\_BICYCLE}}:} -\DoxyCodeLine{00685\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}ON\ BICYCLE"{}};} -\DoxyCodeLine{00686\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58}{BNO08xActivity::ON\_FOOT}}:} -\DoxyCodeLine{00687\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}ON\ FOOT"{}};} -\DoxyCodeLine{00688\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6}{BNO08xActivity::STILL}}:} -\DoxyCodeLine{00689\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}STILL"{}};} -\DoxyCodeLine{00690\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c}{BNO08xActivity::TILTING}}:} -\DoxyCodeLine{00691\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}TILTING"{}};} -\DoxyCodeLine{00692\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3}{BNO08xActivity::WALKING}}:} -\DoxyCodeLine{00693\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}WALKING"{}};} -\DoxyCodeLine{00694\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd}{BNO08xActivity::RUNNING}}:} -\DoxyCodeLine{00695\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}RUNNING"{}};} -\DoxyCodeLine{00696\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515}{BNO08xActivity::ON\_STAIRS}}:} -\DoxyCodeLine{00697\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}ON\ STAIRS"{}};} -\DoxyCodeLine{00698\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{case}\ \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3}{BNO08xActivity::UNDEFINED}}:} -\DoxyCodeLine{00699\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}UNDEFINED"{}};} -\DoxyCodeLine{00700\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{default}:} -\DoxyCodeLine{00701\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{return}\ \textcolor{stringliteral}{"{}INVALID"{}};} -\DoxyCodeLine{00702\ \ \ \ \ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00703\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00704\ \};} - -\end{DoxyCode} diff --git a/documentation/latex/_b_n_o08x_test_suite_8hpp.tex b/documentation/latex/_b_n_o08x_test_suite_8hpp.tex deleted file mode 100644 index 8a29091..0000000 --- a/documentation/latex/_b_n_o08x_test_suite_8hpp.tex +++ /dev/null @@ -1,28 +0,0 @@ -\doxysection{BNO08x\+Test\+Suite.\+hpp File Reference} -\hypertarget{_b_n_o08x_test_suite_8hpp}{}\label{_b_n_o08x_test_suite_8hpp}\index{BNO08xTestSuite.hpp@{BNO08xTestSuite.hpp}} -{\ttfamily \#include $<$stdio.\+h$>$}\newline -{\ttfamily \#include $<$string.\+h$>$}\newline -{\ttfamily \#include "{}unity.\+h"{}}\newline -{\ttfamily \#include "{}BNO08x\+Test\+Helper.\+hpp"{}}\newline -Include dependency graph for BNO08x\+Test\+Suite.\+hpp\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_b_n_o08x_test_suite_8hpp__incl} -\end{center} -\end{figure} -\doxysubsubsection*{Classes} -\begin{DoxyCompactItemize} -\item -class \mbox{\hyperlink{class_b_n_o08x_test_suite}{BNO08x\+Test\+Suite}} -\begin{DoxyCompactList}\small\item\em \doxylink{class_b_n_o08x}{BNO08x} unit test launch point class. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -\begin{DoxyAuthor}{Author} -Myles Parfeniuk -\end{DoxyAuthor} -\begin{DoxyWarning}{Warning} -YOU MUST ADD THE FOLLOWING LINE TO YOUR MAIN PROJECTS CMake\+Lists.\+txt IN ORDER FOR THIS TEST SUITE TO BE BUILT WITH PROJECT\+: set(TEST\+\_\+\+COMPONENTS "{}esp32\+\_\+\+BNO08x"{} CACHE STRING "{}\+Components to test."{}) -\end{DoxyWarning} diff --git a/documentation/latex/_b_n_o08x_test_suite_8hpp__incl.md5 b/documentation/latex/_b_n_o08x_test_suite_8hpp__incl.md5 deleted file mode 100644 index 6c9abaf..0000000 --- a/documentation/latex/_b_n_o08x_test_suite_8hpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -121105176b45b672e5a53b10e3f9dc05 \ No newline at end of file diff --git a/documentation/latex/_b_n_o08x_test_suite_8hpp__incl.pdf b/documentation/latex/_b_n_o08x_test_suite_8hpp__incl.pdf deleted file mode 100644 index 021c1d3..0000000 Binary files a/documentation/latex/_b_n_o08x_test_suite_8hpp__incl.pdf and /dev/null differ diff --git a/documentation/latex/_b_n_o08x_test_suite_8hpp_source.tex b/documentation/latex/_b_n_o08x_test_suite_8hpp_source.tex deleted file mode 100644 index 889b3e5..0000000 --- a/documentation/latex/_b_n_o08x_test_suite_8hpp_source.tex +++ /dev/null @@ -1,99 +0,0 @@ -\doxysection{BNO08x\+Test\+Suite.\+hpp} -\hypertarget{_b_n_o08x_test_suite_8hpp_source}{}\label{_b_n_o08x_test_suite_8hpp_source}\index{BNO08xTestSuite.hpp@{BNO08xTestSuite.hpp}} -\mbox{\hyperlink{_b_n_o08x_test_suite_8hpp}{Go to the documentation of this file.}} -\begin{DoxyCode}{0} -\DoxyCodeLine{00001\ } -\DoxyCodeLine{00009\ \textcolor{preprocessor}{\#pragma\ once}} -\DoxyCodeLine{00010\ } -\DoxyCodeLine{00011\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00012\ \textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{00013\ \textcolor{preprocessor}{\#include\ "{}unity.h"{}}} -\DoxyCodeLine{00014\ \textcolor{preprocessor}{\#include\ "{}\mbox{\hyperlink{_b_n_o08x_test_helper_8hpp}{BNO08xTestHelper.hpp}}"{}}} -\DoxyCodeLine{00015\ } -\DoxyCodeLine{00021\ \textcolor{keyword}{class\ }\mbox{\hyperlink{class_b_n_o08x_test_suite}{BNO08xTestSuite}}} -\DoxyCodeLine{00022\ \{} -\DoxyCodeLine{00023\ \ \ \ \ \textcolor{keyword}{private}:} -\DoxyCodeLine{00024\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085}{print\_begin\_tests\_banner}}(\textcolor{keyword}{const}\ \textcolor{keywordtype}{char}*\ test\_set\_name)} -\DoxyCodeLine{00025\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00026\ \ \ \ \ \ \ \ \ \ \ \ \ printf(\textcolor{stringliteral}{"{}\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\ BEGIN\ TESTS:\ \%s\ \#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\(\backslash\)n\(\backslash\)r"{}},\ test\_set\_name);} -\DoxyCodeLine{00027\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00028\ } -\DoxyCodeLine{00029\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb}{print\_end\_tests\_banner}}(\textcolor{keyword}{const}\ \textcolor{keywordtype}{char}*\ test\_set\_name)} -\DoxyCodeLine{00030\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00031\ \ \ \ \ \ \ \ \ \ \ \ \ printf(\textcolor{stringliteral}{"{}\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\ END\ TESTS:\ \%s\ \#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\#\(\backslash\)n\(\backslash\)r"{}},\ test\_set\_name);} -\DoxyCodeLine{00032\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00033\ } -\DoxyCodeLine{00034\ \ \ \ \ \textcolor{keyword}{public}:} -\DoxyCodeLine{00035\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd}{run\_all\_tests}}()} -\DoxyCodeLine{00036\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00037\ \ \ \ \ \ \ \ \ \ \ \ \ UNITY\_BEGIN();} -\DoxyCodeLine{00038\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16}{run\_init\_deinit\_tests}}(\textcolor{keyword}{false});} -\DoxyCodeLine{00039\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb}{run\_single\_report\_tests}}(\textcolor{keyword}{false});} -\DoxyCodeLine{00040\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5}{run\_multi\_report\_tests}}(\textcolor{keyword}{false});} -\DoxyCodeLine{00041\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8}{run\_callback\_tests}}(\textcolor{keyword}{false});} -\DoxyCodeLine{00042\ \ \ \ \ \ \ \ \ \ \ \ \ UNITY\_END();} -\DoxyCodeLine{00043\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00044\ } -\DoxyCodeLine{00045\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16}{run\_init\_deinit\_tests}}(\textcolor{keywordtype}{bool}\ call\_unity\_end\_begin\ =\ \textcolor{keyword}{true})} -\DoxyCodeLine{00046\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00047\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085}{print\_begin\_tests\_banner}}(\textcolor{stringliteral}{"{}init\_denit\_tests"{}});} -\DoxyCodeLine{00048\ } -\DoxyCodeLine{00049\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (call\_unity\_end\_begin)} -\DoxyCodeLine{00050\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ UNITY\_BEGIN();} -\DoxyCodeLine{00051\ } -\DoxyCodeLine{00052\ \ \ \ \ \ \ \ \ \ \ \ \ unity\_run\_tests\_by\_tag(\textcolor{stringliteral}{"{}[InitComprehensive]"{}},\ \textcolor{keyword}{false});} -\DoxyCodeLine{00053\ \ \ \ \ \ \ \ \ \ \ \ \ unity\_run\_tests\_by\_tag(\textcolor{stringliteral}{"{}[InitDenit]"{}},\ \textcolor{keyword}{false});} -\DoxyCodeLine{00054\ } -\DoxyCodeLine{00055\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (call\_unity\_end\_begin)} -\DoxyCodeLine{00056\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ UNITY\_END();} -\DoxyCodeLine{00057\ } -\DoxyCodeLine{00058\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb}{print\_end\_tests\_banner}}(\textcolor{stringliteral}{"{}init\_denit\_tests"{}});} -\DoxyCodeLine{00059\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00060\ } -\DoxyCodeLine{00061\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb}{run\_single\_report\_tests}}(\textcolor{keywordtype}{bool}\ call\_unity\_end\_begin\ =\ \textcolor{keyword}{true})} -\DoxyCodeLine{00062\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00063\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085}{print\_begin\_tests\_banner}}(\textcolor{stringliteral}{"{}single\_report\_tests"{}});} -\DoxyCodeLine{00064\ } -\DoxyCodeLine{00065\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (call\_unity\_end\_begin)} -\DoxyCodeLine{00066\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ UNITY\_BEGIN();} -\DoxyCodeLine{00067\ } -\DoxyCodeLine{00068\ \ \ \ \ \ \ \ \ \ \ \ \ unity\_run\_tests\_by\_tag(\textcolor{stringliteral}{"{}[SingleReportEnableDisable]"{}},\ \textcolor{keyword}{false});} -\DoxyCodeLine{00069\ } -\DoxyCodeLine{00070\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (call\_unity\_end\_begin)} -\DoxyCodeLine{00071\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ UNITY\_END();} -\DoxyCodeLine{00072\ } -\DoxyCodeLine{00073\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb}{print\_end\_tests\_banner}}(\textcolor{stringliteral}{"{}single\_report\_tests"{}});} -\DoxyCodeLine{00074\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00075\ } -\DoxyCodeLine{00076\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5}{run\_multi\_report\_tests}}(\textcolor{keywordtype}{bool}\ call\_unity\_end\_begin\ =\ \textcolor{keyword}{true})} -\DoxyCodeLine{00077\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00078\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085}{print\_begin\_tests\_banner}}(\textcolor{stringliteral}{"{}multi\_report\_tests"{}});} -\DoxyCodeLine{00079\ } -\DoxyCodeLine{00080\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (call\_unity\_end\_begin)} -\DoxyCodeLine{00081\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ UNITY\_BEGIN();} -\DoxyCodeLine{00082\ } -\DoxyCodeLine{00083\ \ \ \ \ \ \ \ \ \ \ \ \ unity\_run\_tests\_by\_tag(\textcolor{stringliteral}{"{}[MultiReportEnableDisable]"{}},\ \textcolor{keyword}{false});} -\DoxyCodeLine{00084\ } -\DoxyCodeLine{00085\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (call\_unity\_end\_begin)} -\DoxyCodeLine{00086\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ UNITY\_END();} -\DoxyCodeLine{00087\ } -\DoxyCodeLine{00088\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb}{print\_end\_tests\_banner}}(\textcolor{stringliteral}{"{}multi\_report\_tests"{}});} -\DoxyCodeLine{00089\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00090\ } -\DoxyCodeLine{00091\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ \mbox{\hyperlink{class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8}{run\_callback\_tests}}(\textcolor{keywordtype}{bool}\ call\_unity\_end\_begin\ =\ \textcolor{keyword}{true})} -\DoxyCodeLine{00092\ \ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{00093\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085}{print\_begin\_tests\_banner}}(\textcolor{stringliteral}{"{}run\_callback\_tests"{}});} -\DoxyCodeLine{00094\ } -\DoxyCodeLine{00095\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (call\_unity\_end\_begin)} -\DoxyCodeLine{00096\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ UNITY\_BEGIN();} -\DoxyCodeLine{00097\ } -\DoxyCodeLine{00098\ \ \ \ \ \ \ \ \ \ \ \ \ unity\_run\_tests\_by\_tag(\textcolor{stringliteral}{"{}[CallbackTests]"{}},\ \textcolor{keyword}{false});} -\DoxyCodeLine{00099\ } -\DoxyCodeLine{00100\ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}\ (call\_unity\_end\_begin)} -\DoxyCodeLine{00101\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ UNITY\_END();} -\DoxyCodeLine{00102\ } -\DoxyCodeLine{00103\ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb}{print\_end\_tests\_banner}}(\textcolor{stringliteral}{"{}run\_callback\_tests"{}});} -\DoxyCodeLine{00104\ \ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{00105\ \};} - -\end{DoxyCode} diff --git a/documentation/latex/_callback_tests_8cpp.tex b/documentation/latex/_callback_tests_8cpp.tex deleted file mode 100644 index 6327f47..0000000 --- a/documentation/latex/_callback_tests_8cpp.tex +++ /dev/null @@ -1,232 +0,0 @@ -\doxysection{Callback\+Tests.\+cpp File Reference} -\hypertarget{_callback_tests_8cpp}{}\label{_callback_tests_8cpp}\index{CallbackTests.cpp@{CallbackTests.cpp}} -{\ttfamily \#include "{}unity.\+h"{}}\newline -{\ttfamily \#include "{}../include/\+BNO08x\+Test\+Helper.\+hpp"{}}\newline -Include dependency graph for Callback\+Tests.\+cpp\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_callback_tests_8cpp__incl} -\end{center} -\end{figure} -\doxysubsubsection*{Functions} -\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa}{TEST\+\_\+\+CASE}} ("{}BNO08x Driver Creation \mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} \mbox{[}Callback\+Tests\mbox{]} Tests"{}, "{}\mbox{[}Callback\+Tests\mbox{]}"{}) -\item -\mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} \mbox{\hyperlink{_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573}{register\+\_\+cb}} (\mbox{[}\&\mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a8c57d66969fed0b55bdee9b57f6ed0a7}{prev\+\_\+report\+\_\+data}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}}\mbox{]}() \{ static int cb\+\_\+execution\+\_\+cnt=0;cb\+\_\+execution\+\_\+cnt++;\mbox{\hyperlink{class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2}{BNO08x\+Test\+Helper\+::update\+\_\+report\+\_\+data}}(\&\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}});if(\mbox{\hyperlink{class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea}{BNO08x\+Test\+Helper\+::accelerometer\+\_\+data\+\_\+is\+\_\+new}}(\&\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a8c57d66969fed0b55bdee9b57f6ed0a7}{prev\+\_\+report\+\_\+data}})) \{ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}}=true;sprintf(\mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}}, "{}Rx Data Trial \%d Success\+: Angular\+Accel\+: a\+X\+: \%.\+2lf accel a\+Y\+: \%.\+2lf accel a\+Z\+: "{} "{}\%.\+2lf Accuracy \%s"{}, cb\+\_\+execution\+\_\+cnt, report\+\_\+data.\+accel\+\_\+x, report\+\_\+data.\+accel\+\_\+y, report\+\_\+data.\+accel\+\_\+z, \mbox{\hyperlink{class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3}{BNO08x\+Test\+Helper\+::\+BNO08x\+Accuracy\+\_\+to\+\_\+str}}(report\+\_\+data.\+accel\+\_\+accuracy));\mbox{\hyperlink{class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002}{BNO08x\+Test\+Helper\+::print\+\_\+test\+\_\+msg}}(TEST\+\_\+\+TAG, \mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}});\} \}) -\item -\mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} \mbox{\hyperlink{_callback_tests_8cpp_a0f2cacda77ab92640f739aca52b1f99f}{enable\+\_\+accelerometer}} (\mbox{\hyperlink{_callback_tests_8cpp_a4b80e39a1f48d801615a1f7baa210071}{REPORT\+\_\+\+PERIOD}}) -\item -\mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} (int i=0;i$<$ \mbox{\hyperlink{_callback_tests_8cpp_a20cd776c25ed6d39b2dcb95d155cfbda}{RX\+\_\+\+REPORT\+\_\+\+TRIAL\+\_\+\+CNT}};i++) -\item -\mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} \mbox{\hyperlink{_callback_tests_8cpp_a79547a2396efd083faeba3e54d94360d}{disable\+\_\+accelerometer}} () -\item -\mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} \mbox{\hyperlink{_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73}{register\+\_\+cb}} (\mbox{[}\&\mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a8c57d66969fed0b55bdee9b57f6ed0a7}{prev\+\_\+report\+\_\+data}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}}\mbox{]}() \{ static int cb\+\_\+execution\+\_\+cnt=0;cb\+\_\+execution\+\_\+cnt++;\mbox{\hyperlink{class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2}{BNO08x\+Test\+Helper\+::update\+\_\+report\+\_\+data}}(\&\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}});if(\mbox{\hyperlink{class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea}{BNO08x\+Test\+Helper\+::accelerometer\+\_\+data\+\_\+is\+\_\+new}}(\&\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a8c57d66969fed0b55bdee9b57f6ed0a7}{prev\+\_\+report\+\_\+data}})) \{ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}}\mbox{[}0\mbox{]}=true;sprintf(\mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}}, "{}Rx Data Trial \%d Success\+: Angular\+Accel\+: a\+X\+: \%.\+2lf accel a\+Y\+: \%.\+2lf accel a\+Z\+: "{} "{}\%.\+2lf Accuracy \%s"{}, cb\+\_\+execution\+\_\+cnt, report\+\_\+data.\+accel\+\_\+x, report\+\_\+data.\+accel\+\_\+y, report\+\_\+data.\+accel\+\_\+z, \mbox{\hyperlink{class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3}{BNO08x\+Test\+Helper\+::\+BNO08x\+Accuracy\+\_\+to\+\_\+str}}(report\+\_\+data.\+accel\+\_\+accuracy));\mbox{\hyperlink{class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002}{BNO08x\+Test\+Helper\+::print\+\_\+test\+\_\+msg}}(TEST\+\_\+\+TAG, \mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}});\} if(\mbox{\hyperlink{class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590}{BNO08x\+Test\+Helper\+::linear\+\_\+accelerometer\+\_\+data\+\_\+is\+\_\+new}}(\&\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a8c57d66969fed0b55bdee9b57f6ed0a7}{prev\+\_\+report\+\_\+data}})) \{ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}}\mbox{[}1\mbox{]}=true;sprintf(\mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}}, "{}Rx Data Trial \%d Success\+: Linear\+Accel\+: la\+X\+: \%.\+2lf la\+Y\+: \%.\+2lf la\+Z\+: "{} "{}\%.\+2lf Accuracy\+: \%s"{},(cb\+\_\+execution\+\_\+cnt+1), report\+\_\+data.\+lin\+\_\+accel\+\_\+x, report\+\_\+data.\+lin\+\_\+accel\+\_\+y, report\+\_\+data.\+lin\+\_\+accel\+\_\+z, \mbox{\hyperlink{class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3}{BNO08x\+Test\+Helper\+::\+BNO08x\+Accuracy\+\_\+to\+\_\+str}}(report\+\_\+data.\+lin\+\_\+accel\+\_\+accuracy));\mbox{\hyperlink{class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002}{BNO08x\+Test\+Helper\+::print\+\_\+test\+\_\+msg}}(TEST\+\_\+\+TAG, \mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}});\} \}) -\item -\mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} \mbox{\hyperlink{_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0}{enable\+\_\+linear\+\_\+accelerometer}} (\mbox{\hyperlink{_callback_tests_8cpp_a4b80e39a1f48d801615a1f7baa210071}{REPORT\+\_\+\+PERIOD}}) -\item -\mbox{\hyperlink{_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3}{TEST\+\_\+\+ASSERT\+\_\+\+EQUAL}} (true, \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}}\mbox{[}0\mbox{]}) -\item -\mbox{\hyperlink{_callback_tests_8cpp_aa6754207db4cfba956441680c7a6a97d}{TEST\+\_\+\+ASSERT\+\_\+\+EQUAL}} (true, \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}}\mbox{[}1\mbox{]}) -\item -\mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} \mbox{\hyperlink{_callback_tests_8cpp_a5cc5f7e6658e3b1634d99b73dbfd06ab}{disable\+\_\+linear\+\_\+accelerometer}} () -\item -\mbox{\hyperlink{_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8}{TEST\+\_\+\+CASE}} ("{}BNO08x Driver Cleanup \mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} \mbox{[}Callback\+Tests\mbox{]} Tests"{}, "{}\mbox{[}Callback\+Tests\mbox{]}"{}) -\end{DoxyCompactItemize} -\doxysubsubsection*{Variables} -\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{class_b_n_o08x}{BNO08x}} \texorpdfstring{$\ast$}{*} \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} = nullptr -\item -\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t}} \mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}} -\item -\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t}} \mbox{\hyperlink{_callback_tests_8cpp_a8c57d66969fed0b55bdee9b57f6ed0a7}{prev\+\_\+report\+\_\+data}} -\item -const constexpr uint8\+\_\+t \mbox{\hyperlink{_callback_tests_8cpp_a20cd776c25ed6d39b2dcb95d155cfbda}{RX\+\_\+\+REPORT\+\_\+\+TRIAL\+\_\+\+CNT}} = 5 -\item -const constexpr uint32\+\_\+t \mbox{\hyperlink{_callback_tests_8cpp_a4b80e39a1f48d801615a1f7baa210071}{REPORT\+\_\+\+PERIOD}} = 100000\+UL -\item -bool \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}} = false -\item -char \mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}} \mbox{[}200\mbox{]} = \{\} -\item -const constexpr uint8\+\_\+t \mbox{\hyperlink{_callback_tests_8cpp_aafbc34af64f3c93123dce5a8238efd38}{ENABLED\+\_\+\+REPORT\+\_\+\+CNT}} = 2 -\end{DoxyCompactItemize} - - -\doxysubsection{Function Documentation} -\Hypertarget{_callback_tests_8cpp_a79547a2396efd083faeba3e54d94360d}\label{_callback_tests_8cpp_a79547a2396efd083faeba3e54d94360d} -\index{CallbackTests.cpp@{CallbackTests.cpp}!disable\_accelerometer@{disable\_accelerometer}} -\index{disable\_accelerometer@{disable\_accelerometer}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{disable\_accelerometer()}{disable\_accelerometer()}} -{\footnotesize\ttfamily \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} disable\+\_\+accelerometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - -\Hypertarget{_callback_tests_8cpp_a5cc5f7e6658e3b1634d99b73dbfd06ab}\label{_callback_tests_8cpp_a5cc5f7e6658e3b1634d99b73dbfd06ab} -\index{CallbackTests.cpp@{CallbackTests.cpp}!disable\_linear\_accelerometer@{disable\_linear\_accelerometer}} -\index{disable\_linear\_accelerometer@{disable\_linear\_accelerometer}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{disable\_linear\_accelerometer()}{disable\_linear\_accelerometer()}} -{\footnotesize\ttfamily \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} disable\+\_\+linear\+\_\+accelerometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - -\Hypertarget{_callback_tests_8cpp_a0f2cacda77ab92640f739aca52b1f99f}\label{_callback_tests_8cpp_a0f2cacda77ab92640f739aca52b1f99f} -\index{CallbackTests.cpp@{CallbackTests.cpp}!enable\_accelerometer@{enable\_accelerometer}} -\index{enable\_accelerometer@{enable\_accelerometer}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{enable\_accelerometer()}{enable\_accelerometer()}} -{\footnotesize\ttfamily \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} enable\+\_\+accelerometer (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{_callback_tests_8cpp_a4b80e39a1f48d801615a1f7baa210071}{REPORT\+\_\+\+PERIOD}}}]{ }\end{DoxyParamCaption})} - -\Hypertarget{_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0}\label{_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0} -\index{CallbackTests.cpp@{CallbackTests.cpp}!enable\_linear\_accelerometer@{enable\_linear\_accelerometer}} -\index{enable\_linear\_accelerometer@{enable\_linear\_accelerometer}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{enable\_linear\_accelerometer()}{enable\_linear\_accelerometer()}} -{\footnotesize\ttfamily \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} enable\+\_\+linear\+\_\+accelerometer (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{_callback_tests_8cpp_a4b80e39a1f48d801615a1f7baa210071}{REPORT\+\_\+\+PERIOD}}}]{ }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph} -\end{center} -\end{figure} -\Hypertarget{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}\label{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa} -\index{CallbackTests.cpp@{CallbackTests.cpp}!for@{for}} -\index{for@{for}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{for()}{for()}} -{\footnotesize\ttfamily for (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph} -\end{center} -\end{figure} -\Hypertarget{_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573}\label{_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573} -\index{CallbackTests.cpp@{CallbackTests.cpp}!register\_cb@{register\_cb}} -\index{register\_cb@{register\_cb}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{register\_cb()}{register\_cb()}\hspace{0.1cm}{\footnotesize\ttfamily [1/2]}} -{\footnotesize\ttfamily \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} register\+\_\+cb (\begin{DoxyParamCaption}\item[{\mbox{[}\&imu, \&new\+\_\+data, \&report\+\_\+data, \&prev\+\_\+report\+\_\+data, \&msg\+\_\+buff\mbox{]} () \{ static int cb\+\_\+execution\+\_\+cnt=0;cb\+\_\+execution\+\_\+cnt++;\mbox{\hyperlink{class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2}{BNO08x\+Test\+Helper\+::update\+\_\+report\+\_\+data}}(\&\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}});if(\mbox{\hyperlink{class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea}{BNO08x\+Test\+Helper\+::accelerometer\+\_\+data\+\_\+is\+\_\+new}}(\&\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a8c57d66969fed0b55bdee9b57f6ed0a7}{prev\+\_\+report\+\_\+data}})) \{ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}}=true;sprintf(\mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}}, "{}Rx Data Trial \%d Success\+: Angular\+Accel\+: a\+X\+: \%.\+2lf accel a\+Y\+: \%.\+2lf accel a\+Z\+: "{} "{}\%.\+2lf Accuracy \%s"{}, cb\+\_\+execution\+\_\+cnt, report\+\_\+data.\+accel\+\_\+x, report\+\_\+data.\+accel\+\_\+y, report\+\_\+data.\+accel\+\_\+z, \mbox{\hyperlink{class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3}{BNO08x\+Test\+Helper\+::\+BNO08x\+Accuracy\+\_\+to\+\_\+str}}(report\+\_\+data.\+accel\+\_\+accuracy));\mbox{\hyperlink{class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002}{BNO08x\+Test\+Helper\+::print\+\_\+test\+\_\+msg}}(TEST\+\_\+\+TAG, \mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}});\} \}}]{ }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph} -\end{center} -\end{figure} -\Hypertarget{_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73}\label{_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73} -\index{CallbackTests.cpp@{CallbackTests.cpp}!register\_cb@{register\_cb}} -\index{register\_cb@{register\_cb}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{register\_cb()}{register\_cb()}\hspace{0.1cm}{\footnotesize\ttfamily [2/2]}} -{\footnotesize\ttfamily \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}} register\+\_\+cb (\begin{DoxyParamCaption}\item[{\mbox{[}\&imu, \&new\+\_\+data, \&report\+\_\+data, \&prev\+\_\+report\+\_\+data, \&msg\+\_\+buff\mbox{]} () \{ static int cb\+\_\+execution\+\_\+cnt=0;cb\+\_\+execution\+\_\+cnt++;\mbox{\hyperlink{class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2}{BNO08x\+Test\+Helper\+::update\+\_\+report\+\_\+data}}(\&\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}});if(\mbox{\hyperlink{class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea}{BNO08x\+Test\+Helper\+::accelerometer\+\_\+data\+\_\+is\+\_\+new}}(\&\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a8c57d66969fed0b55bdee9b57f6ed0a7}{prev\+\_\+report\+\_\+data}})) \{ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}}\mbox{[}0\mbox{]}=true;sprintf(\mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}}, "{}Rx Data Trial \%d Success\+: Angular\+Accel\+: a\+X\+: \%.\+2lf accel a\+Y\+: \%.\+2lf accel a\+Z\+: "{} "{}\%.\+2lf Accuracy \%s"{}, cb\+\_\+execution\+\_\+cnt, report\+\_\+data.\+accel\+\_\+x, report\+\_\+data.\+accel\+\_\+y, report\+\_\+data.\+accel\+\_\+z, \mbox{\hyperlink{class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3}{BNO08x\+Test\+Helper\+::\+BNO08x\+Accuracy\+\_\+to\+\_\+str}}(report\+\_\+data.\+accel\+\_\+accuracy));\mbox{\hyperlink{class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002}{BNO08x\+Test\+Helper\+::print\+\_\+test\+\_\+msg}}(TEST\+\_\+\+TAG, \mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}});\} if(\mbox{\hyperlink{class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590}{BNO08x\+Test\+Helper\+::linear\+\_\+accelerometer\+\_\+data\+\_\+is\+\_\+new}}(\&\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \&\mbox{\hyperlink{_callback_tests_8cpp_a8c57d66969fed0b55bdee9b57f6ed0a7}{prev\+\_\+report\+\_\+data}})) \{ \mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}}\mbox{[}1\mbox{]}=true;sprintf(\mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}}, "{}Rx Data Trial \%d Success\+: Linear\+Accel\+: la\+X\+: \%.\+2lf la\+Y\+: \%.\+2lf la\+Z\+: "{} "{}\%.\+2lf Accuracy\+: \%s"{},(cb\+\_\+execution\+\_\+cnt+1), report\+\_\+data.\+lin\+\_\+accel\+\_\+x, report\+\_\+data.\+lin\+\_\+accel\+\_\+y, report\+\_\+data.\+lin\+\_\+accel\+\_\+z, \mbox{\hyperlink{class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3}{BNO08x\+Test\+Helper\+::\+BNO08x\+Accuracy\+\_\+to\+\_\+str}}(report\+\_\+data.\+lin\+\_\+accel\+\_\+accuracy));\mbox{\hyperlink{class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002}{BNO08x\+Test\+Helper\+::print\+\_\+test\+\_\+msg}}(TEST\+\_\+\+TAG, \mbox{\hyperlink{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}{msg\+\_\+buff}});\} \}}]{ }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph} -\end{center} -\end{figure} -\Hypertarget{_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3}\label{_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3} -\index{CallbackTests.cpp@{CallbackTests.cpp}!TEST\_ASSERT\_EQUAL@{TEST\_ASSERT\_EQUAL}} -\index{TEST\_ASSERT\_EQUAL@{TEST\_ASSERT\_EQUAL}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_ASSERT\_EQUAL()}{TEST\_ASSERT\_EQUAL()}\hspace{0.1cm}{\footnotesize\ttfamily [1/2]}} -{\footnotesize\ttfamily TEST\+\_\+\+ASSERT\+\_\+\+EQUAL (\begin{DoxyParamCaption}\item[{true}]{, }\item[{\mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}}}]{\mbox{[}0\mbox{]} }\end{DoxyParamCaption})} - -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph} -\end{center} -\end{figure} -\Hypertarget{_callback_tests_8cpp_aa6754207db4cfba956441680c7a6a97d}\label{_callback_tests_8cpp_aa6754207db4cfba956441680c7a6a97d} -\index{CallbackTests.cpp@{CallbackTests.cpp}!TEST\_ASSERT\_EQUAL@{TEST\_ASSERT\_EQUAL}} -\index{TEST\_ASSERT\_EQUAL@{TEST\_ASSERT\_EQUAL}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_ASSERT\_EQUAL()}{TEST\_ASSERT\_EQUAL()}\hspace{0.1cm}{\footnotesize\ttfamily [2/2]}} -{\footnotesize\ttfamily TEST\+\_\+\+ASSERT\+\_\+\+EQUAL (\begin{DoxyParamCaption}\item[{true}]{, }\item[{\mbox{\hyperlink{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}{new\+\_\+data}}}]{\mbox{[}1\mbox{]} }\end{DoxyParamCaption})} - -\Hypertarget{_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8}\label{_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8} -\index{CallbackTests.cpp@{CallbackTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [1/2]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}BNO08x Driver Cleanup \mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} Tests"{}}]{\mbox{[}\+Callback\+Tests\mbox{]}, }\item[{"{}"{}}]{\mbox{[}\+Callback\+Tests\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=326pt]{_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph} -\end{center} -\end{figure} -\Hypertarget{_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa}\label{_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa} -\index{CallbackTests.cpp@{CallbackTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [2/2]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}BNO08x Driver Creation \mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} Tests"{}}]{\mbox{[}\+Callback\+Tests\mbox{]}, }\item[{"{}"{}}]{\mbox{[}\+Callback\+Tests\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph} -\end{center} -\end{figure} - - -\doxysubsection{Variable Documentation} -\Hypertarget{_callback_tests_8cpp_aafbc34af64f3c93123dce5a8238efd38}\label{_callback_tests_8cpp_aafbc34af64f3c93123dce5a8238efd38} -\index{CallbackTests.cpp@{CallbackTests.cpp}!ENABLED\_REPORT\_CNT@{ENABLED\_REPORT\_CNT}} -\index{ENABLED\_REPORT\_CNT@{ENABLED\_REPORT\_CNT}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{ENABLED\_REPORT\_CNT}{ENABLED\_REPORT\_CNT}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t ENABLED\+\_\+\+REPORT\+\_\+\+CNT = 2\hspace{0.3cm}{\ttfamily [constexpr]}} - -\Hypertarget{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}\label{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70} -\index{CallbackTests.cpp@{CallbackTests.cpp}!imu@{imu}} -\index{imu@{imu}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{imu}{imu}} -{\footnotesize\ttfamily \mbox{\hyperlink{class_b_n_o08x}{BNO08x}} \texorpdfstring{$\ast$}{*} imu = nullptr} - -\Hypertarget{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596}\label{_callback_tests_8cpp_a4e7be0e1e700243053709d7544201596} -\index{CallbackTests.cpp@{CallbackTests.cpp}!msg\_buff@{msg\_buff}} -\index{msg\_buff@{msg\_buff}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{msg\_buff}{msg\_buff}} -{\footnotesize\ttfamily char msg\+\_\+buff = \{\}} - -\Hypertarget{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876}\label{_callback_tests_8cpp_a5a4ba60143c31271df0f72bf0e503876} -\index{CallbackTests.cpp@{CallbackTests.cpp}!new\_data@{new\_data}} -\index{new\_data@{new\_data}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{new\_data}{new\_data}} -{\footnotesize\ttfamily bool new\+\_\+data = false} - -\Hypertarget{_callback_tests_8cpp_a8c57d66969fed0b55bdee9b57f6ed0a7}\label{_callback_tests_8cpp_a8c57d66969fed0b55bdee9b57f6ed0a7} -\index{CallbackTests.cpp@{CallbackTests.cpp}!prev\_report\_data@{prev\_report\_data}} -\index{prev\_report\_data@{prev\_report\_data}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{prev\_report\_data}{prev\_report\_data}} -{\footnotesize\ttfamily \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t}} prev\+\_\+report\+\_\+data} - -\Hypertarget{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}\label{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9} -\index{CallbackTests.cpp@{CallbackTests.cpp}!report\_data@{report\_data}} -\index{report\_data@{report\_data}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{report\_data}{report\_data}} -{\footnotesize\ttfamily \mbox{\hyperlink{class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2}{BNO08x\+Test\+Helper\+::update\+\_\+report\+\_\+data}} \& report\+\_\+data} - -\Hypertarget{_callback_tests_8cpp_a4b80e39a1f48d801615a1f7baa210071}\label{_callback_tests_8cpp_a4b80e39a1f48d801615a1f7baa210071} -\index{CallbackTests.cpp@{CallbackTests.cpp}!REPORT\_PERIOD@{REPORT\_PERIOD}} -\index{REPORT\_PERIOD@{REPORT\_PERIOD}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{REPORT\_PERIOD}{REPORT\_PERIOD}} -{\footnotesize\ttfamily const constexpr uint32\+\_\+t REPORT\+\_\+\+PERIOD = 100000\+UL\hspace{0.3cm}{\ttfamily [constexpr]}} - -\Hypertarget{_callback_tests_8cpp_a20cd776c25ed6d39b2dcb95d155cfbda}\label{_callback_tests_8cpp_a20cd776c25ed6d39b2dcb95d155cfbda} -\index{CallbackTests.cpp@{CallbackTests.cpp}!RX\_REPORT\_TRIAL\_CNT@{RX\_REPORT\_TRIAL\_CNT}} -\index{RX\_REPORT\_TRIAL\_CNT@{RX\_REPORT\_TRIAL\_CNT}!CallbackTests.cpp@{CallbackTests.cpp}} -\doxysubsubsection{\texorpdfstring{RX\_REPORT\_TRIAL\_CNT}{RX\_REPORT\_TRIAL\_CNT}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t RX\+\_\+\+REPORT\+\_\+\+TRIAL\+\_\+\+CNT = 5\hspace{0.3cm}{\ttfamily [constexpr]}} - diff --git a/documentation/latex/_callback_tests_8cpp__incl.md5 b/documentation/latex/_callback_tests_8cpp__incl.md5 deleted file mode 100644 index 854836d..0000000 --- a/documentation/latex/_callback_tests_8cpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -904b67c4065b2faabd8ffc0f9b6032ea \ No newline at end of file diff --git a/documentation/latex/_callback_tests_8cpp__incl.pdf b/documentation/latex/_callback_tests_8cpp__incl.pdf deleted file mode 100644 index d09505a..0000000 Binary files a/documentation/latex/_callback_tests_8cpp__incl.pdf and /dev/null differ diff --git a/documentation/latex/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.md5 b/documentation/latex/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.md5 deleted file mode 100644 index 167bcbd..0000000 --- a/documentation/latex/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d15d74dd96076529a0bef5ff54376a73 \ No newline at end of file diff --git a/documentation/latex/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.pdf b/documentation/latex/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.pdf deleted file mode 100644 index 1991807..0000000 Binary files a/documentation/latex/_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.md5 b/documentation/latex/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.md5 deleted file mode 100644 index 7cee81f..0000000 --- a/documentation/latex/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0a7684ee4650b83a916d9c99e1776e4c \ No newline at end of file diff --git a/documentation/latex/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.pdf b/documentation/latex/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.pdf deleted file mode 100644 index dc11f52..0000000 Binary files a/documentation/latex/_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.md5 b/documentation/latex/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.md5 deleted file mode 100644 index 1b9f34d..0000000 --- a/documentation/latex/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c71138db13738de8cea63bf262ce8bba \ No newline at end of file diff --git a/documentation/latex/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.pdf b/documentation/latex/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.pdf deleted file mode 100644 index d9efcb0..0000000 Binary files a/documentation/latex/_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.md5 b/documentation/latex/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.md5 deleted file mode 100644 index 53d196a..0000000 --- a/documentation/latex/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e873bf710e3253e53f117b449e43f427 \ No newline at end of file diff --git a/documentation/latex/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.pdf b/documentation/latex/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.pdf deleted file mode 100644 index 39e4517..0000000 Binary files a/documentation/latex/_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.md5 b/documentation/latex/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.md5 deleted file mode 100644 index 68b578d..0000000 --- a/documentation/latex/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0b9fbdc8ea9fe6d087b50af3bcad9d9b \ No newline at end of file diff --git a/documentation/latex/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.pdf b/documentation/latex/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.pdf deleted file mode 100644 index 7ad06c9..0000000 Binary files a/documentation/latex/_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.md5 b/documentation/latex/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.md5 deleted file mode 100644 index 7530ff1..0000000 --- a/documentation/latex/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9a4e5336afb31eb8a6a19745aa08ba9c \ No newline at end of file diff --git a/documentation/latex/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.pdf b/documentation/latex/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.pdf deleted file mode 100644 index 40a335d..0000000 Binary files a/documentation/latex/_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.md5 b/documentation/latex/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.md5 deleted file mode 100644 index bc87850..0000000 --- a/documentation/latex/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b9ea8364b8e173f34d36dd9941c844a7 \ No newline at end of file diff --git a/documentation/latex/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.pdf b/documentation/latex/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.pdf deleted file mode 100644 index 7c153ee..0000000 Binary files a/documentation/latex/_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_init_deinit_tests_8cpp.tex b/documentation/latex/_init_deinit_tests_8cpp.tex deleted file mode 100644 index b3b1969..0000000 --- a/documentation/latex/_init_deinit_tests_8cpp.tex +++ /dev/null @@ -1,130 +0,0 @@ -\doxysection{Init\+Deinit\+Tests.\+cpp File Reference} -\hypertarget{_init_deinit_tests_8cpp}{}\label{_init_deinit_tests_8cpp}\index{InitDeinitTests.cpp@{InitDeinitTests.cpp}} -{\ttfamily \#include "{}unity.\+h"{}}\newline -{\ttfamily \#include "{}../include/\+BNO08x\+Test\+Helper.\+hpp"{}}\newline -Include dependency graph for Init\+Deinit\+Tests.\+cpp\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_init_deinit_tests_8cpp__incl} -\end{center} -\end{figure} -\doxysubsubsection*{Functions} -\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708}{TEST\+\_\+\+CASE}} ("{}Init Config Args"{}, "{}\mbox{[}Init\+Comprehensive\mbox{]}"{}) -\item -\mbox{\hyperlink{_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b}{TEST\+\_\+\+CASE}} ("{}Init GPIO"{}, "{}\mbox{[}Init\+Comprehensive\mbox{]}"{}) -\item -\mbox{\hyperlink{_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a}{TEST\+\_\+\+CASE}} ("{}Init HINT ISR"{}, "{}\mbox{[}Init\+Comprehensive\mbox{]}"{}) -\item -\mbox{\hyperlink{_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc}{TEST\+\_\+\+CASE}} ("{}Init SPI"{}, "{}\mbox{[}Init\+Comprehensive\mbox{]}"{}) -\item -\mbox{\hyperlink{_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05}{TEST\+\_\+\+CASE}} ("{}Init\+Comprehensive Tasks"{}, "{}\mbox{[}Init\+Comprehensive\mbox{]}"{}) -\item -\mbox{\hyperlink{_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05}{TEST\+\_\+\+CASE}} ("{}Finish Init"{}, "{}\mbox{[}Init\+Comprehensive\mbox{]}"{}) -\item -\mbox{\hyperlink{_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6}{TEST\+\_\+\+CASE}} ("{}Init \& Deinit"{}, "{}\mbox{[}Init\+Denit\mbox{]}"{}) -\end{DoxyCompactItemize} - - -\doxysubsection{Function Documentation} -\Hypertarget{_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05}\label{_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05} -\index{InitDeinitTests.cpp@{InitDeinitTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!InitDeinitTests.cpp@{InitDeinitTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [1/7]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Finish Init"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Init\+Comprehensive\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph} -\end{center} -\end{figure} -\Hypertarget{_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6}\label{_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6} -\index{InitDeinitTests.cpp@{InitDeinitTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!InitDeinitTests.cpp@{InitDeinitTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [2/7]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Init \& Deinit"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Init\+Denit\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph} -\end{center} -\end{figure} -\Hypertarget{_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708}\label{_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708} -\index{InitDeinitTests.cpp@{InitDeinitTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!InitDeinitTests.cpp@{InitDeinitTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [3/7]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Init Config Args"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Init\+Comprehensive\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph} -\end{center} -\end{figure} -\Hypertarget{_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b}\label{_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b} -\index{InitDeinitTests.cpp@{InitDeinitTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!InitDeinitTests.cpp@{InitDeinitTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [4/7]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Init GPIO"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Init\+Comprehensive\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph} -\end{center} -\end{figure} -\Hypertarget{_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a}\label{_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a} -\index{InitDeinitTests.cpp@{InitDeinitTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!InitDeinitTests.cpp@{InitDeinitTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [5/7]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Init HINT ISR"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Init\+Comprehensive\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph} -\end{center} -\end{figure} -\Hypertarget{_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc}\label{_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc} -\index{InitDeinitTests.cpp@{InitDeinitTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!InitDeinitTests.cpp@{InitDeinitTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [6/7]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Init SPI"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Init\+Comprehensive\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph} -\end{center} -\end{figure} -\Hypertarget{_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05}\label{_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05} -\index{InitDeinitTests.cpp@{InitDeinitTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!InitDeinitTests.cpp@{InitDeinitTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [7/7]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Init\+Comprehensive Tasks"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Init\+Comprehensive\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph} -\end{center} -\end{figure} diff --git a/documentation/latex/_init_deinit_tests_8cpp__incl.md5 b/documentation/latex/_init_deinit_tests_8cpp__incl.md5 deleted file mode 100644 index 4fa1b52..0000000 --- a/documentation/latex/_init_deinit_tests_8cpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -affe16a9f4e91132fbca08b7b955f66c \ No newline at end of file diff --git a/documentation/latex/_init_deinit_tests_8cpp__incl.pdf b/documentation/latex/_init_deinit_tests_8cpp__incl.pdf deleted file mode 100644 index 3ee88f9..0000000 Binary files a/documentation/latex/_init_deinit_tests_8cpp__incl.pdf and /dev/null differ diff --git a/documentation/latex/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.md5 b/documentation/latex/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.md5 deleted file mode 100644 index ddb264d..0000000 --- a/documentation/latex/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -29188a1edc5ba826e4fcc2a143050293 \ No newline at end of file diff --git a/documentation/latex/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.pdf b/documentation/latex/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.pdf deleted file mode 100644 index aa3ab4e..0000000 Binary files a/documentation/latex/_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.md5 b/documentation/latex/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.md5 deleted file mode 100644 index 18e64eb..0000000 --- a/documentation/latex/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -99449704d6f09f6863984ddf1f795d69 \ No newline at end of file diff --git a/documentation/latex/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.pdf b/documentation/latex/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.pdf deleted file mode 100644 index e651c46..0000000 Binary files a/documentation/latex/_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.md5 b/documentation/latex/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.md5 deleted file mode 100644 index 0b19baa..0000000 --- a/documentation/latex/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8eb2db2312f3476fa5a5bc495dea7254 \ No newline at end of file diff --git a/documentation/latex/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.pdf b/documentation/latex/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.pdf deleted file mode 100644 index 4b6825e..0000000 Binary files a/documentation/latex/_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.md5 b/documentation/latex/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.md5 deleted file mode 100644 index f08ca71..0000000 --- a/documentation/latex/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9138e72c464378a7608bd9751db292b5 \ No newline at end of file diff --git a/documentation/latex/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.pdf b/documentation/latex/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.pdf deleted file mode 100644 index fa229a7..0000000 Binary files a/documentation/latex/_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.md5 b/documentation/latex/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.md5 deleted file mode 100644 index 416b4ee..0000000 --- a/documentation/latex/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ae9bacc61e138ee8ededc5c79538250a \ No newline at end of file diff --git a/documentation/latex/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.pdf b/documentation/latex/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.pdf deleted file mode 100644 index 38cd0c6..0000000 Binary files a/documentation/latex/_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.md5 b/documentation/latex/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.md5 deleted file mode 100644 index 01a1601..0000000 --- a/documentation/latex/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -aaa1dcf3b9d61555df9d623a501dfab4 \ No newline at end of file diff --git a/documentation/latex/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.pdf b/documentation/latex/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.pdf deleted file mode 100644 index 952a184..0000000 Binary files a/documentation/latex/_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.md5 b/documentation/latex/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.md5 deleted file mode 100644 index f70d244..0000000 --- a/documentation/latex/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6d489ed5f5e4433504e6b55d3fbb0e9f \ No newline at end of file diff --git a/documentation/latex/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.pdf b/documentation/latex/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.pdf deleted file mode 100644 index b106933..0000000 Binary files a/documentation/latex/_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_multi_report_tests_8cpp.tex b/documentation/latex/_multi_report_tests_8cpp.tex deleted file mode 100644 index 54e2f73..0000000 --- a/documentation/latex/_multi_report_tests_8cpp.tex +++ /dev/null @@ -1,114 +0,0 @@ -\doxysection{Multi\+Report\+Tests.\+cpp File Reference} -\hypertarget{_multi_report_tests_8cpp}{}\label{_multi_report_tests_8cpp}\index{MultiReportTests.cpp@{MultiReportTests.cpp}} -{\ttfamily \#include "{}unity.\+h"{}}\newline -{\ttfamily \#include "{}../include/\+BNO08x\+Test\+Helper.\+hpp"{}}\newline -Include dependency graph for Multi\+Report\+Tests.\+cpp\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_multi_report_tests_8cpp__incl} -\end{center} -\end{figure} -\doxysubsubsection*{Functions} -\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda}{TEST\+\_\+\+CASE}} ("{}BNO08x Driver Creation \mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} \mbox{[}Multi\+Report\+Enable\+Disable\mbox{]} Tests"{}, "{}\mbox{[}Multi\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7}{TEST\+\_\+\+CASE}} ("{}Dual Report Enable/Disable"{}, "{}\mbox{[}Multi\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882}{TEST\+\_\+\+CASE}} ("{}Tri Report Enable/Disable"{}, "{}\mbox{[}Multi\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1}{TEST\+\_\+\+CASE}} ("{}Quad Report Enable/Disable"{}, "{}\mbox{[}Multi\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996}{TEST\+\_\+\+CASE}} ("{}Hex Report Enable"{}, "{}\mbox{[}Multi\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090}{TEST\+\_\+\+CASE}} ("{}BNO08x Driver Cleanup \mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} \mbox{[}Multi\+Report\+Enable\+Disable\mbox{]} Tests"{}, "{}\mbox{[}Multi\+Report\+Enable\+Disable\mbox{]}"{}) -\end{DoxyCompactItemize} - - -\doxysubsection{Function Documentation} -\Hypertarget{_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090}\label{_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090} -\index{MultiReportTests.cpp@{MultiReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!MultiReportTests.cpp@{MultiReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [1/6]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}BNO08x Driver Cleanup \mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} Tests"{}}]{\mbox{[}\+Multi\+Report\+Enable\+Disable\mbox{]}, }\item[{"{}"{}}]{\mbox{[}\+Multi\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=326pt]{_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph} -\end{center} -\end{figure} -\Hypertarget{_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda}\label{_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda} -\index{MultiReportTests.cpp@{MultiReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!MultiReportTests.cpp@{MultiReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [2/6]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}BNO08x Driver Creation \mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} Tests"{}}]{\mbox{[}\+Multi\+Report\+Enable\+Disable\mbox{]}, }\item[{"{}"{}}]{\mbox{[}\+Multi\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph} -\end{center} -\end{figure} -\Hypertarget{_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7}\label{_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7} -\index{MultiReportTests.cpp@{MultiReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!MultiReportTests.cpp@{MultiReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [3/6]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Dual Report Enable/Disable"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Multi\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph} -\end{center} -\end{figure} -\Hypertarget{_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996}\label{_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996} -\index{MultiReportTests.cpp@{MultiReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!MultiReportTests.cpp@{MultiReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [4/6]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Hex Report Enable"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Multi\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph} -\end{center} -\end{figure} -\Hypertarget{_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1}\label{_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1} -\index{MultiReportTests.cpp@{MultiReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!MultiReportTests.cpp@{MultiReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [5/6]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Quad Report Enable/Disable"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Multi\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph} -\end{center} -\end{figure} -\Hypertarget{_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882}\label{_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882} -\index{MultiReportTests.cpp@{MultiReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!MultiReportTests.cpp@{MultiReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [6/6]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Tri Report Enable/Disable"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Multi\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph} -\end{center} -\end{figure} diff --git a/documentation/latex/_multi_report_tests_8cpp__incl.md5 b/documentation/latex/_multi_report_tests_8cpp__incl.md5 deleted file mode 100644 index 17b7e9f..0000000 --- a/documentation/latex/_multi_report_tests_8cpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -5f8e94811336ec49bd1ea91fcadf6e54 \ No newline at end of file diff --git a/documentation/latex/_multi_report_tests_8cpp__incl.pdf b/documentation/latex/_multi_report_tests_8cpp__incl.pdf deleted file mode 100644 index 0016dd7..0000000 Binary files a/documentation/latex/_multi_report_tests_8cpp__incl.pdf and /dev/null differ diff --git a/documentation/latex/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.md5 b/documentation/latex/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.md5 deleted file mode 100644 index 26ecdda..0000000 --- a/documentation/latex/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3c08ce81e6b43ce471614469aea08aa9 \ No newline at end of file diff --git a/documentation/latex/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.pdf b/documentation/latex/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.pdf deleted file mode 100644 index 8ac6474..0000000 Binary files a/documentation/latex/_multi_report_tests_8cpp_a1438f6b8587b635b6096dda2927fa9a1_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.md5 b/documentation/latex/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.md5 deleted file mode 100644 index bc87850..0000000 --- a/documentation/latex/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b9ea8364b8e173f34d36dd9941c844a7 \ No newline at end of file diff --git a/documentation/latex/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.pdf b/documentation/latex/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.pdf deleted file mode 100644 index 7c153ee..0000000 Binary files a/documentation/latex/_multi_report_tests_8cpp_a1fd7b6a0d4dbb7f91fd5691b5b054bda_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.md5 b/documentation/latex/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.md5 deleted file mode 100644 index b44075b..0000000 --- a/documentation/latex/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -875378aa26f998657486cc2061397912 \ No newline at end of file diff --git a/documentation/latex/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.pdf b/documentation/latex/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.pdf deleted file mode 100644 index c322de0..0000000 Binary files a/documentation/latex/_multi_report_tests_8cpp_a915d6c272bf95057a8bb22abfb307882_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.md5 b/documentation/latex/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.md5 deleted file mode 100644 index 595f730..0000000 --- a/documentation/latex/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fb8738033f822947b80fa5ac585e9d88 \ No newline at end of file diff --git a/documentation/latex/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.pdf b/documentation/latex/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.pdf deleted file mode 100644 index d078e86..0000000 Binary files a/documentation/latex/_multi_report_tests_8cpp_aa9e0389fa75046b52d13286af2c3b2a7_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.md5 b/documentation/latex/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.md5 deleted file mode 100644 index 1b9f34d..0000000 --- a/documentation/latex/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c71138db13738de8cea63bf262ce8bba \ No newline at end of file diff --git a/documentation/latex/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.pdf b/documentation/latex/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.pdf deleted file mode 100644 index d9efcb0..0000000 Binary files a/documentation/latex/_multi_report_tests_8cpp_ac92ec06fe64f7bedbbe37dee3e64c090_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.md5 b/documentation/latex/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.md5 deleted file mode 100644 index 5ae3ff1..0000000 --- a/documentation/latex/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2c845c935775d6ac2ac015e022f12620 \ No newline at end of file diff --git a/documentation/latex/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.pdf b/documentation/latex/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.pdf deleted file mode 100644 index 7d3996d..0000000 Binary files a/documentation/latex/_multi_report_tests_8cpp_ad96cfd7c30e8693897688ce24bb53996_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_r_e_a_d_m_e_8md.tex b/documentation/latex/_r_e_a_d_m_e_8md.tex deleted file mode 100644 index dffc600..0000000 --- a/documentation/latex/_r_e_a_d_m_e_8md.tex +++ /dev/null @@ -1,2 +0,0 @@ -\doxysection{README.\+md File Reference} -\hypertarget{_r_e_a_d_m_e_8md}{}\label{_r_e_a_d_m_e_8md}\index{README.md@{README.md}} diff --git a/documentation/latex/_single_report_tests_8cpp.tex b/documentation/latex/_single_report_tests_8cpp.tex deleted file mode 100644 index 29782e2..0000000 --- a/documentation/latex/_single_report_tests_8cpp.tex +++ /dev/null @@ -1,312 +0,0 @@ -\doxysection{Single\+Report\+Tests.\+cpp File Reference} -\hypertarget{_single_report_tests_8cpp}{}\label{_single_report_tests_8cpp}\index{SingleReportTests.cpp@{SingleReportTests.cpp}} -{\ttfamily \#include "{}unity.\+h"{}}\newline -{\ttfamily \#include "{}../include/\+BNO08x\+Test\+Helper.\+hpp"{}}\newline -Include dependency graph for Single\+Report\+Tests.\+cpp\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp__incl} -\end{center} -\end{figure} -\doxysubsubsection*{Functions} -\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab}{TEST\+\_\+\+CASE}} ("{}BNO08x Driver Creation \mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} \mbox{[}Single\+Report\+Enable\+Disable\mbox{]} Tests"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a}{TEST\+\_\+\+CASE}} ("{}Enable Incorrect Report"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8}{TEST\+\_\+\+CASE}} ("{}Enable/Disable Rotation Vector"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747}{TEST\+\_\+\+CASE}} ("{}Enable/Disable Game Rotation Vector"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8}{TEST\+\_\+\+CASE}} ("{}Enable/Disable ARVR Stabilized Rotation Vector"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c}{TEST\+\_\+\+CASE}} ("{}Enable/Disable ARVR Stabilized Game Rotation Vector"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_a713376354af2a970230882e2a487050e}{TEST\+\_\+\+CASE}} ("{}Enable/Disable Gyro Integrated Rotation Vector"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c}{TEST\+\_\+\+CASE}} ("{}Enable/Disable Uncalibrated Gyro"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486}{TEST\+\_\+\+CASE}} ("{}Enable/Disable Calibrated Gyro"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949}{TEST\+\_\+\+CASE}} ("{}Enable/Disable Accelerometer"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8}{TEST\+\_\+\+CASE}} ("{}Enable/Disable Linear Accelerometer"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee}{TEST\+\_\+\+CASE}} ("{}Enable/Disable Gravity"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff}{TEST\+\_\+\+CASE}} ("{}Enable/Disable Magnetometer"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502}{TEST\+\_\+\+CASE}} ("{}Enable/Disable Step Counter"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_acf249e215fca056266de6e833875925e}{TEST\+\_\+\+CASE}} ("{}Enable/Disable Stability Classifier"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4}{TEST\+\_\+\+CASE}} ("{}Enable/Disable Activity Classifier"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\item -\mbox{\hyperlink{_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5}{TEST\+\_\+\+CASE}} ("{}BNO08x Driver Cleanup \mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} \mbox{[}Single\+Report\+Enable\+Disable\mbox{]} Tests"{}, "{}\mbox{[}Single\+Report\+Enable\+Disable\mbox{]}"{}) -\end{DoxyCompactItemize} -\doxysubsubsection*{Variables} -\begin{DoxyCompactItemize} -\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{_single_report_tests_8cpp_a20cd776c25ed6d39b2dcb95d155cfbda}{RX\+\_\+\+REPORT\+\_\+\+TRIAL\+\_\+\+CNT}} = 5 -\item -static const constexpr uint32\+\_\+t \mbox{\hyperlink{_single_report_tests_8cpp_a4b80e39a1f48d801615a1f7baa210071}{REPORT\+\_\+\+PERIOD}} = 100000\+UL -\end{DoxyCompactItemize} - - -\doxysubsection{Function Documentation} -\Hypertarget{_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5}\label{_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [1/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}BNO08x Driver Cleanup \mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} Tests"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]}, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=326pt]{_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab}\label{_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [2/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}BNO08x Driver Creation \mbox{\hyperlink{_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa}{for}} Tests"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]}, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a}\label{_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [3/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable Incorrect Report"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949}\label{_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [4/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable Accelerometer"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4}\label{_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [5/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable Activity Classifier"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c}\label{_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [6/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable ARVR Stabilized Game Rotation Vector"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8}\label{_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [7/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable ARVR Stabilized Rotation Vector"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486}\label{_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [8/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable Calibrated Gyro"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747}\label{_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [9/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable Game Rotation Vector"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee}\label{_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [10/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable Gravity"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_a713376354af2a970230882e2a487050e}\label{_single_report_tests_8cpp_a713376354af2a970230882e2a487050e} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [11/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable Gyro Integrated Rotation Vector"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8}\label{_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [12/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable Linear Accelerometer"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff}\label{_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [13/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable Magnetometer"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8}\label{_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [14/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable Rotation Vector"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_acf249e215fca056266de6e833875925e}\label{_single_report_tests_8cpp_acf249e215fca056266de6e833875925e} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [15/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable Stability Classifier"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502}\label{_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [16/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable Step Counter"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph} -\end{center} -\end{figure} -\Hypertarget{_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c}\label{_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!TEST\_CASE@{TEST\_CASE}} -\index{TEST\_CASE@{TEST\_CASE}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{TEST\_CASE()}{TEST\_CASE()}\hspace{0.1cm}{\footnotesize\ttfamily [17/17]}} -{\footnotesize\ttfamily TEST\+\_\+\+CASE (\begin{DoxyParamCaption}\item[{"{}Enable/Disable Uncalibrated Gyro"{}}]{, }\item[{"{}"{}}]{\mbox{[}\+Single\+Report\+Enable\+Disable\mbox{]} }\end{DoxyParamCaption})} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph} -\end{center} -\end{figure} - - -\doxysubsection{Variable Documentation} -\Hypertarget{_single_report_tests_8cpp_a4b80e39a1f48d801615a1f7baa210071}\label{_single_report_tests_8cpp_a4b80e39a1f48d801615a1f7baa210071} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!REPORT\_PERIOD@{REPORT\_PERIOD}} -\index{REPORT\_PERIOD@{REPORT\_PERIOD}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{REPORT\_PERIOD}{REPORT\_PERIOD}} -{\footnotesize\ttfamily const constexpr uint32\+\_\+t REPORT\+\_\+\+PERIOD = 100000\+UL\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - -\Hypertarget{_single_report_tests_8cpp_a20cd776c25ed6d39b2dcb95d155cfbda}\label{_single_report_tests_8cpp_a20cd776c25ed6d39b2dcb95d155cfbda} -\index{SingleReportTests.cpp@{SingleReportTests.cpp}!RX\_REPORT\_TRIAL\_CNT@{RX\_REPORT\_TRIAL\_CNT}} -\index{RX\_REPORT\_TRIAL\_CNT@{RX\_REPORT\_TRIAL\_CNT}!SingleReportTests.cpp@{SingleReportTests.cpp}} -\doxysubsubsection{\texorpdfstring{RX\_REPORT\_TRIAL\_CNT}{RX\_REPORT\_TRIAL\_CNT}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t RX\+\_\+\+REPORT\+\_\+\+TRIAL\+\_\+\+CNT = 5\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - diff --git a/documentation/latex/_single_report_tests_8cpp__incl.md5 b/documentation/latex/_single_report_tests_8cpp__incl.md5 deleted file mode 100644 index d447534..0000000 --- a/documentation/latex/_single_report_tests_8cpp__incl.md5 +++ /dev/null @@ -1 +0,0 @@ -23d09c0cebe8150a1749678736a95cb6 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp__incl.pdf b/documentation/latex/_single_report_tests_8cpp__incl.pdf deleted file mode 100644 index fdb2d39..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp__incl.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.md5 deleted file mode 100644 index 15011a1..0000000 --- a/documentation/latex/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -160f95d6520f67a584db03e994273532 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.pdf deleted file mode 100644 index 0048384..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_a098111e0f361615318674b5b1b05ece4_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.md5 deleted file mode 100644 index 9a4d0bb..0000000 --- a/documentation/latex/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1f591d73e68925af32de6f34b14403cf \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.pdf deleted file mode 100644 index f38fd1d..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_a35b0417a053d9fbf61a91a2110c3495c_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.md5 deleted file mode 100644 index 06f6fe1..0000000 --- a/documentation/latex/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -486c1f45a235d92b4484710ed252db13 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.pdf deleted file mode 100644 index f07ac45..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_a3cce613b379b768244a176a32b37667c_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.md5 deleted file mode 100644 index b2cb3d6..0000000 --- a/documentation/latex/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -947301946ac785c73e674671fb93623b \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.pdf deleted file mode 100644 index 0327895..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_a429f6e7897a9609ddd093d66b6f7b1ff_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.md5 deleted file mode 100644 index 1b9f34d..0000000 --- a/documentation/latex/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c71138db13738de8cea63bf262ce8bba \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.pdf deleted file mode 100644 index d9efcb0..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_a697ac897c8756d7553854e52229d36f5_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.md5 deleted file mode 100644 index 0a6b828..0000000 --- a/documentation/latex/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7388ebd4cc658a2542bf35c0812d1788 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.pdf deleted file mode 100644 index d398b2b..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_a713376354af2a970230882e2a487050e_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.md5 deleted file mode 100644 index 706afee..0000000 --- a/documentation/latex/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5017258128885e39c859864016dee401 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.pdf deleted file mode 100644 index 67e28df..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_a90980a9fc26b3a692ab2529c9f8e4747_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.md5 deleted file mode 100644 index 9dd35b4..0000000 --- a/documentation/latex/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c12d54489a04c3e18c6415efe0f979ab \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.pdf deleted file mode 100644 index 79bc7c3..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_a9f2e049a5b61721869c5f4757e313502_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.md5 deleted file mode 100644 index bc87850..0000000 --- a/documentation/latex/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b9ea8364b8e173f34d36dd9941c844a7 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.pdf deleted file mode 100644 index 7c153ee..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_aac644123799c1f836d379c9789a064ab_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.md5 deleted file mode 100644 index 53f55b3..0000000 --- a/documentation/latex/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f6536edf3e20525c74777b7da45e5358 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.pdf deleted file mode 100644 index d3f3c91..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_aaefa1a1d4b3c190b7f46bb7f42512949_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.md5 deleted file mode 100644 index 6446563..0000000 --- a/documentation/latex/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8dcbe705990be85e0cf12d03c1529f87 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.pdf deleted file mode 100644 index b5612b6..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_ab9b4ae43e33572d90c4c889452cd91ee_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.md5 deleted file mode 100644 index acdb9a3..0000000 --- a/documentation/latex/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -eefc7583602acbba420fdfc0d38fe9e7 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.pdf deleted file mode 100644 index 0a14e8a..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_ace1544ccc126d0b9eadd433f9cb41486_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.md5 deleted file mode 100644 index f7bb956..0000000 --- a/documentation/latex/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -60648872e2ccf83f04018ba719071f33 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.pdf deleted file mode 100644 index 32ca756..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_acf249e215fca056266de6e833875925e_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.md5 deleted file mode 100644 index 1dff2e0..0000000 --- a/documentation/latex/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -42ba46cd39d520f16fc63c60adf56e33 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.pdf deleted file mode 100644 index b1e0f02..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_ae436161f7f0085f01ce63d9373944ae8_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.md5 deleted file mode 100644 index 73ea5d0..0000000 --- a/documentation/latex/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -49c4fcaf8468507aebe24f166623a665 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.pdf deleted file mode 100644 index 102e78f..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_ae4d70e11995e36808b6390b171aba0e8_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.md5 deleted file mode 100644 index 609d629..0000000 --- a/documentation/latex/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c1f99cc24b9e7cd3e2d107e90f84dc2e \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.pdf deleted file mode 100644 index 8c2b52f..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_af30c5c1549bda77b45a1e6fb5f76844a_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.md5 b/documentation/latex/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.md5 deleted file mode 100644 index 617b550..0000000 --- a/documentation/latex/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7f10d5b9d84ffe3242358c12393b5ba2 \ No newline at end of file diff --git a/documentation/latex/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.pdf b/documentation/latex/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.pdf deleted file mode 100644 index d4ecb5d..0000000 Binary files a/documentation/latex/_single_report_tests_8cpp_af9d07441bd8651bc21743664b7f99bb8_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/annotated.tex b/documentation/latex/annotated.tex deleted file mode 100644 index 3a563d5..0000000 --- a/documentation/latex/annotated.tex +++ /dev/null @@ -1,12 +0,0 @@ -\doxysection{Class List} -Here are the classes, structs, unions and interfaces with brief descriptions\+:\begin{DoxyCompactList} -\item\contentsline{section}{\mbox{\hyperlink{class_b_n_o08x}{BNO08x}} \\*\doxylink{class_b_n_o08x}{BNO08x} IMU driver class }{\pageref{class_b_n_o08x}}{} -\item\contentsline{section}{\mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}} \\*IMU configuration settings passed into constructor }{\pageref{structbno08x__config__t}}{} -\item\contentsline{section}{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t}{BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t}} \\*Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup) }{\pageref{struct_b_n_o08x_1_1bno08x__init__status__t}}{} -\item\contentsline{section}{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__report__period__tracker__t}{BNO08x\+::bno08x\+\_\+report\+\_\+period\+\_\+tracker\+\_\+t}} }{\pageref{struct_b_n_o08x_1_1bno08x__report__period__tracker__t}}{} -\item\contentsline{section}{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{BNO08x\+::bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \\*Holds data that is received over spi }{\pageref{struct_b_n_o08x_1_1bno08x__rx__packet__t}}{} -\item\contentsline{section}{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__tx__packet__t}{BNO08x\+::bno08x\+\_\+tx\+\_\+packet\+\_\+t}} \\*Holds data that is sent over spi }{\pageref{struct_b_n_o08x_1_1bno08x__tx__packet__t}}{} -\item\contentsline{section}{\mbox{\hyperlink{class_b_n_o08x_test_helper}{BNO08x\+Test\+Helper}} \\*\doxylink{class_b_n_o08x}{BNO08x} unit test helper class }{\pageref{class_b_n_o08x_test_helper}}{} -\item\contentsline{section}{\mbox{\hyperlink{class_b_n_o08x_test_suite}{BNO08x\+Test\+Suite}} \\*\doxylink{class_b_n_o08x}{BNO08x} unit test launch point class }{\pageref{class_b_n_o08x_test_suite}}{} -\item\contentsline{section}{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t}} \\*IMU configuration settings passed into constructor }{\pageref{struct_b_n_o08x_test_helper_1_1imu__report__data__t}}{} -\end{DoxyCompactList} diff --git a/documentation/latex/class_b_n_o08x.tex b/documentation/latex/class_b_n_o08x.tex deleted file mode 100644 index 44035e5..0000000 --- a/documentation/latex/class_b_n_o08x.tex +++ /dev/null @@ -1,7785 +0,0 @@ -\doxysection{BNO08x Class Reference} -\hypertarget{class_b_n_o08x}{}\label{class_b_n_o08x}\index{BNO08x@{BNO08x}} - - -\doxylink{class_b_n_o08x}{BNO08x} IMU driver class. - - - - -{\ttfamily \#include $<$BNO08x.\+hpp$>$} - - - -Collaboration diagram for BNO08x\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x__coll__graph} -\end{center} -\end{figure} -\doxysubsubsection*{Classes} -\begin{DoxyCompactItemize} -\item -struct \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t}{bno08x\+\_\+init\+\_\+status\+\_\+t}} -\begin{DoxyCompactList}\small\item\em Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup). \end{DoxyCompactList}\item -struct \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__report__period__tracker__t}{bno08x\+\_\+report\+\_\+period\+\_\+tracker\+\_\+t}} -\item -struct \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} -\begin{DoxyCompactList}\small\item\em Holds data that is received over spi. \end{DoxyCompactList}\item -struct \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__tx__packet__t}{bno08x\+\_\+tx\+\_\+packet\+\_\+t}} -\begin{DoxyCompactList}\small\item\em Holds data that is sent over spi. \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Public Member Functions} -\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{class_b_n_o08x_ad12fb6cf310ad7a04a4e53809833bd61}{BNO08x}} (\mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}} \mbox{\hyperlink{class_b_n_o08x_aeda443e9f608fccfec0e6770edc90c82}{imu\+\_\+config}}=\mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}}()) -\begin{DoxyCompactList}\small\item\em \doxylink{class_b_n_o08x}{BNO08x} imu constructor. \end{DoxyCompactList}\item -\mbox{\hyperlink{class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9}{\texorpdfstring{$\sim$}{\string~}\+BNO08x}} () -\begin{DoxyCompactList}\small\item\em \doxylink{class_b_n_o08x}{BNO08x} imu deconstructor. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798}{initialize}} () -\begin{DoxyCompactList}\small\item\em Initializes \doxylink{class_b_n_o08x}{BNO08x} sensor. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_a28cd1c0b3477571d87133234e6358503}{hard\+\_\+reset}} () -\begin{DoxyCompactList}\small\item\em Hard resets \doxylink{class_b_n_o08x}{BNO08x} sensor. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e}{soft\+\_\+reset}} () -\begin{DoxyCompactList}\small\item\em Soft resets \doxylink{class_b_n_o08x}{BNO08x} sensor using executable channel. \end{DoxyCompactList}\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147}{BNO08x\+Reset\+Reason}} \mbox{\hyperlink{class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85}{get\+\_\+reset\+\_\+reason}} () -\begin{DoxyCompactList}\small\item\em Requests product ID, prints the returned info over serial, and returns the reason for the most resent reset. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b}{mode\+\_\+sleep}} () -\begin{DoxyCompactList}\small\item\em Puts \doxylink{class_b_n_o08x}{BNO08x} sensor into sleep/low power mode using executable channel. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698}{mode\+\_\+on}} () -\begin{DoxyCompactList}\small\item\em Turns on/ brings \doxylink{class_b_n_o08x}{BNO08x} sensor out of sleep mode using executable channel. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9}{q\+\_\+to\+\_\+float}} (int16\+\_\+t fixed\+\_\+point\+\_\+value, uint8\+\_\+t q\+\_\+point) -\begin{DoxyCompactList}\small\item\em Converts a register value to a float using its associated Q point. (See \href{https://en.wikipedia.org/wiki/Q_(number_format)}{\texttt{ https\+://en.\+wikipedia.\+org/wiki/\+Q\+\_\+(number\+\_\+format)}}) \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a}{run\+\_\+full\+\_\+calibration\+\_\+routine}} () -\begin{DoxyCompactList}\small\item\em Runs full calibration routine. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128}{calibrate\+\_\+all}} () -\begin{DoxyCompactList}\small\item\em Sends command to calibrate accelerometer, gyro, and magnetometer. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc}{calibrate\+\_\+accelerometer}} () -\begin{DoxyCompactList}\small\item\em Sends command to calibrate accelerometer. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1}{calibrate\+\_\+gyro}} () -\begin{DoxyCompactList}\small\item\em Sends command to calibrate gyro. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a}{calibrate\+\_\+magnetometer}} () -\begin{DoxyCompactList}\small\item\em Sends command to calibrate magnetometer. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26}{calibrate\+\_\+planar\+\_\+accelerometer}} () -\begin{DoxyCompactList}\small\item\em Sends command to calibrate planar accelerometer. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11}{request\+\_\+calibration\+\_\+status}} () -\begin{DoxyCompactList}\small\item\em Requests ME calibration status from \doxylink{class_b_n_o08x}{BNO08x} (see Ref. Manual 6.\+4.\+7.\+2) \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b}{calibration\+\_\+complete}} () -\begin{DoxyCompactList}\small\item\em Returns true if calibration has completed. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2}{end\+\_\+calibration}} () -\begin{DoxyCompactList}\small\item\em Sends command to end calibration procedure. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54}{save\+\_\+calibration}} () -\begin{DoxyCompactList}\small\item\em Sends command to save internal calibration data (See Ref. Manual 6.\+4.\+7). \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7}{enable\+\_\+rotation\+\_\+vector}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable rotation vector reports (See Ref. Manual 6.\+5.\+18) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947}{enable\+\_\+game\+\_\+rotation\+\_\+vector}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable game rotation vector reports (See Ref. Manual 6.\+5.\+19) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc}{enable\+\_\+\+ARVR\+\_\+stabilized\+\_\+rotation\+\_\+vector}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6.\+5.\+42) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8}{enable\+\_\+\+ARVR\+\_\+stabilized\+\_\+game\+\_\+rotation\+\_\+vector}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6.\+5.\+43) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d}{enable\+\_\+gyro\+\_\+integrated\+\_\+rotation\+\_\+vector}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75}{enable\+\_\+uncalibrated\+\_\+gyro}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.\+5.\+14) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53}{enable\+\_\+calibrated\+\_\+gyro}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable calibrated gyro reports (See Ref. Manual 6.\+5.\+13) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91}{enable\+\_\+accelerometer}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable accelerometer reports (See Ref. Manual 6.\+5.\+9) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b}{enable\+\_\+linear\+\_\+accelerometer}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable linear accelerometer reports (See Ref. Manual 6.\+5.\+10) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a030eae12c3586acf09b48e94630b2544}{enable\+\_\+gravity}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable gravity reading reports (See Ref. Manual 6.\+5.\+11) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59}{enable\+\_\+magnetometer}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable magnetometer reports (See Ref. Manual 6.\+5.\+16) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566}{enable\+\_\+tap\+\_\+detector}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable tap detector reports (See Ref. Manual 6.\+5.\+27) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f}{enable\+\_\+step\+\_\+counter}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable step counter reports (See Ref. Manual 6.\+5.\+29) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655}{enable\+\_\+stability\+\_\+classifier}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable activity stability classifier reports (See Ref. Manual 6.\+5.\+31) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a039e8770759e784baa438324ae17883c}{enable\+\_\+activity\+\_\+classifier}} (uint32\+\_\+t time\+\_\+between\+\_\+reports, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0f}{BNO08x\+Activity\+Enable}} activities\+\_\+to\+\_\+enable, uint8\+\_\+t(\&activity\+\_\+confidence\+\_\+vals)\mbox{[}9\mbox{]}) -\begin{DoxyCompactList}\small\item\em Sends command to enable activity classifier reports (See Ref. Manual 6.\+5.\+36) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a8be135ed41646199540583b29806d4e5}{enable\+\_\+raw\+\_\+mems\+\_\+gyro}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable raw MEMs gyro reports (See Ref. Manual 6.\+5.\+12) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b}{enable\+\_\+raw\+\_\+mems\+\_\+accelerometer}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable raw MEMs accelerometer reports (See Ref. Manual 6.\+5.\+8) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5}{enable\+\_\+raw\+\_\+mems\+\_\+magnetometer}} (uint32\+\_\+t time\+\_\+between\+\_\+reports) -\begin{DoxyCompactList}\small\item\em Sends command to enable raw MEMs magnetometer reports (See Ref. Manual 6.\+5.\+15) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921}{disable\+\_\+rotation\+\_\+vector}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable rotation vector reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a7665cce95e791c89161ec863f49c0392}{disable\+\_\+game\+\_\+rotation\+\_\+vector}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable game rotation vector reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4}{disable\+\_\+\+ARVR\+\_\+stabilized\+\_\+rotation\+\_\+vector}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable ARVR stabilized rotation vector reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c}{disable\+\_\+\+ARVR\+\_\+stabilized\+\_\+game\+\_\+rotation\+\_\+vector}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable ARVR stabilized game rotation vector reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931}{disable\+\_\+gyro\+\_\+integrated\+\_\+rotation\+\_\+vector}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable gyro integrated rotation vector reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ad5c991150895b80bee68c933059a4058}{disable\+\_\+accelerometer}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable accelerometer reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f}{disable\+\_\+linear\+\_\+accelerometer}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable linear accelerometer reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f}{disable\+\_\+gravity}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable gravity reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c}{disable\+\_\+calibrated\+\_\+gyro}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable calibrated gyro reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc}{disable\+\_\+uncalibrated\+\_\+gyro}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable uncalibrated gyro reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338}{disable\+\_\+magnetometer}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable magnetometer reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a427550a4ba25252912436b899124e157}{disable\+\_\+step\+\_\+counter}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable step counter reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932}{disable\+\_\+stability\+\_\+classifier}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable stability reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376}{disable\+\_\+activity\+\_\+classifier}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable activity classifier reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2}{disable\+\_\+tap\+\_\+detector}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable tap detector reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce}{disable\+\_\+raw\+\_\+mems\+\_\+accelerometer}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable raw accelerometer reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725}{disable\+\_\+raw\+\_\+mems\+\_\+gyro}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable raw gyro reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2}{disable\+\_\+raw\+\_\+mems\+\_\+magnetometer}} () -\begin{DoxyCompactList}\small\item\em Sends command to disable raw magnetometer reports by setting report interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f}{tare\+\_\+now}} (uint8\+\_\+t axis\+\_\+sel=\mbox{\hyperlink{class_b_n_o08x_a1ef13f6f330810934416ad5fe0ee55b2}{TARE\+\_\+\+AXIS\+\_\+\+ALL}}, uint8\+\_\+t rotation\+\_\+vector\+\_\+basis=\mbox{\hyperlink{class_b_n_o08x_a8e2cfc25d0e34ae53a762b88cc3ac3c8}{TARE\+\_\+\+ROTATION\+\_\+\+VECTOR}}) -\begin{DoxyCompactList}\small\item\em Sends command to tare an axis (See Ref. Manual 6.\+4.\+4.\+1) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2}{save\+\_\+tare}} () -\begin{DoxyCompactList}\small\item\em Sends command to save tare into non-\/volatile memory of \doxylink{class_b_n_o08x}{BNO08x} (See Ref. Manual 6.\+4.\+4.\+2) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e}{clear\+\_\+tare}} () -\begin{DoxyCompactList}\small\item\em Sends command to clear persistent tare settings in non-\/volatile memory of \doxylink{class_b_n_o08x}{BNO08x} (See Ref. Manual 6.\+4.\+4.\+3) \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86}{data\+\_\+available}} (bool ignore\+\_\+no\+\_\+reports\+\_\+enabled=false) -\begin{DoxyCompactList}\small\item\em Checks if \doxylink{class_b_n_o08x}{BNO08x} has asserted interrupt and sent data. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a06bb0c70305421b5357e64f31579fdc7}{register\+\_\+cb}} (std\+::function$<$ void()$>$ cb\+\_\+fxn) -\begin{DoxyCompactList}\small\item\em Registers a callback to execute when new data from a report is received. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61}{reset\+\_\+all\+\_\+data\+\_\+to\+\_\+defaults}} () -\begin{DoxyCompactList}\small\item\em Resets all data returned by public getter APIs to initial values of 0 and low accuracy. \end{DoxyCompactList}\item -uint32\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ad9137777271421a58159f3fe5e05ed20}{get\+\_\+time\+\_\+stamp}} () -\begin{DoxyCompactList}\small\item\em Return timestamp of most recent report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb}{get\+\_\+magf}} (float \&x, float \&y, float \&z, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \&accuracy) -\begin{DoxyCompactList}\small\item\em Get the full magnetic field vector. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d}{get\+\_\+magf\+\_\+X}} () -\begin{DoxyCompactList}\small\item\em Get X component of magnetic field vector. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea}{get\+\_\+magf\+\_\+Y}} () -\begin{DoxyCompactList}\small\item\em Get Y component of magnetic field vector. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282}{get\+\_\+magf\+\_\+Z}} () -\begin{DoxyCompactList}\small\item\em Get Z component of magnetic field vector. \end{DoxyCompactList}\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \mbox{\hyperlink{class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9}{get\+\_\+magf\+\_\+accuracy}} () -\begin{DoxyCompactList}\small\item\em Get accuracy of reported magnetic field vector. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a067678914e928a6691625b17c40237a0}{get\+\_\+gravity}} (float \&x, float \&y, float \&z, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \&accuracy) -\begin{DoxyCompactList}\small\item\em Get full reported gravity vector, units in m/s\texorpdfstring{$^\wedge$}{\string^}2. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae}{get\+\_\+gravity\+\_\+X}} () -\begin{DoxyCompactList}\small\item\em Get the reported x axis gravity. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a8a36db7f1c932f33e05e494632059801}{get\+\_\+gravity\+\_\+Y}} () -\begin{DoxyCompactList}\small\item\em Get the reported y axis gravity. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807}{get\+\_\+gravity\+\_\+Z}} () -\begin{DoxyCompactList}\small\item\em Get the reported z axis gravity. \end{DoxyCompactList}\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \mbox{\hyperlink{class_b_n_o08x_a77c82cece30dde944efcde81643fd62d}{get\+\_\+gravity\+\_\+accuracy}} () -\begin{DoxyCompactList}\small\item\em Get the reported gravity accuracy. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a89618eba08186ee8e679e7313907ddef}{get\+\_\+roll}} () -\begin{DoxyCompactList}\small\item\em Get the reported rotation about x axis. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3}{get\+\_\+pitch}} () -\begin{DoxyCompactList}\small\item\em Get the reported rotation about y axis. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17}{get\+\_\+yaw}} () -\begin{DoxyCompactList}\small\item\em Get the reported rotation about z axis. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6}{get\+\_\+roll\+\_\+deg}} () -\begin{DoxyCompactList}\small\item\em Get the reported rotation about x axis. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_af50010400cbd1445e9ddfa259384b412}{get\+\_\+pitch\+\_\+deg}} () -\begin{DoxyCompactList}\small\item\em Get the reported rotation about y axis. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_af80f7795656e695e036d3b1557aed94c}{get\+\_\+yaw\+\_\+deg}} () -\begin{DoxyCompactList}\small\item\em Get the reported rotation about z axis. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a}{get\+\_\+quat}} (float \&i, float \&j, float \&k, float \&real, float \&rad\+\_\+accuracy, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \&accuracy) -\begin{DoxyCompactList}\small\item\em Get the full quaternion reading. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5}{get\+\_\+quat\+\_\+I}} () -\begin{DoxyCompactList}\small\item\em Get I component of reported quaternion. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015}{get\+\_\+quat\+\_\+J}} () -\begin{DoxyCompactList}\small\item\em Get J component of reported quaternion. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8}{get\+\_\+quat\+\_\+K}} () -\begin{DoxyCompactList}\small\item\em Get K component of reported quaternion. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7}{get\+\_\+quat\+\_\+real}} () -\begin{DoxyCompactList}\small\item\em Get real component of reported quaternion. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630}{get\+\_\+quat\+\_\+radian\+\_\+accuracy}} () -\begin{DoxyCompactList}\small\item\em Get radian accuracy of reported quaternion. \end{DoxyCompactList}\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \mbox{\hyperlink{class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654}{get\+\_\+quat\+\_\+accuracy}} () -\begin{DoxyCompactList}\small\item\em Get accuracy of reported quaternion. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885}{get\+\_\+accel}} (float \&x, float \&y, float \&z, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \&accuracy) -\begin{DoxyCompactList}\small\item\em Get full acceleration (total acceleration of device, units in m/s\texorpdfstring{$^\wedge$}{\string^}2). \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69}{get\+\_\+accel\+\_\+X}} () -\begin{DoxyCompactList}\small\item\em Get x axis acceleration (total acceleration of device, units in m/s\texorpdfstring{$^\wedge$}{\string^}2). \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1}{get\+\_\+accel\+\_\+Y}} () -\begin{DoxyCompactList}\small\item\em Get y axis acceleration (total acceleration of device, units in m/s\texorpdfstring{$^\wedge$}{\string^}2). \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1}{get\+\_\+accel\+\_\+Z}} () -\begin{DoxyCompactList}\small\item\em Get z axis acceleration (total acceleration of device, units in m/s\texorpdfstring{$^\wedge$}{\string^}2). \end{DoxyCompactList}\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \mbox{\hyperlink{class_b_n_o08x_a6eed9e2d3e639ec7e38dfdf092c14ea1}{get\+\_\+accel\+\_\+accuracy}} () -\begin{DoxyCompactList}\small\item\em Get accuracy of linear acceleration. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46}{get\+\_\+linear\+\_\+accel}} (float \&x, float \&y, float \&z, \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \&accuracy) -\begin{DoxyCompactList}\small\item\em Get full linear acceleration (acceleration of the device minus gravity, units in m/s\texorpdfstring{$^\wedge$}{\string^}2). \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3}{get\+\_\+linear\+\_\+accel\+\_\+X}} () -\begin{DoxyCompactList}\small\item\em Get x axis linear acceleration (acceleration of device minus gravity, units in m/s\texorpdfstring{$^\wedge$}{\string^}2) \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191}{get\+\_\+linear\+\_\+accel\+\_\+Y}} () -\begin{DoxyCompactList}\small\item\em Get y axis linear acceleration (acceleration of device minus gravity, units in m/s\texorpdfstring{$^\wedge$}{\string^}2) \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84}{get\+\_\+linear\+\_\+accel\+\_\+Z}} () -\begin{DoxyCompactList}\small\item\em Get z axis linear acceleration (acceleration of device minus gravity, units in m/s\texorpdfstring{$^\wedge$}{\string^}2) \end{DoxyCompactList}\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \mbox{\hyperlink{class_b_n_o08x_a6114ba3c8967ac8fde06233c81623c80}{get\+\_\+linear\+\_\+accel\+\_\+accuracy}} () -\begin{DoxyCompactList}\small\item\em Get accuracy of linear acceleration. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_aa6bbad8c9123b4dba5007f72a8806303}{get\+\_\+raw\+\_\+mems\+\_\+accel}} (uint16\+\_\+t \&x, uint16\+\_\+t \&y, uint16\+\_\+t \&z) -\begin{DoxyCompactList}\small\item\em Get full raw acceleration from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8). \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a868b24d96cb12f614431a410bcc9e434}{get\+\_\+raw\+\_\+mems\+\_\+accel\+\_\+X}} () -\begin{DoxyCompactList}\small\item\em Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aebcbaf9c3aaf37d85a78d22dc22c614a}{get\+\_\+raw\+\_\+mems\+\_\+accel\+\_\+Y}} () -\begin{DoxyCompactList}\small\item\em Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a85d1331ebe762f6823bde4bf76a33e21}{get\+\_\+raw\+\_\+mems\+\_\+accel\+\_\+Z}} () -\begin{DoxyCompactList}\small\item\em Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27}{get\+\_\+raw\+\_\+mems\+\_\+gyro}} (uint16\+\_\+t \&x, uint16\+\_\+t \&y, uint16\+\_\+t \&z) -\begin{DoxyCompactList}\small\item\em Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a8872241c73bca2ac1698ae867f7d1913}{get\+\_\+raw\+\_\+mems\+\_\+gyro\+\_\+X}} () -\begin{DoxyCompactList}\small\item\em Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a4bcc58423b5cc7c24080c2ef812d3d86}{get\+\_\+raw\+\_\+mems\+\_\+gyro\+\_\+Y}} () -\begin{DoxyCompactList}\small\item\em Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ae684dd13ef630dfdbb8de18ee5ea90bb}{get\+\_\+raw\+\_\+mems\+\_\+gyro\+\_\+Z}} () -\begin{DoxyCompactList}\small\item\em Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a929ad333f73614fb5830c186e3e03a00}{get\+\_\+raw\+\_\+mems\+\_\+magf}} (uint16\+\_\+t \&x, uint16\+\_\+t \&y, uint16\+\_\+t \&z) -\begin{DoxyCompactList}\small\item\em Get raw magnetometer full reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a347444f461b2fab5ff37de346ba2a595}{get\+\_\+raw\+\_\+mems\+\_\+magf\+\_\+X}} () -\begin{DoxyCompactList}\small\item\em Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ad8a215314ae96b25b59fdc363c52261c}{get\+\_\+raw\+\_\+mems\+\_\+magf\+\_\+Y}} () -\begin{DoxyCompactList}\small\item\em Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a780651af54485edb36d197f30c071615}{get\+\_\+raw\+\_\+mems\+\_\+magf\+\_\+Z}} () -\begin{DoxyCompactList}\small\item\em Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f}{get\+\_\+calibrated\+\_\+gyro\+\_\+velocity}} (float \&x, float \&y, float \&z) -\begin{DoxyCompactList}\small\item\em Get full rotational velocity with drift compensation (units in Rad/s). \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889}{get\+\_\+calibrated\+\_\+gyro\+\_\+velocity\+\_\+X}} () -\begin{DoxyCompactList}\small\item\em Get calibrated gyro x axis angular velocity measurement. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50}{get\+\_\+calibrated\+\_\+gyro\+\_\+velocity\+\_\+Y}} () -\begin{DoxyCompactList}\small\item\em Get calibrated gyro y axis angular velocity measurement. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea}{get\+\_\+calibrated\+\_\+gyro\+\_\+velocity\+\_\+Z}} () -\begin{DoxyCompactList}\small\item\em Get calibrated gyro z axis angular velocity measurement. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104}{get\+\_\+uncalibrated\+\_\+gyro\+\_\+velocity}} (float \&x, float \&y, float \&z, float \&bx, float \&by, float \&bz) -\begin{DoxyCompactList}\small\item\em Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is given but not applied. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486}{get\+\_\+uncalibrated\+\_\+gyro\+\_\+velocity\+\_\+X}} () -\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro x axis angular velocity measurement. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de}{get\+\_\+uncalibrated\+\_\+gyro\+\_\+velocity\+\_\+Y}} () -\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro Y axis angular velocity measurement. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592}{get\+\_\+uncalibrated\+\_\+gyro\+\_\+velocity\+\_\+Z}} () -\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro Z axis angular velocity measurement. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b}{get\+\_\+uncalibrated\+\_\+gyro\+\_\+bias\+\_\+X}} () -\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro x axis drift estimate. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a74725517129dd548c7a3de705d5861bd}{get\+\_\+uncalibrated\+\_\+gyro\+\_\+bias\+\_\+Y}} () -\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro Y axis drift estimate. \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7}{get\+\_\+uncalibrated\+\_\+gyro\+\_\+bias\+\_\+Z}} () -\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro Z axis drift estimate. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f}{get\+\_\+integrated\+\_\+gyro\+\_\+velocity}} (float \&x, float \&y, float \&z) -\begin{DoxyCompactList}\small\item\em Full rotational velocity from gyro-\/integrated rotation vector (See Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff}{get\+\_\+integrated\+\_\+gyro\+\_\+velocity\+\_\+X}} () -\begin{DoxyCompactList}\small\item\em Get x axis angular velocity from gyro-\/integrated rotation vector. (See Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1}{get\+\_\+integrated\+\_\+gyro\+\_\+velocity\+\_\+Y}} () -\begin{DoxyCompactList}\small\item\em Get y axis angular velocity from gyro-\/integrated rotation vector. (See Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add}{get\+\_\+integrated\+\_\+gyro\+\_\+velocity\+\_\+Z}} () -\begin{DoxyCompactList}\small\item\em Get z axis angular velocity from gyro-\/integrated rotation vector. (See Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item -uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a4797ec731de4c158716da1a7af9d1602}{get\+\_\+tap\+\_\+detector}} () -\begin{DoxyCompactList}\small\item\em Get if tap has occured. \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef}{get\+\_\+step\+\_\+count}} () -\begin{DoxyCompactList}\small\item\em Get the counted amount of steps. \end{DoxyCompactList}\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}{BNO08x\+Stability}} \mbox{\hyperlink{class_b_n_o08x_a248544b262582d10d917a687190cb454}{get\+\_\+stability\+\_\+classifier}} () -\begin{DoxyCompactList}\small\item\em Get the current stability classifier (Seee Ref. Manual 6.\+5.\+31) \end{DoxyCompactList}\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}{BNO08x\+Activity}} \mbox{\hyperlink{class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed}{get\+\_\+activity\+\_\+classifier}} () -\begin{DoxyCompactList}\small\item\em Get the current activity classifier (Seee Ref. Manual 6.\+5.\+36) \end{DoxyCompactList}\item -int16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a4421c43323945946ad605f8422958dcf}{get\+\_\+\+Q1}} (uint16\+\_\+t record\+\_\+\+ID) -\begin{DoxyCompactList}\small\item\em Gets Q1 point from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system). \end{DoxyCompactList}\item -int16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b}{get\+\_\+\+Q2}} (uint16\+\_\+t record\+\_\+\+ID) -\begin{DoxyCompactList}\small\item\em Gets Q2 point from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system). \end{DoxyCompactList}\item -int16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a}{get\+\_\+\+Q3}} (uint16\+\_\+t record\+\_\+\+ID) -\begin{DoxyCompactList}\small\item\em Gets Q3 point from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system). \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372}{get\+\_\+resolution}} (uint16\+\_\+t record\+\_\+\+ID) -\begin{DoxyCompactList}\small\item\em Gets resolution from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system). \end{DoxyCompactList}\item -float \mbox{\hyperlink{class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0}{get\+\_\+range}} (uint16\+\_\+t record\+\_\+\+ID) -\begin{DoxyCompactList}\small\item\em Gets range from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system). \end{DoxyCompactList}\item -uint32\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41}{FRS\+\_\+read\+\_\+word}} (uint16\+\_\+t record\+\_\+\+ID, uint8\+\_\+t word\+\_\+number) -\begin{DoxyCompactList}\small\item\em Reads meta data word from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system) given the record ID and word number. (See Ref. Manual 5.\+1 \& 6.\+3.\+7) \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_adf789e709ac1667656db757c8d559af9}{FRS\+\_\+read\+\_\+request}} (uint16\+\_\+t record\+\_\+\+ID, uint16\+\_\+t read\+\_\+offset, uint16\+\_\+t block\+\_\+size) -\begin{DoxyCompactList}\small\item\em Requests meta data from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.\+1 \& 6.\+3.\+6) \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1}{FRS\+\_\+read\+\_\+data}} (uint16\+\_\+t record\+\_\+\+ID, uint8\+\_\+t start\+\_\+location, uint8\+\_\+t words\+\_\+to\+\_\+read) -\begin{DoxyCompactList}\small\item\em Read meta data from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.\+1 \& 6.\+3.\+7) \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Static Public Attributes} -\begin{DoxyCompactItemize} -\item -static const constexpr uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ad7ef7d7068af5f92239c12022dbeb16d}{FRS\+\_\+\+RECORD\+\_\+\+ID\+\_\+\+ACCELEROMETER}} -\begin{DoxyCompactList}\small\item\em Accelerometer record ID, to be passed in metadata functions like \doxylink{class_b_n_o08x_a4421c43323945946ad605f8422958dcf}{get\+\_\+\+Q1()} \end{DoxyCompactList}\item -static const constexpr uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a35d8f641e73c308f92a5a0a772f90f48}{FRS\+\_\+\+RECORD\+\_\+\+ID\+\_\+\+GYROSCOPE\+\_\+\+CALIBRATED}} -\begin{DoxyCompactList}\small\item\em Calirated gyroscope record ID, to be passed in metadata functions like \doxylink{class_b_n_o08x_a4421c43323945946ad605f8422958dcf}{get\+\_\+\+Q1()} \end{DoxyCompactList}\item -static const constexpr uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a0992d77f9bae0b8e3c8d9331fe84fe24}{FRS\+\_\+\+RECORD\+\_\+\+ID\+\_\+\+MAGNETIC\+\_\+\+FIELD\+\_\+\+CALIBRATED}} -\begin{DoxyCompactList}\small\item\em Calibrated magnetometer record ID, to be passed in metadata functions like \doxylink{class_b_n_o08x_a4421c43323945946ad605f8422958dcf}{get\+\_\+\+Q1()} \end{DoxyCompactList}\item -static const constexpr uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a9f35840b19c8ad11fd1b4622c3269250}{FRS\+\_\+\+RECORD\+\_\+\+ID\+\_\+\+ROTATION\+\_\+\+VECTOR}} -\begin{DoxyCompactList}\small\item\em Rotation vector record ID, to be passed in metadata functions like \doxylink{class_b_n_o08x_a4421c43323945946ad605f8422958dcf}{get\+\_\+\+Q1()} \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a1ef13f6f330810934416ad5fe0ee55b2}{TARE\+\_\+\+AXIS\+\_\+\+ALL}} = 0x07U -\begin{DoxyCompactList}\small\item\em Tare all axes (used with tare now command) \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aecb3e11c1ca5769fd60f42c17a105731}{TARE\+\_\+\+AXIS\+\_\+Z}} = 0x04U -\begin{DoxyCompactList}\small\item\em Tar yaw axis only (used with tare now command) \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a8e2cfc25d0e34ae53a762b88cc3ac3c8}{TARE\+\_\+\+ROTATION\+\_\+\+VECTOR}} = 0U -\begin{DoxyCompactList}\small\item\em Tare rotation vector. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_abaf1ec8bb197db1998a9ed3cec6180d5}{TARE\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR}} = 1U -\begin{DoxyCompactList}\small\item\em Tare game rotation vector. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a225397a04d849e5647992ca80d68febb}{TARE\+\_\+\+GEOMAGNETIC\+\_\+\+ROTATION\+\_\+\+VECTOR}} = 2U -\begin{DoxyCompactList}\small\item\em tare geomagnetic rotation vector \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a9ec354d75249f06f13599abf7bedfde0}{TARE\+\_\+\+GYRO\+\_\+\+INTEGRATED\+\_\+\+ROTATION\+\_\+\+VECTOR}} = 3U -\begin{DoxyCompactList}\small\item\em Tare gyro integrated rotation vector. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_abff9abe904bcdde951cf88c378284b45}{TARE\+\_\+\+ARVR\+\_\+\+STABILIZED\+\_\+\+ROTATION\+\_\+\+VECTOR}} = 4U -\begin{DoxyCompactList}\small\item\em Tare ARVR stabilized rotation vector. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a68aaaab144adbe5af00597408f044d9d}{TARE\+\_\+\+ARVR\+\_\+\+STABILIZED\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR}} = 5U -\begin{DoxyCompactList}\small\item\em Tare ARVR stabilized game rotation vector. \end{DoxyCompactList}\item -static const constexpr int16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a0b19c8f2de2b2bfe033da7f93cdd2608}{ROTATION\+\_\+\+VECTOR\+\_\+\+Q1}} = 14 -\begin{DoxyCompactList}\small\item\em Rotation vector Q point (See SH-\/2 Ref. Manual 6.\+5.\+18) \end{DoxyCompactList}\item -static const constexpr int16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a923d65d8568cc31873ad56a3908e1939}{ROTATION\+\_\+\+VECTOR\+\_\+\+ACCURACY\+\_\+\+Q1}} = 12 -\begin{DoxyCompactList}\small\item\em Rotation vector accuracy estimate Q point (See SH-\/2 Ref. Manual 6.\+5.\+18) \end{DoxyCompactList}\item -static const constexpr int16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a0564aaf5b20dc42b54db4fb3115ac1c7}{ACCELEROMETER\+\_\+\+Q1}} = 8 -\begin{DoxyCompactList}\small\item\em Acceleration Q point (See SH-\/2 Ref. Manual 6.\+5.\+9) \end{DoxyCompactList}\item -static const constexpr int16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ad0d37fe07ced24f2c9afc21145a74e7b}{LINEAR\+\_\+\+ACCELEROMETER\+\_\+\+Q1}} = 8 -\begin{DoxyCompactList}\small\item\em Linear acceleration Q point (See SH-\/2 Ref. Manual 6.\+5.\+10) \end{DoxyCompactList}\item -static const constexpr int16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aa3bec8effefa61cec6fa170e9d02c4dd}{GYRO\+\_\+\+Q1}} = 9 -\begin{DoxyCompactList}\small\item\em Gyro Q point (See SH-\/2 Ref. Manual 6.\+5.\+13) \end{DoxyCompactList}\item -static const constexpr int16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a9fac9b811b7c2117675a784cb4df204c}{MAGNETOMETER\+\_\+\+Q1}} = 4 -\begin{DoxyCompactList}\small\item\em Magnetometer Q point (See SH-\/2 Ref. Manual 6.\+5.\+16) \end{DoxyCompactList}\item -static const constexpr int16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aafe117561fe9138800073a04a778b4ce}{ANGULAR\+\_\+\+VELOCITY\+\_\+\+Q1}} = 10 -\begin{DoxyCompactList}\small\item\em Angular velocity Q point (See SH-\/2 Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item -static const constexpr int16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ae10722334dfce9635e76519598e165a2}{GRAVITY\+\_\+\+Q1}} = 8 -\begin{DoxyCompactList}\small\item\em Gravity Q point (See SH-\/2 Ref. Manual 6.\+5.\+11) \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Private Types} -\begin{DoxyCompactItemize} -\item -enum \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638f}{channels\+\_\+t}} \{ \newline -\mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fad116268ebf7fb5e5cb4795ccc27867ed}{CHANNEL\+\_\+\+COMMAND}} -, \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fab1f28434b161c7ffa7b1a5c5f1a8a95b}{CHANNEL\+\_\+\+EXECUTABLE}} -, \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fa5b5d133bf4a91e14741fdd8e635e897e}{CHANNEL\+\_\+\+CONTROL}} -, \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fabeb0a4983bc57ad2ce9f98360742e03e}{CHANNEL\+\_\+\+REPORTS}} -, \newline -\mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638faefb874de7f2f90fb99b42bedf9623d21}{CHANNEL\+\_\+\+WAKE\+\_\+\+REPORTS}} -, \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fadd3caa696e525dd901de7a8e3dbf0731}{CHANNEL\+\_\+\+GYRO}} - \} -\begin{DoxyCompactList}\small\item\em SHTP protocol channels. \end{DoxyCompactList}\item -typedef struct BNO08x\+::bno08x\+\_\+rx\+\_\+packet\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} -\begin{DoxyCompactList}\small\item\em Holds data that is received over spi. \end{DoxyCompactList}\item -typedef struct BNO08x\+::bno08x\+\_\+tx\+\_\+packet\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a3a1a869ac69e6ee850bd2a7f90dd8945}{bno08x\+\_\+tx\+\_\+packet\+\_\+t}} -\begin{DoxyCompactList}\small\item\em Holds data that is sent over spi. \end{DoxyCompactList}\item -typedef struct BNO08x\+::bno08x\+\_\+report\+\_\+period\+\_\+tracker\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ae87c0e3c6eb34e209855d8e5d48c624b}{bno08x\+\_\+report\+\_\+period\+\_\+tracker\+\_\+t}} -\item -typedef struct BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a200dfd32391bcaff73e8498674c7ec87}{bno08x\+\_\+init\+\_\+status\+\_\+t}} -\begin{DoxyCompactList}\small\item\em Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup). \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Private Member Functions} -\begin{DoxyCompactItemize} -\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d}{init\+\_\+config\+\_\+args}} () -\begin{DoxyCompactList}\small\item\em Initializes required esp-\/idf SPI data structures with values from user passed \doxylink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t} struct. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10}{init\+\_\+gpio}} () -\begin{DoxyCompactList}\small\item\em Initializes required gpio. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4}{init\+\_\+gpio\+\_\+inputs}} () -\begin{DoxyCompactList}\small\item\em Initializes required gpio inputs. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64}{init\+\_\+gpio\+\_\+outputs}} () -\begin{DoxyCompactList}\small\item\em Initializes required gpio outputs. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61}{init\+\_\+hint\+\_\+isr}} () -\begin{DoxyCompactList}\small\item\em Initializes host interrupt ISR. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81}{init\+\_\+spi}} () -\begin{DoxyCompactList}\small\item\em Initializes SPI. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3}{deinit\+\_\+gpio}} () -\begin{DoxyCompactList}\small\item\em Deinitializes GPIO, called from deconstructor. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c}{deinit\+\_\+gpio\+\_\+inputs}} () -\begin{DoxyCompactList}\small\item\em Deinitializes GPIO inputs, called from deconstructor. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ab132a061bd437fd109225446aa1f6010}{deinit\+\_\+gpio\+\_\+outputs}} () -\begin{DoxyCompactList}\small\item\em Deinitializes GPIO outputs, called from deconstructor. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758}{deinit\+\_\+hint\+\_\+isr}} () -\begin{DoxyCompactList}\small\item\em Deinitializes host interrupt ISR, called from deconstructor. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a233920ce97f685fbdabecccacf471d85}{deinit\+\_\+spi}} () -\begin{DoxyCompactList}\small\item\em Deinitializes SPI. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e}{wait\+\_\+for\+\_\+rx\+\_\+done}} () -\begin{DoxyCompactList}\small\item\em Waits for data to be received over SPI, or host\+\_\+int\+\_\+timeout\+\_\+ms to elapse. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773}{wait\+\_\+for\+\_\+tx\+\_\+done}} () -\begin{DoxyCompactList}\small\item\em Waits for a queued packet to be sent or host\+\_\+int\+\_\+timeout\+\_\+ms to elapse. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf}{wait\+\_\+for\+\_\+data}} () -\begin{DoxyCompactList}\small\item\em Waits for a valid or invalid packet to be received or host\+\_\+int\+\_\+timeout\+\_\+ms to elapse. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638}{receive\+\_\+packet}} () -\begin{DoxyCompactList}\small\item\em Receives a SHTP packet via SPI and sends it to \doxylink{class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8}{data\+\_\+proc\+\_\+task()} \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_acb246769719351e02bf2aff06d039475}{receive\+\_\+packet\+\_\+header}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Receives a SHTP packet header via SPI. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c}{receive\+\_\+packet\+\_\+body}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Receives a SHTP packet body via SPI. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a}{send\+\_\+packet}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__tx__packet__t}{bno08x\+\_\+tx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Sends a queued SHTP packet via SPI. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc}{flush\+\_\+rx\+\_\+packets}} (uint8\+\_\+t flush\+\_\+count) -\item -void \mbox{\hyperlink{class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca}{enable\+\_\+report}} (uint8\+\_\+t report\+\_\+\+ID, uint32\+\_\+t time\+\_\+between\+\_\+reports, const Event\+Bits\+\_\+t report\+\_\+evt\+\_\+grp\+\_\+bit, uint32\+\_\+t special\+\_\+config=0) -\begin{DoxyCompactList}\small\item\em Enables a sensor report for a given ID. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693}{disable\+\_\+report}} (uint8\+\_\+t report\+\_\+\+ID, const Event\+Bits\+\_\+t report\+\_\+evt\+\_\+grp\+\_\+bit) -\begin{DoxyCompactList}\small\item\em Disables a sensor report for a given ID by setting its time interval to 0. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f}{queue\+\_\+packet}} (uint8\+\_\+t channel\+\_\+number, uint8\+\_\+t data\+\_\+length, uint8\+\_\+t \texorpdfstring{$\ast$}{*}commands) -\begin{DoxyCompactList}\small\item\em Queues an SHTP packet to be sent via SPI. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9}{queue\+\_\+command}} (uint8\+\_\+t command, uint8\+\_\+t \texorpdfstring{$\ast$}{*}commands) -\begin{DoxyCompactList}\small\item\em Queues a packet containing a command. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3}{queue\+\_\+feature\+\_\+command}} (uint8\+\_\+t report\+\_\+\+ID, uint32\+\_\+t time\+\_\+between\+\_\+reports, uint32\+\_\+t specific\+\_\+config=0) -\begin{DoxyCompactList}\small\item\em Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.\+5.\+4) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91}{queue\+\_\+calibrate\+\_\+command}} (uint8\+\_\+t \+\_\+to\+\_\+calibrate) -\begin{DoxyCompactList}\small\item\em Queues a packet containing a command to calibrate the specified sensor. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2}{queue\+\_\+tare\+\_\+command}} (uint8\+\_\+t command, uint8\+\_\+t axis=\mbox{\hyperlink{class_b_n_o08x_a1ef13f6f330810934416ad5fe0ee55b2}{TARE\+\_\+\+AXIS\+\_\+\+ALL}}, uint8\+\_\+t rotation\+\_\+vector\+\_\+basis=\mbox{\hyperlink{class_b_n_o08x_a8e2cfc25d0e34ae53a762b88cc3ac3c8}{TARE\+\_\+\+ROTATION\+\_\+\+VECTOR}}) -\begin{DoxyCompactList}\small\item\em Queues a packet containing a command related to zeroing sensor\textquotesingle{}s axes. (See Ref. Manual 6.\+4.\+4.\+1) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1}{queue\+\_\+request\+\_\+product\+\_\+id\+\_\+command}} () -\begin{DoxyCompactList}\small\item\em Queues a packet containing the request product ID command. \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924}{parse\+\_\+packet}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet, bool \¬ify\+\_\+users) -\begin{DoxyCompactList}\small\item\em Parses a packet received from bno08x, updating any data according to received reports. \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036}{parse\+\_\+product\+\_\+id\+\_\+report}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Parses product id report and prints device info. \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a51b360d795563b55559f11efb40be36a}{parse\+\_\+frs\+\_\+read\+\_\+response\+\_\+report}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Sends packet to be parsed to meta data function call (\doxylink{class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1}{FRS\+\_\+read\+\_\+data()}) through queue. \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981}{parse\+\_\+feature\+\_\+get\+\_\+response\+\_\+report}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Parses get feature request report received from \doxylink{class_b_n_o08x}{BNO08x}. \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d}{parse\+\_\+input\+\_\+report}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Parses received input report sent by \doxylink{class_b_n_o08x}{BNO08x}. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55}{parse\+\_\+input\+\_\+report\+\_\+data}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet, uint16\+\_\+t \texorpdfstring{$\ast$}{*}data, uint16\+\_\+t data\+\_\+length) -\begin{DoxyCompactList}\small\item\em Parses data from received input report. \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d}{parse\+\_\+gyro\+\_\+integrated\+\_\+rotation\+\_\+vector\+\_\+report}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Parses received gyro integrated rotation vector report sent by \doxylink{class_b_n_o08x}{BNO08x}. \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7}{parse\+\_\+command\+\_\+report}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Parses received command report sent by \doxylink{class_b_n_o08x}{BNO08x} (See Ref. Manual 6.\+3.\+9) \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_afe588fbd0055193d3bc08984d7732354}{update\+\_\+accelerometer\+\_\+data}} (uint16\+\_\+t \texorpdfstring{$\ast$}{*}data, uint8\+\_\+t status) -\begin{DoxyCompactList}\small\item\em Updates accelerometer data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708}{update\+\_\+lin\+\_\+accelerometer\+\_\+data}} (uint16\+\_\+t \texorpdfstring{$\ast$}{*}data, uint8\+\_\+t status) -\begin{DoxyCompactList}\small\item\em Updates linear accelerometer data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab}{update\+\_\+calibrated\+\_\+gyro\+\_\+data}} (uint16\+\_\+t \texorpdfstring{$\ast$}{*}data, uint8\+\_\+t status) -\begin{DoxyCompactList}\small\item\em Updates linear gyro data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e}{update\+\_\+uncalibrated\+\_\+gyro\+\_\+data}} (uint16\+\_\+t \texorpdfstring{$\ast$}{*}data, uint8\+\_\+t status) -\begin{DoxyCompactList}\small\item\em Updates uncalibrated gyro data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88}{update\+\_\+magf\+\_\+data}} (uint16\+\_\+t \texorpdfstring{$\ast$}{*}data, uint8\+\_\+t status) -\begin{DoxyCompactList}\small\item\em Updates magnetic field data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e}{update\+\_\+gravity\+\_\+data}} (uint16\+\_\+t \texorpdfstring{$\ast$}{*}data, uint8\+\_\+t status) -\begin{DoxyCompactList}\small\item\em Updates gravity data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b}{update\+\_\+rotation\+\_\+vector\+\_\+data}} (uint16\+\_\+t \texorpdfstring{$\ast$}{*}data, uint8\+\_\+t status) -\begin{DoxyCompactList}\small\item\em Updates roation vector data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f}{update\+\_\+step\+\_\+counter\+\_\+data}} (uint16\+\_\+t \texorpdfstring{$\ast$}{*}data) -\begin{DoxyCompactList}\small\item\em Updates step counter data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22}{update\+\_\+raw\+\_\+accelerometer\+\_\+data}} (uint16\+\_\+t \texorpdfstring{$\ast$}{*}data) -\begin{DoxyCompactList}\small\item\em Updates raw accelerometer data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea}{update\+\_\+raw\+\_\+gyro\+\_\+data}} (uint16\+\_\+t \texorpdfstring{$\ast$}{*}data) -\begin{DoxyCompactList}\small\item\em Updates raw gyro data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245}{update\+\_\+raw\+\_\+magf\+\_\+data}} (uint16\+\_\+t \texorpdfstring{$\ast$}{*}data) -\begin{DoxyCompactList}\small\item\em Updates raw magnetic field data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1}{update\+\_\+tap\+\_\+detector\+\_\+data}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Updates tap detector data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a358316b883928c50dd381f024e6b0645}{update\+\_\+stability\+\_\+classifier\+\_\+data}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Updates stability classifier data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0}{update\+\_\+personal\+\_\+activity\+\_\+classifier\+\_\+data}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Updates activity classifier data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c}{update\+\_\+command\+\_\+data}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Updates command data from parsed input report. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab}{update\+\_\+integrated\+\_\+gyro\+\_\+rotation\+\_\+vector\+\_\+data}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Updates integrated gyro rotation vector data from SHTP channel 5 (CHANNEL\+\_\+\+GYRO) special report data. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a35856c108a47de8b3b38c4395aabb4eb}{print\+\_\+header}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Prints the header of the passed SHTP packet to serial console with ESP\+\_\+\+LOG statement. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49}{print\+\_\+packet}} (\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}packet) -\begin{DoxyCompactList}\small\item\em Prints the passed SHTP packet to serial console with ESP\+\_\+\+LOG statement. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf}{spi\+\_\+task}} () -\begin{DoxyCompactList}\small\item\em Task responsible for SPI transactions. Executed when HINT in is asserted by \doxylink{class_b_n_o08x}{BNO08x}. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8}{data\+\_\+proc\+\_\+task}} () -\begin{DoxyCompactList}\small\item\em Task responsible parsing packets. Executed when SPI task sends a packet to be parsed, notifies \doxylink{class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf}{wait\+\_\+for\+\_\+data()} call. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be}{launch\+\_\+tasks}} () -\begin{DoxyCompactList}\small\item\em Launches spi\+\_\+task and data\+\_\+proc\+\_\+task on constructor call. \end{DoxyCompactList}\item -esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0}{kill\+\_\+all\+\_\+tasks}} () -\begin{DoxyCompactList}\small\item\em Deletes spi\+\_\+task and data\+\_\+proc\+\_\+task safely on deconstructor call. \end{DoxyCompactList}\item -void \mbox{\hyperlink{class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64}{update\+\_\+report\+\_\+period\+\_\+trackers}} (uint8\+\_\+t report\+\_\+\+ID, uint32\+\_\+t new\+\_\+period) -\begin{DoxyCompactList}\small\item\em Updates period of respective report in report\+\_\+period\+\_\+trackers and recalculates host\+\_\+int\+\_\+timeout\+\_\+ms according to next longest report period. \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Static Private Member Functions} -\begin{DoxyCompactItemize} -\item -static void \mbox{\hyperlink{class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74}{spi\+\_\+task\+\_\+trampoline}} (void \texorpdfstring{$\ast$}{*}arg) -\begin{DoxyCompactList}\small\item\em Static function used to launch spi task. \end{DoxyCompactList}\item -static void \mbox{\hyperlink{class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520}{data\+\_\+proc\+\_\+task\+\_\+trampoline}} (void \texorpdfstring{$\ast$}{*}arg) -\begin{DoxyCompactList}\small\item\em Static function used to launch data processing task. \end{DoxyCompactList}\item -static uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa}{report\+\_\+\+ID\+\_\+to\+\_\+report\+\_\+period\+\_\+tracker\+\_\+idx}} (uint8\+\_\+t report\+\_\+\+ID) -\begin{DoxyCompactList}\small\item\em Converts report id to respective index in report\+\_\+period\+\_\+trackers. \end{DoxyCompactList}\item -static void IRAM\+\_\+\+ATTR \mbox{\hyperlink{class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7}{hint\+\_\+handler}} (void \texorpdfstring{$\ast$}{*}arg) -\begin{DoxyCompactList}\small\item\em HINT interrupt service routine, handles falling edge of \doxylink{class_b_n_o08x}{BNO08x} HINT pin. \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Private Attributes} -\begin{DoxyCompactItemize} -\item -bool \mbox{\hyperlink{class_b_n_o08x_ae4670fed6de963a087ab58f95fda319b}{first\+\_\+boot}} = true -\begin{DoxyCompactList}\small\item\em true only for first execution of \doxylink{class_b_n_o08x_a28cd1c0b3477571d87133234e6358503}{hard\+\_\+reset()}, used to suppress the printing of product ID report. \end{DoxyCompactList}\item -Task\+Handle\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a615090aae15f1b0410a7e5ecb94957b5}{spi\+\_\+task\+\_\+hdl}} -\begin{DoxyCompactList}\small\item\em \doxylink{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf}{spi\+\_\+task()} handle \end{DoxyCompactList}\item -Task\+Handle\+\_\+t \mbox{\hyperlink{class_b_n_o08x_af9b6fbf35e7cd55d517d30c6429a21a4}{data\+\_\+proc\+\_\+task\+\_\+hdl}} -\begin{DoxyCompactList}\small\item\em \doxylink{class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8}{data\+\_\+proc\+\_\+task()} task handle \end{DoxyCompactList}\item -Semaphore\+Handle\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aa92ff86d82a097a565ed2a2b9000b571}{sem\+\_\+kill\+\_\+tasks}} -\begin{DoxyCompactList}\small\item\em semaphore to count amount of killed tasks \end{DoxyCompactList}\item -Event\+Group\+Handle\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aa2b4442b5cc63ebf0c495e6fb537c85e}{evt\+\_\+grp\+\_\+spi}} -\begin{DoxyCompactList}\small\item\em Event group for indicating when bno08x hint pin has triggered and when new data has been processed. Used by calls to sending or receiving functions. \end{DoxyCompactList}\item -Event\+Group\+Handle\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a63eb6c8be6f3bc943a86bb0496871275}{evt\+\_\+grp\+\_\+report\+\_\+en}} -\begin{DoxyCompactList}\small\item\em Event group for indicating which reports are currently enabled. \end{DoxyCompactList}\item -Event\+Group\+Handle\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ac4b1fae7a1155c8b93b645b4eb6eb0f1}{evt\+\_\+grp\+\_\+task\+\_\+flow}} -\begin{DoxyCompactList}\small\item\em Event group for indicating when tasks should complete and self-\/delete (on deconstructor call) \end{DoxyCompactList}\item -Queue\+Handle\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a7d4661d3aae56013caa8f2bff0f67c08}{queue\+\_\+rx\+\_\+data}} -\begin{DoxyCompactList}\small\item\em Packet queue used to send data received from bno08x from spi\+\_\+task to data\+\_\+proc\+\_\+task. \end{DoxyCompactList}\item -Queue\+Handle\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a4d5c5eee87a578de9c8318cd294b3a22}{queue\+\_\+tx\+\_\+data}} -\begin{DoxyCompactList}\small\item\em Packet queue used to send data to be sent over SPI from sending functions to spi\+\_\+task. \end{DoxyCompactList}\item -Queue\+Handle\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a9a1c851e8fa5633e11f6abee293d7e9b}{queue\+\_\+frs\+\_\+read\+\_\+data}} -\begin{DoxyCompactList}\small\item\em Queue used to send packet body from data\+\_\+proc\+\_\+task to frs read functions. \end{DoxyCompactList}\item -Queue\+Handle\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a84b3639cc159262e0137adb0db5cf9aa}{queue\+\_\+reset\+\_\+reason}} -\begin{DoxyCompactList}\small\item\em Queue used to send reset reason from product id report to reset\+\_\+reason() function. \end{DoxyCompactList}\item -std\+::vector$<$ std\+::function$<$ void()$>$ $>$ \mbox{\hyperlink{class_b_n_o08x_a6a15e3a64dd71ea61f0448afcce96409}{cb\+\_\+list}} -\item -uint32\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a7bd032712a975e73e66bd72a3502baba}{meta\+\_\+data}} \mbox{[}9\mbox{]} -\begin{DoxyCompactList}\small\item\em First 9 bytes of meta data returned from FRS read operation (we don\textquotesingle{}t really need the rest) (See Ref. Manual 5.\+1) \end{DoxyCompactList}\item -\mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}} \mbox{\hyperlink{class_b_n_o08x_aeda443e9f608fccfec0e6770edc90c82}{imu\+\_\+config}} \{\} -\begin{DoxyCompactList}\small\item\em IMU configuration settings. \end{DoxyCompactList}\item -spi\+\_\+bus\+\_\+config\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a982f065df42f00e53fd87c840efdb0f1}{bus\+\_\+config}} \{\} -\begin{DoxyCompactList}\small\item\em SPI bus GPIO configuration settings. \end{DoxyCompactList}\item -spi\+\_\+device\+\_\+interface\+\_\+config\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a425a1f5a9f3232aadc685caaf4c2f82e}{imu\+\_\+spi\+\_\+config}} \{\} -\begin{DoxyCompactList}\small\item\em SPI slave device settings. \end{DoxyCompactList}\item -spi\+\_\+device\+\_\+handle\+\_\+t \mbox{\hyperlink{class_b_n_o08x_acc0ea091465fc9a5736f5e0c6a0ce8ef}{spi\+\_\+hdl}} \{\} -\begin{DoxyCompactList}\small\item\em SPI device handle. \end{DoxyCompactList}\item -spi\+\_\+transaction\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ac16adc5f00b0039c98a4921f13895026}{spi\+\_\+transaction}} \{\} -\begin{DoxyCompactList}\small\item\em SPI transaction handle. \end{DoxyCompactList}\item -\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t}{bno08x\+\_\+init\+\_\+status\+\_\+t}} \mbox{\hyperlink{class_b_n_o08x_a4520fc3e1dec6389d470945786680013}{init\+\_\+status}} -\begin{DoxyCompactList}\small\item\em Initialization status of various functionality, used by deconstructor during cleanup, set during initialization. \end{DoxyCompactList}\item -uint32\+\_\+t \mbox{\hyperlink{class_b_n_o08x_abc972db20affbd0040b4e6c4892dd57b}{time\+\_\+stamp}} -\begin{DoxyCompactList}\small\item\em Report timestamp (see datasheet 1.\+3.\+5.\+3) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a75fb2f06c5bbe26e3f3c794934ef954c}{raw\+\_\+accel\+\_\+X}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ab56e2ba505fa293d03e955137625c562}{raw\+\_\+accel\+\_\+Y}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_af254d245b368027df6952b7d7522bd35}{raw\+\_\+accel\+\_\+Z}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a3365b7ebde01e284274e655c60343df9}{accel\+\_\+accuracy}} -\begin{DoxyCompactList}\small\item\em Raw acceleration readings (See SH-\/2 Ref. Manual 6.\+5.\+8) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ae1f71a432cb15e75f522fa18f29f4d50}{raw\+\_\+lin\+\_\+accel\+\_\+X}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aff3a5590471d1c9fc485a5610433915f}{raw\+\_\+lin\+\_\+accel\+\_\+Y}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_abc8add47f1babc66c812a015614143d3}{raw\+\_\+lin\+\_\+accel\+\_\+Z}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a35e1635ef5edde8fc8640f978c6f2e3c}{accel\+\_\+lin\+\_\+accuracy}} -\begin{DoxyCompactList}\small\item\em Raw linear acceleration (See SH-\/2 Ref. Manual 6.\+5.\+10) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a87faca2c8c71ff46bf2e6ad4ba271b3a}{raw\+\_\+calib\+\_\+gyro\+\_\+X}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a66c48af1d4162a9ec25c3a1c95660fe4}{raw\+\_\+calib\+\_\+gyro\+\_\+Y}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_af5450d1a9c20c2a5c62c960e3df11c0e}{raw\+\_\+calib\+\_\+gyro\+\_\+Z}} -\begin{DoxyCompactList}\small\item\em Raw gyro reading (See SH-\/2 Ref. Manual 6.\+5.\+13) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a69dc7e97875060213085ba964b3bd987}{raw\+\_\+quat\+\_\+I}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a61ae05dc5572b326541bf8099f0c2a54}{raw\+\_\+quat\+\_\+J}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a7720c44ed1c0f1a0663d2adc5e1a1ea1}{raw\+\_\+quat\+\_\+K}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a867354267253ae828be4fae15c062db3}{raw\+\_\+quat\+\_\+real}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a033d6cb1aa137743b69cc3e401df67b7}{raw\+\_\+quat\+\_\+radian\+\_\+accuracy}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a36223f7124751fa71e860b2ef55dd2ac}{quat\+\_\+accuracy}} -\begin{DoxyCompactList}\small\item\em Raw quaternion reading (See SH-\/2 Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a6537ed69245cf71cad6a6a44480dddaa}{integrated\+\_\+gyro\+\_\+velocity\+\_\+X}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a00b39e22ea9fe306e88aaed490ee0a51}{integrated\+\_\+gyro\+\_\+velocity\+\_\+Y}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ad112beb64badd22a2e1d717e1ee921c8}{integrated\+\_\+gyro\+\_\+velocity\+\_\+Z}} -\begin{DoxyCompactList}\small\item\em Raw gyro angular velocity reading from integrated gyro rotation vector (See SH-\/2 Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_af45016be9ea523d80be8467b2907b499}{gravity\+\_\+X}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_af20dcd487a9fe8fa6243817d51e37be5}{gravity\+\_\+Y}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_afa1cf5c3afbb258d97c55c5fb187f2d6}{gravity\+\_\+Z}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ae01698d287ea999179a11e2244902022}{gravity\+\_\+accuracy}} -\begin{DoxyCompactList}\small\item\em Gravity reading in m/s\texorpdfstring{$^\wedge$}{\string^}2 (See SH-\/2 Ref. Manual 6.\+5.\+11) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_afdc5cdb65bd0b36528b5b671b9d27053}{raw\+\_\+uncalib\+\_\+gyro\+\_\+X}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_acc2c66e2985975266a286385ea855117}{raw\+\_\+uncalib\+\_\+gyro\+\_\+Y}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_afac9dd4161f4c0051255293680c9082b}{raw\+\_\+uncalib\+\_\+gyro\+\_\+Z}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a8a2667f668317cee0a9fc4ef0accc3f5}{raw\+\_\+bias\+\_\+X}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ac38ff5eb93d3c3db0af2504ba02fd93c}{raw\+\_\+bias\+\_\+Y}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a0968eaed9b3d979a2caa1aba6e6b417a}{raw\+\_\+bias\+\_\+Z}} -\begin{DoxyCompactList}\small\item\em Uncalibrated gyro reading (See SH-\/2 Ref. Manual 6.\+5.\+14) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aa5bdf740161b7c37adcac0154a410118}{raw\+\_\+magf\+\_\+X}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_acd365418f24a6da61122c66d82086639}{raw\+\_\+magf\+\_\+Y}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ab4862de31d0874b44b6745678e1c905e}{raw\+\_\+magf\+\_\+Z}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ac5d4e151690774687efa951ca41c16ae}{magf\+\_\+accuracy}} -\begin{DoxyCompactList}\small\item\em Calibrated magnetic field reading in u\+Tesla (See SH-\/2 Ref. Manual 6.\+5.\+16) \end{DoxyCompactList}\item -uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a1171a5738a4e6831ec7fa32a29f15554}{tap\+\_\+detector}} -\begin{DoxyCompactList}\small\item\em Tap detector reading (See SH-\/2 Ref. Manual 6.\+5.\+27) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ad80a77973371b12d722ea39063c648be}{step\+\_\+count}} -\begin{DoxyCompactList}\small\item\em Step counter reading (See SH-\/2 Ref. Manual 6.\+5.\+29) \end{DoxyCompactList}\item -uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a1b12471e92536a79d0c425d77676f2e1}{stability\+\_\+classifier}} -\begin{DoxyCompactList}\small\item\em BNO08x\+Stability status reading (See SH-\/2 Ref. Manual 6.\+5.\+31) \end{DoxyCompactList}\item -uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a75cea49c1c08ca28d9fa7e5ed61c6e7b}{activity\+\_\+classifier}} -\begin{DoxyCompactList}\small\item\em BNO08x\+Activity status reading (See SH-\/2 Ref. Manual 6.\+5.\+36) \end{DoxyCompactList}\item -uint8\+\_\+t \texorpdfstring{$\ast$}{*} \mbox{\hyperlink{class_b_n_o08x_af96e8cd070459f945ffbf01b98106e13}{activity\+\_\+confidences}} = nullptr -\begin{DoxyCompactList}\small\item\em Confidence of read activities (See SH-\/2 Ref. Manual 6.\+5.\+36) \end{DoxyCompactList}\item -uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ad212b5028a31e857e76d251ced2724e1}{calibration\+\_\+status}} -\begin{DoxyCompactList}\small\item\em Calibration status of device (See SH-\/2 Ref. Manual 6.\+4.\+7.\+1 \& 6.\+4.\+7.\+2) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a937cbdc4edaac72c8cad041d79de5701}{mems\+\_\+raw\+\_\+accel\+\_\+X}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ad83cecb8a5d2be01db6792755b6057e9}{mems\+\_\+raw\+\_\+accel\+\_\+Y}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a59a4d75f1302ab693b1b26e9ccaa5341}{mems\+\_\+raw\+\_\+accel\+\_\+Z}} -\begin{DoxyCompactList}\small\item\em Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.\+5.\+8) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a3d6b6257462951ea023af7076c80f6dd}{mems\+\_\+raw\+\_\+gyro\+\_\+X}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ab6b142416912a096886dd63ad0beb865}{mems\+\_\+raw\+\_\+gyro\+\_\+Y}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ac35d5b12721ab876eaeb1f714a9b3b1d}{mems\+\_\+raw\+\_\+gyro\+\_\+Z}} -\begin{DoxyCompactList}\small\item\em Raw gyro readings from MEMS sensor (See SH-\/2 Ref. Manual 6.\+5.\+12) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ab587cdf991342b69b7fff3b33f537eb5}{mems\+\_\+raw\+\_\+magf\+\_\+X}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aad926054c81818fff611e10ed913706a}{mems\+\_\+raw\+\_\+magf\+\_\+Y}} -\item -uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a90f0cdf11decc276006f76a494d42ce3}{mems\+\_\+raw\+\_\+magf\+\_\+Z}} -\begin{DoxyCompactList}\small\item\em Raw magnetometer (compass) readings from MEMS sensor (See SH-\/2 Ref. Manual 6.\+5.\+15) \end{DoxyCompactList}\item -\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__report__period__tracker__t}{bno08x\+\_\+report\+\_\+period\+\_\+tracker\+\_\+t}} \mbox{\hyperlink{class_b_n_o08x_ae3750acb4578ccdd7fcf20abcd8e0904}{report\+\_\+period\+\_\+trackers}} \mbox{[}\mbox{\hyperlink{class_b_n_o08x_a9658c821658ab51fe6831a83d8903a53}{REPORT\+\_\+\+CNT}}\mbox{]} -\begin{DoxyCompactList}\small\item\em Current sample period of each report in microseconds linked to report ID (0 if not enabled). \end{DoxyCompactList}\item -uint32\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a7ffc2875b3dff21a827052e4faf273b7}{largest\+\_\+sample\+\_\+period\+\_\+us}} -\begin{DoxyCompactList}\small\item\em Current largest sample period of any enabled report in microseconds (used to determine timeout for hint ISR). \end{DoxyCompactList}\item -uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ae2e8382b5ff8d0ca3375a10b6e273f0c}{current\+\_\+slowest\+\_\+report\+\_\+\+ID}} -\begin{DoxyCompactList}\small\item\em ID of the currently enabled report with the largest sample period. \end{DoxyCompactList}\item -Tick\+Type\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ab0c1b4ef4dbcc05a2a6cf37ee039ba0e}{host\+\_\+int\+\_\+timeout\+\_\+ms}} -\begin{DoxyCompactList}\small\item\em Max wait between HINT being asserted by \doxylink{class_b_n_o08x}{BNO08x} before transaction is considered failed (in miliseconds), determined by enabled report with longest period. \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Static Private Attributes} -\begin{DoxyCompactItemize} -\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a5448bffec9a90f5c388b3c22928463ae}{TASK\+\_\+\+CNT}} = 2U -\begin{DoxyCompactList}\small\item\em Total amount of tasks utilized by \doxylink{class_b_n_o08x}{BNO08x} driver library. \end{DoxyCompactList}\item -static const constexpr uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a1a037bda37493cde56732cc6fdc7884b}{RX\+\_\+\+DATA\+\_\+\+LENGTH}} = 300U -\begin{DoxyCompactList}\small\item\em length buffer containing data received over spi \end{DoxyCompactList}\item -static const constexpr uint16\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a2a5b978233eab4c103ab01cfc33a1750}{MAX\+\_\+\+METADATA\+\_\+\+LENGTH}} = 9U -\begin{DoxyCompactList}\small\item\em max length of metadata used in frs read operations \end{DoxyCompactList}\item -static const constexpr Tick\+Type\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ae51d4e3228a91ee407d5866e604804c4}{HOST\+\_\+\+INT\+\_\+\+TIMEOUT\+\_\+\+DEFAULT\+\_\+\+MS}} -\begin{DoxyCompactList}\small\item\em Max wait between HINT being asserted by \doxylink{class_b_n_o08x}{BNO08x} before transaction is considered failed (in miliseconds), when no reports are enabled (ie during reset) \end{DoxyCompactList}\item -static const constexpr Tick\+Type\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aa07e329d693eb8d9270a7f9ad6f1d94b}{HARD\+\_\+\+RESET\+\_\+\+DELAY\+\_\+\+MS}} -\begin{DoxyCompactList}\small\item\em How long RST pin is held low during hard reset (min 10ns according to datasheet, but should be longer for stable operation) \end{DoxyCompactList}\item -static const constexpr Tick\+Type\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a38e31bdb22afdfe05372ffcd5eabfdd2}{CMD\+\_\+\+EXECUTION\+\_\+\+DELAY\+\_\+\+MS}} -\begin{DoxyCompactList}\small\item\em How long to delay after queueing command to allow it to execute (for ex. after sending command to enable report). \end{DoxyCompactList}\item -static const constexpr uint32\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a031976dacd97917d9d72edccb607160c}{SCLK\+\_\+\+MAX\+\_\+\+SPEED}} = 3000000\+UL -\begin{DoxyCompactList}\small\item\em Max SPI SCLK speed \doxylink{class_b_n_o08x}{BNO08x} is capable of. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a32cffd8f78881925d22d5a7cb55f2bbc}{EVT\+\_\+\+GRP\+\_\+\+SPI\+\_\+\+RX\+\_\+\+DONE\+\_\+\+BIT}} -\begin{DoxyCompactList}\small\item\em When this bit is set it indicates a receive procedure has completed. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a96342b0182f339d5a8d6cac1214ce174}{EVT\+\_\+\+GRP\+\_\+\+SPI\+\_\+\+RX\+\_\+\+VALID\+\_\+\+PACKET\+\_\+\+BIT}} -\begin{DoxyCompactList}\small\item\em When this bit is set, it indicates a valid packet has been received and processed. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a15e3f92812f8fe70b30966b73a7cb5b2}{EVT\+\_\+\+GRP\+\_\+\+SPI\+\_\+\+RX\+\_\+\+INVALID\+\_\+\+PACKET\+\_\+\+BIT}} -\begin{DoxyCompactList}\small\item\em When this bit is set, it indicates an invalid packet has been received. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_adf2c292674e428c3b65c846cfab4deb7}{EVT\+\_\+\+GRP\+\_\+\+SPI\+\_\+\+TX\+\_\+\+DONE\+\_\+\+BIT}} = (1 $<$$<$ 3) -\begin{DoxyCompactList}\small\item\em When this bit is set, it indicates a queued packet has been sent. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a198da2ee3cd9cfa459c3c41c4f8c44b7}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+ROTATION\+\_\+\+VECTOR\+\_\+\+BIT}} = (1 $<$$<$ 0) -\begin{DoxyCompactList}\small\item\em When set, rotation vector reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a0f3f33d93b72ba6564f9d5fa93c24f98}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR\+\_\+\+BIT}} = (1 $<$$<$ 1) -\begin{DoxyCompactList}\small\item\em When set, game rotation vector reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aa9703cee46912a545b5e85e671f08e4b}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+ARVR\+\_\+\+S\+\_\+\+ROTATION\+\_\+\+VECTOR\+\_\+\+BIT}} -\begin{DoxyCompactList}\small\item\em When set, ARVR stabilized rotation vector reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a79d3fff1e0f19467cad231b22edafa0f}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+ARVR\+\_\+\+S\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR\+\_\+\+BIT}} -\begin{DoxyCompactList}\small\item\em When set, ARVR stabilized game rotation vector reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a541155dc4544193451cf102e2a992da9}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+GYRO\+\_\+\+ROTATION\+\_\+\+VECTOR\+\_\+\+BIT}} -\begin{DoxyCompactList}\small\item\em When set, gyro integrator rotation vector reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a17b19c32d4dfbc9ae2761a0cdd873314}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+ACCELEROMETER\+\_\+\+BIT}} = (1U $<$$<$ 5U) -\begin{DoxyCompactList}\small\item\em When set, accelerometer reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ad93161968a53ff53a6bb74ab7c34fbff}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+LINEAR\+\_\+\+ACCELEROMETER\+\_\+\+BIT}} = (1U $<$$<$ 6U) -\begin{DoxyCompactList}\small\item\em When set, linear accelerometer reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ab94a8f69673a3db7556ba67775c5ea93}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+GRAVITY\+\_\+\+BIT}} = (1U $<$$<$ 7U) -\begin{DoxyCompactList}\small\item\em When set, gravity reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a3a8b12ea9b75f97191785a60d1aa962a}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+GYRO\+\_\+\+BIT}} = (1U $<$$<$ 8U) -\begin{DoxyCompactList}\small\item\em When set, gyro reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_af86821bc0f1e7f5897de20b5e47a85bd}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+GYRO\+\_\+\+UNCALIBRATED\+\_\+\+BIT}} = (1U $<$$<$ 9U) -\begin{DoxyCompactList}\small\item\em When set, uncalibrated gyro reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a901af6f2d552f197ee830d0a1c06679c}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+MAGNETOMETER\+\_\+\+BIT}} = (1U $<$$<$ 10U) -\begin{DoxyCompactList}\small\item\em When set, magnetometer reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a665464f781fe891b9179478d0174af47}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+TAP\+\_\+\+DETECTOR\+\_\+\+BIT}} = (1U $<$$<$ 11U) -\begin{DoxyCompactList}\small\item\em When set, tap detector reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ab264b65a3aa5a9a74ed11b8977164a73}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+STEP\+\_\+\+COUNTER\+\_\+\+BIT}} = (1U $<$$<$ 12U) -\begin{DoxyCompactList}\small\item\em When set, step counter reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a7d6ee23222f55dbe9f70e04b36d9add2}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+STABILITY\+\_\+\+CLASSIFIER\+\_\+\+BIT}} = (1U $<$$<$ 13U) -\begin{DoxyCompactList}\small\item\em When set, stability classifier reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a96eb1b1bfe1266791fd424b3ce402c56}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+ACTIVITY\+\_\+\+CLASSIFIER\+\_\+\+BIT}} = (1U $<$$<$ 14U) -\begin{DoxyCompactList}\small\item\em When set, activity classifier reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a3e56d12435f7be81956d68196f1a46b4}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+RAW\+\_\+\+ACCELEROMETER\+\_\+\+BIT}} = (1U $<$$<$ 15U) -\begin{DoxyCompactList}\small\item\em When set, raw accelerometer reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a6be7b240e4447c2c643e706954093aa0}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+RAW\+\_\+\+GYRO\+\_\+\+BIT}} = (1U $<$$<$ 16U) -\begin{DoxyCompactList}\small\item\em When set, raw gyro reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ac28553b40b82c7cb409938681afe6cec}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+RAW\+\_\+\+MAGNETOMETER\+\_\+\+BIT}} = (1U $<$$<$ 17U) -\begin{DoxyCompactList}\small\item\em When set, raw magnetometer reports are active. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a5fc8c8969043c5d08fce80eb1d74a761}{EVT\+\_\+\+GRP\+\_\+\+TSK\+\_\+\+FLW\+\_\+\+RUNNING\+\_\+\+BIT}} -\begin{DoxyCompactList}\small\item\em When set, data\+\_\+proc\+\_\+task and spi\+\_\+task are active, when 0 they are pending deletion or deleted. \end{DoxyCompactList}\item -static const constexpr Event\+Bits\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a89399e8a68a53bc2a269ab73625a2da2}{EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+ALL\+\_\+\+BITS}} -\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_acd5b44d705af1f9aaa271a59a9d2d595}{CALIBRATE\+\_\+\+ACCEL}} = 0U -\begin{DoxyCompactList}\small\item\em Calibrate accelerometer command used by queue\+\_\+calibrate\+\_\+command. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aeac84719a1cc0f9c8d5a9a749391d4db}{CALIBRATE\+\_\+\+GYRO}} = 1U -\begin{DoxyCompactList}\small\item\em Calibrate gyro command used by queue\+\_\+calibrate\+\_\+command. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ac00e8b59ae8d710cf79956eaafa97ddb}{CALIBRATE\+\_\+\+MAG}} = 2U -\begin{DoxyCompactList}\small\item\em Calibrate magnetometer command used by queue\+\_\+calibrate\+\_\+command. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a955dcb60da150490e17367a871b3a3d2}{CALIBRATE\+\_\+\+PLANAR\+\_\+\+ACCEL}} = 3U -\begin{DoxyCompactList}\small\item\em Calibrate planar acceleration command used by queue\+\_\+calibrate\+\_\+command. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_af53d9e99f163d97ef92fe989b1dd25cc}{CALIBRATE\+\_\+\+ACCEL\+\_\+\+GYRO\+\_\+\+MAG}} -\begin{DoxyCompactList}\small\item\em Calibrate accelerometer, gyro, \& magnetometer command used by queue\+\_\+calibrate\+\_\+command. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a584bfa04a39feb93279ee673c340db54}{CALIBRATE\+\_\+\+STOP}} = 5U -\begin{DoxyCompactList}\small\item\em Stop calibration command used by queue\+\_\+calibrate\+\_\+command. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a384a1efc9857ad938be3bb44f871539b}{COMMAND\+\_\+\+ERRORS}} = 1U -\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a93dd073c0cc1f3ccfde552649f6ebccc}{COMMAND\+\_\+\+COUNTER}} = 2U -\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a0a1756bc16ba3eac45f4229b1e350107}{COMMAND\+\_\+\+TARE}} = 3U -\begin{DoxyCompactList}\small\item\em Command and response to tare command (See Sh2 Ref. Manual 6.\+4.\+4) \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a30eb6d305a187d4d36546841e12176b9}{COMMAND\+\_\+\+INITIALIZE}} = 4U -\begin{DoxyCompactList}\small\item\em Reinitialize sensor hub components See (SH2 Ref. Manual 6.\+4.\+5) \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_af124a6c1d8b871f3181b6c85f1099cb2}{COMMAND\+\_\+\+DCD}} = 6U -\begin{DoxyCompactList}\small\item\em Save DCD command (See SH2 Ref. Manual 6.\+4.\+7) \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a8381dfe403ddff522f172cb16780731a}{COMMAND\+\_\+\+ME\+\_\+\+CALIBRATE}} = 7U -\begin{DoxyCompactList}\small\item\em Command and response to configure ME calibration (See SH2 Ref. Manual 6.\+4.\+7) \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a7a246989c94cd87f68166b20b7ad4c8b}{COMMAND\+\_\+\+DCD\+\_\+\+PERIOD\+\_\+\+SAVE}} = 9U -\begin{DoxyCompactList}\small\item\em Configure DCD periodic saving (See SH2 Ref. Manual 6.\+4) \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a308c8b5307d93a67b5b9066d44494aa5}{COMMAND\+\_\+\+OSCILLATOR}} = 10U -\begin{DoxyCompactList}\small\item\em Retrieve oscillator type command (See SH2 Ref. Manual 6.\+4) \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a4f580b3cb232a762ea7019ee7b04d419}{COMMAND\+\_\+\+CLEAR\+\_\+\+DCD}} = 11U -\begin{DoxyCompactList}\small\item\em Clear DCD \& Reset command (See SH2 Ref. Manual 6.\+4) \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a1e5b64caa514b7e4fe64ab214758b875}{SHTP\+\_\+\+REPORT\+\_\+\+COMMAND\+\_\+\+RESPONSE}} = 0x\+F1U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+3.\+9. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ab04695dd189412092254e52bd6e5a75a}{SHTP\+\_\+\+REPORT\+\_\+\+COMMAND\+\_\+\+REQUEST}} = 0x\+F2U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+3.\+8. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aeb760b095dcf808a413ef696f2608e43}{SHTP\+\_\+\+REPORT\+\_\+\+FRS\+\_\+\+READ\+\_\+\+RESPONSE}} = 0x\+F3U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+3.\+7. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a74af7eacc35cc825940b647c2de0d368}{SHTP\+\_\+\+REPORT\+\_\+\+FRS\+\_\+\+READ\+\_\+\+REQUEST}} = 0x\+F4U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+3.\+6. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a0177134162e116501bc9483c6e4b76c3}{SHTP\+\_\+\+REPORT\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+RESPONSE}} = 0x\+F8U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+3.\+2. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a542405639c28bd56bc4361b922763c95}{SHTP\+\_\+\+REPORT\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REQUEST}} = 0x\+F9U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+3.\+1. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ae37d6f8431c8c465bfb0c662772b5cb9}{SHTP\+\_\+\+REPORT\+\_\+\+BASE\+\_\+\+TIMESTAMP}} = 0x\+FBU -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 7.\+2.\+1. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a1d3bff4e20c2c3d47db322c9e34ef338}{SHTP\+\_\+\+REPORT\+\_\+\+SET\+\_\+\+FEATURE\+\_\+\+COMMAND}} = 0x\+FDU -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+4. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ad09312802cf5b8b5115362c86b53858b}{SHTP\+\_\+\+REPORT\+\_\+\+GET\+\_\+\+FEATURE\+\_\+\+RESPONSE}} = 0x\+FCU -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+5. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a354eaff2218eb382a1851537a75badcc}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+ACCELEROMETER}} = 0x01U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+9. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a224fb8f833806dd530c5f16e7ab5bc7a}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+GYROSCOPE}} = 0x02U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+13. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a06058a84d6604054aa66ee008ac64aa9}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+MAGNETIC\+\_\+\+FIELD}} = 0x03U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+16. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ace7720a02c9f4ef38e319849f6c36a0b}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+LINEAR\+\_\+\+ACCELERATION}} = 0x04U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+10. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a37c91f995c385556486df5fbbce8a3d5}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+ROTATION\+\_\+\+VECTOR}} = 0x05U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+18. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a6730acb92053d44decb690a7b7234032}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+GRAVITY}} = 0x06U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+11. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_acb8e83fbb0645d4e98a96120ce9f431c}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+UNCALIBRATED\+\_\+\+GYRO}} = 0x07U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+14. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ada7dbda9f7a0bfb0894a787ce0ff9cef}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR}} = 0x08U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+19. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_abb6d0586a5a87b7b34f4c65ae52965a4}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+GEOMAGNETIC\+\_\+\+ROTATION\+\_\+\+VECTOR}} = 0x09U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+20. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_acd0fc6ffa70dd2761cba0ac0b88c234f}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+GYRO\+\_\+\+INTEGRATED\+\_\+\+ROTATION\+\_\+\+VECTOR}} = 0x2\+AU -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+44. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a8114460c50e84b0ac750293ab72868c8}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+TAP\+\_\+\+DETECTOR}} = 0x10U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+27. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a2a10161bb564067a07f3fcf4021e00bb}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+STEP\+\_\+\+COUNTER}} = 0x11U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+29. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_ab5c29f31714b4755c0edbce7156652f7}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+STABILITY\+\_\+\+CLASSIFIER}} = 0x13U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+31. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a80ea70c4787dea6c3eabb48f583f1916}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+RAW\+\_\+\+ACCELEROMETER}} = 0x14U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+8. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a03b3000424e6d966b80655443ec546bc}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+RAW\+\_\+\+GYROSCOPE}} = 0x15U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+12. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a9e9a7578b7584e7eb2ad562b29565fa7}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+RAW\+\_\+\+MAGNETOMETER}} = 0x16U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+15. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a7274f6d3bda04da0bb304386b4e8d603}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+PERSONAL\+\_\+\+ACTIVITY\+\_\+\+CLASSIFIER}} = 0x1\+EU -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+36. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a8d4b91149cfc1a3cd615f60a4ad2275e}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+ARVR\+\_\+\+STABILIZED\+\_\+\+ROTATION\+\_\+\+VECTOR}} = 0x28U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+42. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_aeb51ebb6c82158cd7e23bd682c08c4e0}{SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+ARVR\+\_\+\+STABILIZED\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR}} = 0x29U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+43. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a27df630f3e52b35552d2c1f2cf3496b0}{TARE\+\_\+\+NOW}} = 0U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+4.\+4.\+1. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a115aef7b38ec0dec2085f6917d832912}{TARE\+\_\+\+PERSIST}} = 1U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+4.\+4.\+2. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a59cde7dd301c94a20b84735c5d49008e}{TARE\+\_\+\+SET\+\_\+\+REORIENTATION}} = 2U -\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+4.\+4.\+3. \end{DoxyCompactList}\item -static const constexpr uint8\+\_\+t \mbox{\hyperlink{class_b_n_o08x_a9658c821658ab51fe6831a83d8903a53}{REPORT\+\_\+\+CNT}} = 19 -\begin{DoxyCompactList}\small\item\em Total unique reports that can be returned by \doxylink{class_b_n_o08x}{BNO08x}. \end{DoxyCompactList}\item -static const constexpr char \texorpdfstring{$\ast$}{*} \mbox{\hyperlink{class_b_n_o08x_a2c98d5f2c406a3efd0b48c5666fa8c46}{TAG}} = "{}BNO08x"{} -\begin{DoxyCompactList}\small\item\em Class tag used for serial print statements. \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Friends} -\begin{DoxyCompactItemize} -\item -class \mbox{\hyperlink{class_b_n_o08x_a190775b71c35d8007faae7dd6a9f1030}{BNO08x\+Test\+Helper}} -\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -\doxylink{class_b_n_o08x}{BNO08x} IMU driver class. - -\doxysubsection{Member Typedef Documentation} -\Hypertarget{class_b_n_o08x_a200dfd32391bcaff73e8498674c7ec87}\label{class_b_n_o08x_a200dfd32391bcaff73e8498674c7ec87} -\index{BNO08x@{BNO08x}!bno08x\_init\_status\_t@{bno08x\_init\_status\_t}} -\index{bno08x\_init\_status\_t@{bno08x\_init\_status\_t}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{bno08x\_init\_status\_t}{bno08x\_init\_status\_t}} -{\footnotesize\ttfamily typedef struct BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t\hspace{0.3cm}{\ttfamily [private]}} - - - -Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup). - -\Hypertarget{class_b_n_o08x_ae87c0e3c6eb34e209855d8e5d48c624b}\label{class_b_n_o08x_ae87c0e3c6eb34e209855d8e5d48c624b} -\index{BNO08x@{BNO08x}!bno08x\_report\_period\_tracker\_t@{bno08x\_report\_period\_tracker\_t}} -\index{bno08x\_report\_period\_tracker\_t@{bno08x\_report\_period\_tracker\_t}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{bno08x\_report\_period\_tracker\_t}{bno08x\_report\_period\_tracker\_t}} -{\footnotesize\ttfamily typedef struct BNO08x\+::bno08x\+\_\+report\+\_\+period\+\_\+tracker\+\_\+t BNO08x\+::bno08x\+\_\+report\+\_\+period\+\_\+tracker\+\_\+t\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba}\label{class_b_n_o08x_a407711b4a84223a52cc043a152aea8ba} -\index{BNO08x@{BNO08x}!bno08x\_rx\_packet\_t@{bno08x\_rx\_packet\_t}} -\index{bno08x\_rx\_packet\_t@{bno08x\_rx\_packet\_t}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{bno08x\_rx\_packet\_t}{bno08x\_rx\_packet\_t}} -{\footnotesize\ttfamily typedef struct BNO08x\+::bno08x\+\_\+rx\+\_\+packet\+\_\+t BNO08x\+::bno08x\+\_\+rx\+\_\+packet\+\_\+t\hspace{0.3cm}{\ttfamily [private]}} - - - -Holds data that is received over spi. - -\Hypertarget{class_b_n_o08x_a3a1a869ac69e6ee850bd2a7f90dd8945}\label{class_b_n_o08x_a3a1a869ac69e6ee850bd2a7f90dd8945} -\index{BNO08x@{BNO08x}!bno08x\_tx\_packet\_t@{bno08x\_tx\_packet\_t}} -\index{bno08x\_tx\_packet\_t@{bno08x\_tx\_packet\_t}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{bno08x\_tx\_packet\_t}{bno08x\_tx\_packet\_t}} -{\footnotesize\ttfamily typedef struct BNO08x\+::bno08x\+\_\+tx\+\_\+packet\+\_\+t BNO08x\+::bno08x\+\_\+tx\+\_\+packet\+\_\+t\hspace{0.3cm}{\ttfamily [private]}} - - - -Holds data that is sent over spi. - - - -\doxysubsection{Member Enumeration Documentation} -\Hypertarget{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638f}\label{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638f} -\index{BNO08x@{BNO08x}!channels\_t@{channels\_t}} -\index{channels\_t@{channels\_t}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{channels\_t}{channels\_t}} -{\footnotesize\ttfamily enum \mbox{\hyperlink{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638f}{BNO08x\+::channels\+\_\+t}}\hspace{0.3cm}{\ttfamily [private]}} - - - -SHTP protocol channels. - -\begin{DoxyEnumFields}{Enumerator} -\raisebox{\heightof{T}}[0pt][0pt]{\index{CHANNEL\_COMMAND@{CHANNEL\_COMMAND}!BNO08x@{BNO08x}}\index{BNO08x@{BNO08x}!CHANNEL\_COMMAND@{CHANNEL\_COMMAND}}}\Hypertarget{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fad116268ebf7fb5e5cb4795ccc27867ed}\label{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fad116268ebf7fb5e5cb4795ccc27867ed} -CHANNEL\+\_\+\+COMMAND&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{CHANNEL\_EXECUTABLE@{CHANNEL\_EXECUTABLE}!BNO08x@{BNO08x}}\index{BNO08x@{BNO08x}!CHANNEL\_EXECUTABLE@{CHANNEL\_EXECUTABLE}}}\Hypertarget{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fab1f28434b161c7ffa7b1a5c5f1a8a95b}\label{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fab1f28434b161c7ffa7b1a5c5f1a8a95b} -CHANNEL\+\_\+\+EXECUTABLE&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{CHANNEL\_CONTROL@{CHANNEL\_CONTROL}!BNO08x@{BNO08x}}\index{BNO08x@{BNO08x}!CHANNEL\_CONTROL@{CHANNEL\_CONTROL}}}\Hypertarget{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fa5b5d133bf4a91e14741fdd8e635e897e}\label{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fa5b5d133bf4a91e14741fdd8e635e897e} -CHANNEL\+\_\+\+CONTROL&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{CHANNEL\_REPORTS@{CHANNEL\_REPORTS}!BNO08x@{BNO08x}}\index{BNO08x@{BNO08x}!CHANNEL\_REPORTS@{CHANNEL\_REPORTS}}}\Hypertarget{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fabeb0a4983bc57ad2ce9f98360742e03e}\label{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fabeb0a4983bc57ad2ce9f98360742e03e} -CHANNEL\+\_\+\+REPORTS&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{CHANNEL\_WAKE\_REPORTS@{CHANNEL\_WAKE\_REPORTS}!BNO08x@{BNO08x}}\index{BNO08x@{BNO08x}!CHANNEL\_WAKE\_REPORTS@{CHANNEL\_WAKE\_REPORTS}}}\Hypertarget{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638faefb874de7f2f90fb99b42bedf9623d21}\label{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638faefb874de7f2f90fb99b42bedf9623d21} -CHANNEL\+\_\+\+WAKE\+\_\+\+REPORTS&\\ -\hline - -\raisebox{\heightof{T}}[0pt][0pt]{\index{CHANNEL\_GYRO@{CHANNEL\_GYRO}!BNO08x@{BNO08x}}\index{BNO08x@{BNO08x}!CHANNEL\_GYRO@{CHANNEL\_GYRO}}}\Hypertarget{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fadd3caa696e525dd901de7a8e3dbf0731}\label{class_b_n_o08x_ac14e319f54399031ed30cd24ad1c638fadd3caa696e525dd901de7a8e3dbf0731} -CHANNEL\+\_\+\+GYRO&\\ -\hline - -\end{DoxyEnumFields} - - -\doxysubsection{Constructor \& Destructor Documentation} -\Hypertarget{class_b_n_o08x_ad12fb6cf310ad7a04a4e53809833bd61}\label{class_b_n_o08x_ad12fb6cf310ad7a04a4e53809833bd61} -\index{BNO08x@{BNO08x}!BNO08x@{BNO08x}} -\index{BNO08x@{BNO08x}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{BNO08x()}{BNO08x()}} -{\footnotesize\ttfamily BNO08x\+::\+BNO08x (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}}}]{imu\+\_\+config = {\ttfamily \mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}}()} }\end{DoxyParamCaption})} - - - -\doxylink{class_b_n_o08x}{BNO08x} imu constructor. - -Construct a \doxylink{class_b_n_o08x}{BNO08x} object for managing a \doxylink{class_b_n_o08x}{BNO08x} sensor. - - -\begin{DoxyParams}{Parameters} -{\em imu\+\_\+config} & Configuration settings (optional), default settings can be seen in \doxylink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t} \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9}\label{class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9} -\index{BNO08x@{BNO08x}!````~BNO08x@{\texorpdfstring{$\sim$}{\string~}BNO08x}} -\index{````~BNO08x@{\texorpdfstring{$\sim$}{\string~}BNO08x}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{\texorpdfstring{$\sim$}{\string~}BNO08x()}{\string~BNO08x()}} -{\footnotesize\ttfamily BNO08x\+::\texorpdfstring{$\sim$}{\string~}\+BNO08x (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -\doxylink{class_b_n_o08x}{BNO08x} imu deconstructor. - -Deconstructs a \doxylink{class_b_n_o08x}{BNO08x} object and releases any utilized resources. - -\begin{DoxyReturn}{Returns} -void, nothing to return. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph} -\end{center} -\end{figure} - - -\doxysubsection{Member Function Documentation} -\Hypertarget{class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc}\label{class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc} -\index{BNO08x@{BNO08x}!calibrate\_accelerometer@{calibrate\_accelerometer}} -\index{calibrate\_accelerometer@{calibrate\_accelerometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{calibrate\_accelerometer()}{calibrate\_accelerometer()}} -{\footnotesize\ttfamily void BNO08x\+::calibrate\+\_\+accelerometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to calibrate accelerometer. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128}\label{class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128} -\index{BNO08x@{BNO08x}!calibrate\_all@{calibrate\_all}} -\index{calibrate\_all@{calibrate\_all}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{calibrate\_all()}{calibrate\_all()}} -{\footnotesize\ttfamily void BNO08x\+::calibrate\+\_\+all (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to calibrate accelerometer, gyro, and magnetometer. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1}\label{class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1} -\index{BNO08x@{BNO08x}!calibrate\_gyro@{calibrate\_gyro}} -\index{calibrate\_gyro@{calibrate\_gyro}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{calibrate\_gyro()}{calibrate\_gyro()}} -{\footnotesize\ttfamily void BNO08x\+::calibrate\+\_\+gyro (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to calibrate gyro. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a}\label{class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a} -\index{BNO08x@{BNO08x}!calibrate\_magnetometer@{calibrate\_magnetometer}} -\index{calibrate\_magnetometer@{calibrate\_magnetometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{calibrate\_magnetometer()}{calibrate\_magnetometer()}} -{\footnotesize\ttfamily void BNO08x\+::calibrate\+\_\+magnetometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to calibrate magnetometer. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26}\label{class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26} -\index{BNO08x@{BNO08x}!calibrate\_planar\_accelerometer@{calibrate\_planar\_accelerometer}} -\index{calibrate\_planar\_accelerometer@{calibrate\_planar\_accelerometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{calibrate\_planar\_accelerometer()}{calibrate\_planar\_accelerometer()}} -{\footnotesize\ttfamily void BNO08x\+::calibrate\+\_\+planar\+\_\+accelerometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to calibrate planar accelerometer. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b}\label{class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b} -\index{BNO08x@{BNO08x}!calibration\_complete@{calibration\_complete}} -\index{calibration\_complete@{calibration\_complete}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{calibration\_complete()}{calibration\_complete()}} -{\footnotesize\ttfamily bool BNO08x\+::calibration\+\_\+complete (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Returns true if calibration has completed. - -\begin{DoxyReturn}{Returns} -True if calibration complete, false if otherwise. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e}\label{class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e} -\index{BNO08x@{BNO08x}!clear\_tare@{clear\_tare}} -\index{clear\_tare@{clear\_tare}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{clear\_tare()}{clear\_tare()}} -{\footnotesize\ttfamily void BNO08x\+::clear\+\_\+tare (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to clear persistent tare settings in non-\/volatile memory of \doxylink{class_b_n_o08x}{BNO08x} (See Ref. Manual 6.\+4.\+4.\+3) - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86}\label{class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86} -\index{BNO08x@{BNO08x}!data\_available@{data\_available}} -\index{data\_available@{data\_available}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{data\_available()}{data\_available()}} -{\footnotesize\ttfamily bool BNO08x\+::data\+\_\+available (\begin{DoxyParamCaption}\item[{bool}]{ignore\+\_\+no\+\_\+reports\+\_\+enabled = {\ttfamily false} }\end{DoxyParamCaption})} - - - -Checks if \doxylink{class_b_n_o08x}{BNO08x} has asserted interrupt and sent data. - - -\begin{DoxyParams}{Parameters} -{\em ignore\+\_\+no\+\_\+reports\+\_\+enabled} & Forces a wait for data even if no reports are enabled (default is false), used for unit tests.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if new data has been parsed and saved, false if otherwise. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8}\label{class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8} -\index{BNO08x@{BNO08x}!data\_proc\_task@{data\_proc\_task}} -\index{data\_proc\_task@{data\_proc\_task}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{data\_proc\_task()}{data\_proc\_task()}} -{\footnotesize\ttfamily void BNO08x\+::data\+\_\+proc\+\_\+task (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Task responsible parsing packets. Executed when SPI task sends a packet to be parsed, notifies \doxylink{class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf}{wait\+\_\+for\+\_\+data()} call. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520}\label{class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520} -\index{BNO08x@{BNO08x}!data\_proc\_task\_trampoline@{data\_proc\_task\_trampoline}} -\index{data\_proc\_task\_trampoline@{data\_proc\_task\_trampoline}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{data\_proc\_task\_trampoline()}{data\_proc\_task\_trampoline()}} -{\footnotesize\ttfamily void BNO08x\+::data\+\_\+proc\+\_\+task\+\_\+trampoline (\begin{DoxyParamCaption}\item[{void \texorpdfstring{$\ast$}{*}}]{arg }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [private]}} - - - -Static function used to launch data processing task. - -Used such that \doxylink{class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8}{data\+\_\+proc\+\_\+task()} can be non-\/static class member. - - -\begin{DoxyParams}{Parameters} -{\em arg} & void pointer to \doxylink{class_b_n_o08x}{BNO08x} imu object \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3}\label{class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3} -\index{BNO08x@{BNO08x}!deinit\_gpio@{deinit\_gpio}} -\index{deinit\_gpio@{deinit\_gpio}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{deinit\_gpio()}{deinit\_gpio()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::deinit\+\_\+gpio (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Deinitializes GPIO, called from deconstructor. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if deinitialization was success. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=327pt]{class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=323pt]{class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c}\label{class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c} -\index{BNO08x@{BNO08x}!deinit\_gpio\_inputs@{deinit\_gpio\_inputs}} -\index{deinit\_gpio\_inputs@{deinit\_gpio\_inputs}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{deinit\_gpio\_inputs()}{deinit\_gpio\_inputs()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::deinit\+\_\+gpio\+\_\+inputs (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Deinitializes GPIO inputs, called from deconstructor. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if deinitialization was success. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ab132a061bd437fd109225446aa1f6010}\label{class_b_n_o08x_ab132a061bd437fd109225446aa1f6010} -\index{BNO08x@{BNO08x}!deinit\_gpio\_outputs@{deinit\_gpio\_outputs}} -\index{deinit\_gpio\_outputs@{deinit\_gpio\_outputs}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{deinit\_gpio\_outputs()}{deinit\_gpio\_outputs()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::deinit\+\_\+gpio\+\_\+outputs (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Deinitializes GPIO outputs, called from deconstructor. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if deinitialization was success. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758}\label{class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758} -\index{BNO08x@{BNO08x}!deinit\_hint\_isr@{deinit\_hint\_isr}} -\index{deinit\_hint\_isr@{deinit\_hint\_isr}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{deinit\_hint\_isr()}{deinit\_hint\_isr()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::deinit\+\_\+hint\+\_\+isr (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Deinitializes host interrupt ISR, called from deconstructor. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if deinitialization was success. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=336pt]{class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a233920ce97f685fbdabecccacf471d85}\label{class_b_n_o08x_a233920ce97f685fbdabecccacf471d85} -\index{BNO08x@{BNO08x}!deinit\_spi@{deinit\_spi}} -\index{deinit\_spi@{deinit\_spi}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{deinit\_spi()}{deinit\_spi()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::deinit\+\_\+spi (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Deinitializes SPI. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if deinitialization was success. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=318pt]{class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ad5c991150895b80bee68c933059a4058}\label{class_b_n_o08x_ad5c991150895b80bee68c933059a4058} -\index{BNO08x@{BNO08x}!disable\_accelerometer@{disable\_accelerometer}} -\index{disable\_accelerometer@{disable\_accelerometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_accelerometer()}{disable\_accelerometer()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+accelerometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable accelerometer reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=345pt]{class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376}\label{class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376} -\index{BNO08x@{BNO08x}!disable\_activity\_classifier@{disable\_activity\_classifier}} -\index{disable\_activity\_classifier@{disable\_activity\_classifier}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_activity\_classifier()}{disable\_activity\_classifier()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+activity\+\_\+classifier (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable activity classifier reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=313pt]{class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c}\label{class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c} -\index{BNO08x@{BNO08x}!disable\_ARVR\_stabilized\_game\_rotation\_vector@{disable\_ARVR\_stabilized\_game\_rotation\_vector}} -\index{disable\_ARVR\_stabilized\_game\_rotation\_vector@{disable\_ARVR\_stabilized\_game\_rotation\_vector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_ARVR\_stabilized\_game\_rotation\_vector()}{disable\_ARVR\_stabilized\_game\_rotation\_vector()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+\+ARVR\+\_\+stabilized\+\_\+game\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable ARVR stabilized game rotation vector reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=318pt]{class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4}\label{class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4} -\index{BNO08x@{BNO08x}!disable\_ARVR\_stabilized\_rotation\_vector@{disable\_ARVR\_stabilized\_rotation\_vector}} -\index{disable\_ARVR\_stabilized\_rotation\_vector@{disable\_ARVR\_stabilized\_rotation\_vector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_ARVR\_stabilized\_rotation\_vector()}{disable\_ARVR\_stabilized\_rotation\_vector()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+\+ARVR\+\_\+stabilized\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable ARVR stabilized rotation vector reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=310pt]{class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c}\label{class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c} -\index{BNO08x@{BNO08x}!disable\_calibrated\_gyro@{disable\_calibrated\_gyro}} -\index{disable\_calibrated\_gyro@{disable\_calibrated\_gyro}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_calibrated\_gyro()}{disable\_calibrated\_gyro()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+calibrated\+\_\+gyro (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable calibrated gyro reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=349pt]{class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a7665cce95e791c89161ec863f49c0392}\label{class_b_n_o08x_a7665cce95e791c89161ec863f49c0392} -\index{BNO08x@{BNO08x}!disable\_game\_rotation\_vector@{disable\_game\_rotation\_vector}} -\index{disable\_game\_rotation\_vector@{disable\_game\_rotation\_vector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_game\_rotation\_vector()}{disable\_game\_rotation\_vector()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+game\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable game rotation vector reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=307pt]{class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f}\label{class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f} -\index{BNO08x@{BNO08x}!disable\_gravity@{disable\_gravity}} -\index{disable\_gravity@{disable\_gravity}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_gravity()}{disable\_gravity()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+gravity (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable gravity reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=311pt]{class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931}\label{class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931} -\index{BNO08x@{BNO08x}!disable\_gyro\_integrated\_rotation\_vector@{disable\_gyro\_integrated\_rotation\_vector}} -\index{disable\_gyro\_integrated\_rotation\_vector@{disable\_gyro\_integrated\_rotation\_vector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_gyro\_integrated\_rotation\_vector()}{disable\_gyro\_integrated\_rotation\_vector()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+gyro\+\_\+integrated\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable gyro integrated rotation vector reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=302pt]{class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f}\label{class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f} -\index{BNO08x@{BNO08x}!disable\_linear\_accelerometer@{disable\_linear\_accelerometer}} -\index{disable\_linear\_accelerometer@{disable\_linear\_accelerometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_linear\_accelerometer()}{disable\_linear\_accelerometer()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+linear\+\_\+accelerometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable linear accelerometer reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=306pt]{class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338}\label{class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338} -\index{BNO08x@{BNO08x}!disable\_magnetometer@{disable\_magnetometer}} -\index{disable\_magnetometer@{disable\_magnetometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_magnetometer()}{disable\_magnetometer()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+magnetometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable magnetometer reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=345pt]{class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce}\label{class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce} -\index{BNO08x@{BNO08x}!disable\_raw\_mems\_accelerometer@{disable\_raw\_mems\_accelerometer}} -\index{disable\_raw\_mems\_accelerometer@{disable\_raw\_mems\_accelerometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_raw\_mems\_accelerometer()}{disable\_raw\_mems\_accelerometer()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+raw\+\_\+mems\+\_\+accelerometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable raw accelerometer reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725}\label{class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725} -\index{BNO08x@{BNO08x}!disable\_raw\_mems\_gyro@{disable\_raw\_mems\_gyro}} -\index{disable\_raw\_mems\_gyro@{disable\_raw\_mems\_gyro}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_raw\_mems\_gyro()}{disable\_raw\_mems\_gyro()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+raw\+\_\+mems\+\_\+gyro (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable raw gyro reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2}\label{class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2} -\index{BNO08x@{BNO08x}!disable\_raw\_mems\_magnetometer@{disable\_raw\_mems\_magnetometer}} -\index{disable\_raw\_mems\_magnetometer@{disable\_raw\_mems\_magnetometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_raw\_mems\_magnetometer()}{disable\_raw\_mems\_magnetometer()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+raw\+\_\+mems\+\_\+magnetometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable raw magnetometer reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693}\label{class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693} -\index{BNO08x@{BNO08x}!disable\_report@{disable\_report}} -\index{disable\_report@{disable\_report}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_report()}{disable\_report()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+report (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{report\+\_\+\+ID, }\item[{const Event\+Bits\+\_\+t}]{report\+\_\+evt\+\_\+grp\+\_\+bit }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Disables a sensor report for a given ID by setting its time interval to 0. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+\+ID} & The report ID of the sensor, i.\+e. SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+X \\ -\hline -{\em report\+\_\+evt\+\_\+grp\+\_\+bit} & The event group bit for the respective report, to indicate to \doxylink{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf}{spi\+\_\+task()} it\textquotesingle{}s disabled, i.\+e. EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+X\\ -\hline -\end{DoxyParams} -If no reports are enabled after disabling, this function will disable interrupts on hint pin. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921}\label{class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921} -\index{BNO08x@{BNO08x}!disable\_rotation\_vector@{disable\_rotation\_vector}} -\index{disable\_rotation\_vector@{disable\_rotation\_vector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_rotation\_vector()}{disable\_rotation\_vector()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable rotation vector reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=315pt]{class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932}\label{class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932} -\index{BNO08x@{BNO08x}!disable\_stability\_classifier@{disable\_stability\_classifier}} -\index{disable\_stability\_classifier@{disable\_stability\_classifier}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_stability\_classifier()}{disable\_stability\_classifier()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+stability\+\_\+classifier (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable stability reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=317pt]{class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a427550a4ba25252912436b899124e157}\label{class_b_n_o08x_a427550a4ba25252912436b899124e157} -\index{BNO08x@{BNO08x}!disable\_step\_counter@{disable\_step\_counter}} -\index{disable\_step\_counter@{disable\_step\_counter}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_step\_counter()}{disable\_step\_counter()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+step\+\_\+counter (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable step counter reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=302pt]{class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2}\label{class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2} -\index{BNO08x@{BNO08x}!disable\_tap\_detector@{disable\_tap\_detector}} -\index{disable\_tap\_detector@{disable\_tap\_detector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_tap\_detector()}{disable\_tap\_detector()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+tap\+\_\+detector (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable tap detector reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc}\label{class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc} -\index{BNO08x@{BNO08x}!disable\_uncalibrated\_gyro@{disable\_uncalibrated\_gyro}} -\index{disable\_uncalibrated\_gyro@{disable\_uncalibrated\_gyro}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{disable\_uncalibrated\_gyro()}{disable\_uncalibrated\_gyro()}} -{\footnotesize\ttfamily void BNO08x\+::disable\+\_\+uncalibrated\+\_\+gyro (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to disable uncalibrated gyro reports by setting report interval to 0. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91}\label{class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91} -\index{BNO08x@{BNO08x}!enable\_accelerometer@{enable\_accelerometer}} -\index{enable\_accelerometer@{enable\_accelerometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_accelerometer()}{enable\_accelerometer()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+accelerometer (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable accelerometer reports (See Ref. Manual 6.\+5.\+9) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=342pt]{class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a039e8770759e784baa438324ae17883c}\label{class_b_n_o08x_a039e8770759e784baa438324ae17883c} -\index{BNO08x@{BNO08x}!enable\_activity\_classifier@{enable\_activity\_classifier}} -\index{enable\_activity\_classifier@{enable\_activity\_classifier}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_activity\_classifier()}{enable\_activity\_classifier()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+activity\+\_\+classifier (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports, }\item[{\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_adc1b530563e35a96fc1b8911ff133e0f}{BNO08x\+Activity\+Enable}}}]{activities\+\_\+to\+\_\+enable, }\item[{uint8\+\_\+t(\&)}]{activity\+\_\+confidence\+\_\+vals\mbox{[}9\mbox{]} }\end{DoxyParamCaption})} - - - -Sends command to enable activity classifier reports (See Ref. Manual 6.\+5.\+36) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -{\em activities\+\_\+to\+\_\+enable} & Desired activities to enable (0x1F enables all). \\ -\hline -{\em activity\+\_\+confidence\+\_\+vals} & Returned activity level confidences. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=311pt]{class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8}\label{class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8} -\index{BNO08x@{BNO08x}!enable\_ARVR\_stabilized\_game\_rotation\_vector@{enable\_ARVR\_stabilized\_game\_rotation\_vector}} -\index{enable\_ARVR\_stabilized\_game\_rotation\_vector@{enable\_ARVR\_stabilized\_game\_rotation\_vector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_ARVR\_stabilized\_game\_rotation\_vector()}{enable\_ARVR\_stabilized\_game\_rotation\_vector()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+\+ARVR\+\_\+stabilized\+\_\+game\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6.\+5.\+43) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=318pt]{class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc}\label{class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc} -\index{BNO08x@{BNO08x}!enable\_ARVR\_stabilized\_rotation\_vector@{enable\_ARVR\_stabilized\_rotation\_vector}} -\index{enable\_ARVR\_stabilized\_rotation\_vector@{enable\_ARVR\_stabilized\_rotation\_vector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_ARVR\_stabilized\_rotation\_vector()}{enable\_ARVR\_stabilized\_rotation\_vector()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+\+ARVR\+\_\+stabilized\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6.\+5.\+42) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=308pt]{class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53}\label{class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53} -\index{BNO08x@{BNO08x}!enable\_calibrated\_gyro@{enable\_calibrated\_gyro}} -\index{enable\_calibrated\_gyro@{enable\_calibrated\_gyro}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_calibrated\_gyro()}{enable\_calibrated\_gyro()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+calibrated\+\_\+gyro (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable calibrated gyro reports (See Ref. Manual 6.\+5.\+13) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=347pt]{class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947}\label{class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947} -\index{BNO08x@{BNO08x}!enable\_game\_rotation\_vector@{enable\_game\_rotation\_vector}} -\index{enable\_game\_rotation\_vector@{enable\_game\_rotation\_vector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_game\_rotation\_vector()}{enable\_game\_rotation\_vector()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+game\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable game rotation vector reports (See Ref. Manual 6.\+5.\+19) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a030eae12c3586acf09b48e94630b2544}\label{class_b_n_o08x_a030eae12c3586acf09b48e94630b2544} -\index{BNO08x@{BNO08x}!enable\_gravity@{enable\_gravity}} -\index{enable\_gravity@{enable\_gravity}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_gravity()}{enable\_gravity()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+gravity (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable gravity reading reports (See Ref. Manual 6.\+5.\+11) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=309pt]{class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d}\label{class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d} -\index{BNO08x@{BNO08x}!enable\_gyro\_integrated\_rotation\_vector@{enable\_gyro\_integrated\_rotation\_vector}} -\index{enable\_gyro\_integrated\_rotation\_vector@{enable\_gyro\_integrated\_rotation\_vector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_gyro\_integrated\_rotation\_vector()}{enable\_gyro\_integrated\_rotation\_vector()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+gyro\+\_\+integrated\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6.\+5.\+44) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=300pt]{class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b}\label{class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b} -\index{BNO08x@{BNO08x}!enable\_linear\_accelerometer@{enable\_linear\_accelerometer}} -\index{enable\_linear\_accelerometer@{enable\_linear\_accelerometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_linear\_accelerometer()}{enable\_linear\_accelerometer()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+linear\+\_\+accelerometer (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable linear accelerometer reports (See Ref. Manual 6.\+5.\+10) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=304pt]{class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59}\label{class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59} -\index{BNO08x@{BNO08x}!enable\_magnetometer@{enable\_magnetometer}} -\index{enable\_magnetometer@{enable\_magnetometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_magnetometer()}{enable\_magnetometer()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+magnetometer (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable magnetometer reports (See Ref. Manual 6.\+5.\+16) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b}\label{class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b} -\index{BNO08x@{BNO08x}!enable\_raw\_mems\_accelerometer@{enable\_raw\_mems\_accelerometer}} -\index{enable\_raw\_mems\_accelerometer@{enable\_raw\_mems\_accelerometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_raw\_mems\_accelerometer()}{enable\_raw\_mems\_accelerometer()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+raw\+\_\+mems\+\_\+accelerometer (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable raw MEMs accelerometer reports (See Ref. Manual 6.\+5.\+8) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a8be135ed41646199540583b29806d4e5}\label{class_b_n_o08x_a8be135ed41646199540583b29806d4e5} -\index{BNO08x@{BNO08x}!enable\_raw\_mems\_gyro@{enable\_raw\_mems\_gyro}} -\index{enable\_raw\_mems\_gyro@{enable\_raw\_mems\_gyro}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_raw\_mems\_gyro()}{enable\_raw\_mems\_gyro()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+raw\+\_\+mems\+\_\+gyro (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable raw MEMs gyro reports (See Ref. Manual 6.\+5.\+12) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5}\label{class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5} -\index{BNO08x@{BNO08x}!enable\_raw\_mems\_magnetometer@{enable\_raw\_mems\_magnetometer}} -\index{enable\_raw\_mems\_magnetometer@{enable\_raw\_mems\_magnetometer}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_raw\_mems\_magnetometer()}{enable\_raw\_mems\_magnetometer()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+raw\+\_\+mems\+\_\+magnetometer (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable raw MEMs magnetometer reports (See Ref. Manual 6.\+5.\+15) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca}\label{class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca} -\index{BNO08x@{BNO08x}!enable\_report@{enable\_report}} -\index{enable\_report@{enable\_report}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_report()}{enable\_report()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+report (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{report\+\_\+\+ID, }\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports, }\item[{const Event\+Bits\+\_\+t}]{report\+\_\+evt\+\_\+grp\+\_\+bit, }\item[{uint32\+\_\+t}]{special\+\_\+config = {\ttfamily 0} }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Enables a sensor report for a given ID. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+\+ID} & The report ID of the sensor, i.\+e. SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+X \\ -\hline -{\em time\+\_\+between\+\_\+reports} & The desired time in microseconds between each report. The \doxylink{class_b_n_o08x}{BNO08x} will send reports according to this interval. \\ -\hline -{\em report\+\_\+evt\+\_\+grp\+\_\+bit} & The event group bit for the respective report, to indicate to \doxylink{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf}{spi\+\_\+task()} it\textquotesingle{}s enabled, i.\+e. EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+X\\ -\hline -\end{DoxyParams} -If no reports were enabled prior to call, this function will re-\/enable interrupts on hint pin. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7}\label{class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7} -\index{BNO08x@{BNO08x}!enable\_rotation\_vector@{enable\_rotation\_vector}} -\index{enable\_rotation\_vector@{enable\_rotation\_vector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_rotation\_vector()}{enable\_rotation\_vector()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable rotation vector reports (See Ref. Manual 6.\+5.\+18) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=313pt]{class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655}\label{class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655} -\index{BNO08x@{BNO08x}!enable\_stability\_classifier@{enable\_stability\_classifier}} -\index{enable\_stability\_classifier@{enable\_stability\_classifier}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_stability\_classifier()}{enable\_stability\_classifier()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+stability\+\_\+classifier (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable activity stability classifier reports (See Ref. Manual 6.\+5.\+31) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=315pt]{class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f}\label{class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f} -\index{BNO08x@{BNO08x}!enable\_step\_counter@{enable\_step\_counter}} -\index{enable\_step\_counter@{enable\_step\_counter}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_step\_counter()}{enable\_step\_counter()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+step\+\_\+counter (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable step counter reports (See Ref. Manual 6.\+5.\+29) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=300pt]{class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566}\label{class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566} -\index{BNO08x@{BNO08x}!enable\_tap\_detector@{enable\_tap\_detector}} -\index{enable\_tap\_detector@{enable\_tap\_detector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_tap\_detector()}{enable\_tap\_detector()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+tap\+\_\+detector (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable tap detector reports (See Ref. Manual 6.\+5.\+27) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75}\label{class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75} -\index{BNO08x@{BNO08x}!enable\_uncalibrated\_gyro@{enable\_uncalibrated\_gyro}} -\index{enable\_uncalibrated\_gyro@{enable\_uncalibrated\_gyro}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{enable\_uncalibrated\_gyro()}{enable\_uncalibrated\_gyro()}} -{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+uncalibrated\+\_\+gyro (\begin{DoxyParamCaption}\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} - - - -Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.\+5.\+14) - - -\begin{DoxyParams}{Parameters} -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2}\label{class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2} -\index{BNO08x@{BNO08x}!end\_calibration@{end\_calibration}} -\index{end\_calibration@{end\_calibration}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{end\_calibration()}{end\_calibration()}} -{\footnotesize\ttfamily void BNO08x\+::end\+\_\+calibration (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to end calibration procedure. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc}\label{class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc} -\index{BNO08x@{BNO08x}!flush\_rx\_packets@{flush\_rx\_packets}} -\index{flush\_rx\_packets@{flush\_rx\_packets}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{flush\_rx\_packets()}{flush\_rx\_packets()}} -{\footnotesize\ttfamily void BNO08x\+::flush\+\_\+rx\+\_\+packets (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{flush\+\_\+count }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1}\label{class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1} -\index{BNO08x@{BNO08x}!FRS\_read\_data@{FRS\_read\_data}} -\index{FRS\_read\_data@{FRS\_read\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{FRS\_read\_data()}{FRS\_read\_data()}} -{\footnotesize\ttfamily bool BNO08x\+::\+FRS\+\_\+read\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID, }\item[{uint8\+\_\+t}]{start\+\_\+location, }\item[{uint8\+\_\+t}]{words\+\_\+to\+\_\+read }\end{DoxyParamCaption})} - - - -Read meta data from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.\+1 \& 6.\+3.\+7) - -Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. - - -\begin{DoxyParams}{Parameters} -{\em record\+\_\+\+ID} & Which record ID/ sensor to request meta data from. \\ -\hline -{\em start\+\_\+location} & Start byte location. \\ -\hline -{\em words\+\_\+to\+\_\+read} & Length of words to read.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if meta data read successfully. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_adf789e709ac1667656db757c8d559af9}\label{class_b_n_o08x_adf789e709ac1667656db757c8d559af9} -\index{BNO08x@{BNO08x}!FRS\_read\_request@{FRS\_read\_request}} -\index{FRS\_read\_request@{FRS\_read\_request}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{FRS\_read\_request()}{FRS\_read\_request()}} -{\footnotesize\ttfamily bool BNO08x\+::\+FRS\+\_\+read\+\_\+request (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID, }\item[{uint16\+\_\+t}]{read\+\_\+offset, }\item[{uint16\+\_\+t}]{block\+\_\+size }\end{DoxyParamCaption})} - - - -Requests meta data from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.\+1 \& 6.\+3.\+6) - -Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. - - -\begin{DoxyParams}{Parameters} -{\em record\+\_\+\+ID} & Which record ID/ sensor to request meta data from. \\ -\hline -{\em start\+\_\+location} & Start byte location. \\ -\hline -{\em words\+\_\+to\+\_\+read} & Length of words to read.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if read request acknowledged (HINT was asserted) -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41}\label{class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41} -\index{BNO08x@{BNO08x}!FRS\_read\_word@{FRS\_read\_word}} -\index{FRS\_read\_word@{FRS\_read\_word}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{FRS\_read\_word()}{FRS\_read\_word()}} -{\footnotesize\ttfamily uint32\+\_\+t BNO08x\+::\+FRS\+\_\+read\+\_\+word (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID, }\item[{uint8\+\_\+t}]{word\+\_\+number }\end{DoxyParamCaption})} - - - -Reads meta data word from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system) given the record ID and word number. (See Ref. Manual 5.\+1 \& 6.\+3.\+7) - -Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. - - -\begin{DoxyParams}{Parameters} -{\em record\+\_\+\+ID} & Which record ID/ sensor to request meta data from. \\ -\hline -{\em word\+\_\+number} & Desired word to read.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Requested meta data word, 0 if failed. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885}\label{class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885} -\index{BNO08x@{BNO08x}!get\_accel@{get\_accel}} -\index{get\_accel@{get\_accel}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_accel()}{get\_accel()}} -{\footnotesize\ttfamily void BNO08x\+::get\+\_\+accel (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z, }\item[{\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \&}]{accuracy }\end{DoxyParamCaption})} - - - -Get full acceleration (total acceleration of device, units in m/s\texorpdfstring{$^\wedge$}{\string^}2). - - -\begin{DoxyParams}{Parameters} -{\em x} & Reference variable to save X axis acceleration. \\ -\hline -{\em y} & Reference variable to save Y axis acceleration. \\ -\hline -{\em z} & Reference variable to save Z axis acceleration. \\ -\hline -{\em accuracy} & Reference variable to save reported acceleration accuracy.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=318pt]{class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a6eed9e2d3e639ec7e38dfdf092c14ea1}\label{class_b_n_o08x_a6eed9e2d3e639ec7e38dfdf092c14ea1} -\index{BNO08x@{BNO08x}!get\_accel\_accuracy@{get\_accel\_accuracy}} -\index{get\_accel\_accuracy@{get\_accel\_accuracy}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_accel\_accuracy()}{get\_accel\_accuracy()}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} BNO08x\+::get\+\_\+accel\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get accuracy of linear acceleration. - -\begin{DoxyReturn}{Returns} -Accuracy of linear acceleration. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69}\label{class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69} -\index{BNO08x@{BNO08x}!get\_accel\_X@{get\_accel\_X}} -\index{get\_accel\_X@{get\_accel\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_accel\_X()}{get\_accel\_X()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+accel\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get x axis acceleration (total acceleration of device, units in m/s\texorpdfstring{$^\wedge$}{\string^}2). - -\begin{DoxyReturn}{Returns} -The angular reported x axis acceleration. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=328pt]{class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1}\label{class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1} -\index{BNO08x@{BNO08x}!get\_accel\_Y@{get\_accel\_Y}} -\index{get\_accel\_Y@{get\_accel\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_accel\_Y()}{get\_accel\_Y()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+accel\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get y axis acceleration (total acceleration of device, units in m/s\texorpdfstring{$^\wedge$}{\string^}2). - -\begin{DoxyReturn}{Returns} -The angular reported y axis acceleration. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=330pt]{class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1}\label{class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1} -\index{BNO08x@{BNO08x}!get\_accel\_Z@{get\_accel\_Z}} -\index{get\_accel\_Z@{get\_accel\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_accel\_Z()}{get\_accel\_Z()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+accel\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get z axis acceleration (total acceleration of device, units in m/s\texorpdfstring{$^\wedge$}{\string^}2). - -\begin{DoxyReturn}{Returns} -The angular reported z axis acceleration. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=328pt]{class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed}\label{class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed} -\index{BNO08x@{BNO08x}!get\_activity\_classifier@{get\_activity\_classifier}} -\index{get\_activity\_classifier@{get\_activity\_classifier}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_activity\_classifier()}{get\_activity\_classifier()}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}{BNO08x\+Activity}} BNO08x\+::get\+\_\+activity\+\_\+classifier (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the current activity classifier (Seee Ref. Manual 6.\+5.\+36) - -\begin{DoxyReturn}{Returns} -The current activity\+: 0 = unknown 1 = in vehicle 2 = on bicycle 3 = on foot 4 = still 5 = tilting 6 = walking 7 = runnning 8 = on stairs -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f}\label{class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f} -\index{BNO08x@{BNO08x}!get\_calibrated\_gyro\_velocity@{get\_calibrated\_gyro\_velocity}} -\index{get\_calibrated\_gyro\_velocity@{get\_calibrated\_gyro\_velocity}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_calibrated\_gyro\_velocity()}{get\_calibrated\_gyro\_velocity()}} -{\footnotesize\ttfamily void BNO08x\+::get\+\_\+calibrated\+\_\+gyro\+\_\+velocity (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z }\end{DoxyParamCaption})} - - - -Get full rotational velocity with drift compensation (units in Rad/s). - - -\begin{DoxyParams}{Parameters} -{\em x} & Reference variable to save X axis angular velocity \\ -\hline -{\em y} & Reference variable to save Y axis angular velocity \\ -\hline -{\em z} & Reference variable to save Z axis angular velocity\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=336pt]{class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889}\label{class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889} -\index{BNO08x@{BNO08x}!get\_calibrated\_gyro\_velocity\_X@{get\_calibrated\_gyro\_velocity\_X}} -\index{get\_calibrated\_gyro\_velocity\_X@{get\_calibrated\_gyro\_velocity\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_calibrated\_gyro\_velocity\_X()}{get\_calibrated\_gyro\_velocity\_X()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+calibrated\+\_\+gyro\+\_\+velocity\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get calibrated gyro x axis angular velocity measurement. - -\begin{DoxyReturn}{Returns} -The angular reported x axis angular velocity from calibrated gyro (drift compensation applied). -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=336pt]{class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50}\label{class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50} -\index{BNO08x@{BNO08x}!get\_calibrated\_gyro\_velocity\_Y@{get\_calibrated\_gyro\_velocity\_Y}} -\index{get\_calibrated\_gyro\_velocity\_Y@{get\_calibrated\_gyro\_velocity\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_calibrated\_gyro\_velocity\_Y()}{get\_calibrated\_gyro\_velocity\_Y()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+calibrated\+\_\+gyro\+\_\+velocity\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get calibrated gyro y axis angular velocity measurement. - -\begin{DoxyReturn}{Returns} -The angular reported y axis angular velocity from calibrated gyro (drift compensation applied). -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=336pt]{class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea}\label{class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea} -\index{BNO08x@{BNO08x}!get\_calibrated\_gyro\_velocity\_Z@{get\_calibrated\_gyro\_velocity\_Z}} -\index{get\_calibrated\_gyro\_velocity\_Z@{get\_calibrated\_gyro\_velocity\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_calibrated\_gyro\_velocity\_Z()}{get\_calibrated\_gyro\_velocity\_Z()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+calibrated\+\_\+gyro\+\_\+velocity\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get calibrated gyro z axis angular velocity measurement. - -\begin{DoxyReturn}{Returns} -The angular reported z axis angular velocity from calibrated gyro (drift compensation applied). -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=336pt]{class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a067678914e928a6691625b17c40237a0}\label{class_b_n_o08x_a067678914e928a6691625b17c40237a0} -\index{BNO08x@{BNO08x}!get\_gravity@{get\_gravity}} -\index{get\_gravity@{get\_gravity}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_gravity()}{get\_gravity()}} -{\footnotesize\ttfamily void BNO08x\+::get\+\_\+gravity (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z, }\item[{\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \&}]{accuracy }\end{DoxyParamCaption})} - - - -Get full reported gravity vector, units in m/s\texorpdfstring{$^\wedge$}{\string^}2. - - -\begin{DoxyParams}{Parameters} -{\em x} & Reference variable to save X axis gravity. \\ -\hline -{\em y} & Reference variable to save Y axis axis gravity. \\ -\hline -{\em z} & Reference variable to save Z axis axis gravity. \\ -\hline -{\em accuracy} & Reference variable to save reported gravity accuracy.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=322pt]{class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a77c82cece30dde944efcde81643fd62d}\label{class_b_n_o08x_a77c82cece30dde944efcde81643fd62d} -\index{BNO08x@{BNO08x}!get\_gravity\_accuracy@{get\_gravity\_accuracy}} -\index{get\_gravity\_accuracy@{get\_gravity\_accuracy}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_gravity\_accuracy()}{get\_gravity\_accuracy()}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} BNO08x\+::get\+\_\+gravity\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the reported gravity accuracy. - -\begin{DoxyReturn}{Returns} -Accuracy of reported gravity. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae}\label{class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae} -\index{BNO08x@{BNO08x}!get\_gravity\_X@{get\_gravity\_X}} -\index{get\_gravity\_X@{get\_gravity\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_gravity\_X()}{get\_gravity\_X()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+gravity\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the reported x axis gravity. - -\begin{DoxyReturn}{Returns} -x axis gravity in m/s\texorpdfstring{$^\wedge$}{\string^}2 -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=333pt]{class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a8a36db7f1c932f33e05e494632059801}\label{class_b_n_o08x_a8a36db7f1c932f33e05e494632059801} -\index{BNO08x@{BNO08x}!get\_gravity\_Y@{get\_gravity\_Y}} -\index{get\_gravity\_Y@{get\_gravity\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_gravity\_Y()}{get\_gravity\_Y()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+gravity\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the reported y axis gravity. - -\begin{DoxyReturn}{Returns} -y axis gravity in m/s\texorpdfstring{$^\wedge$}{\string^}2 -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=334pt]{class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807}\label{class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807} -\index{BNO08x@{BNO08x}!get\_gravity\_Z@{get\_gravity\_Z}} -\index{get\_gravity\_Z@{get\_gravity\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_gravity\_Z()}{get\_gravity\_Z()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+gravity\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the reported z axis gravity. - -\begin{DoxyReturn}{Returns} -z axis gravity in m/s\texorpdfstring{$^\wedge$}{\string^}2 -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=333pt]{class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f}\label{class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f} -\index{BNO08x@{BNO08x}!get\_integrated\_gyro\_velocity@{get\_integrated\_gyro\_velocity}} -\index{get\_integrated\_gyro\_velocity@{get\_integrated\_gyro\_velocity}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_integrated\_gyro\_velocity()}{get\_integrated\_gyro\_velocity()}} -{\footnotesize\ttfamily void BNO08x\+::get\+\_\+integrated\+\_\+gyro\+\_\+velocity (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z }\end{DoxyParamCaption})} - - - -Full rotational velocity from gyro-\/integrated rotation vector (See Ref. Manual 6.\+5.\+44) - - -\begin{DoxyParams}{Parameters} -{\em x} & Reference variable to save X axis angular velocity \\ -\hline -{\em y} & Reference variable to save Y axis angular velocity \\ -\hline -{\em z} & Reference variable to save Z axis angular velocity\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=337pt]{class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff}\label{class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff} -\index{BNO08x@{BNO08x}!get\_integrated\_gyro\_velocity\_X@{get\_integrated\_gyro\_velocity\_X}} -\index{get\_integrated\_gyro\_velocity\_X@{get\_integrated\_gyro\_velocity\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_integrated\_gyro\_velocity\_X()}{get\_integrated\_gyro\_velocity\_X()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+integrated\+\_\+gyro\+\_\+velocity\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get x axis angular velocity from gyro-\/integrated rotation vector. (See Ref. Manual 6.\+5.\+44) - -\begin{DoxyReturn}{Returns} -The reported x axis angular velocity. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=337pt]{class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1}\label{class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1} -\index{BNO08x@{BNO08x}!get\_integrated\_gyro\_velocity\_Y@{get\_integrated\_gyro\_velocity\_Y}} -\index{get\_integrated\_gyro\_velocity\_Y@{get\_integrated\_gyro\_velocity\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_integrated\_gyro\_velocity\_Y()}{get\_integrated\_gyro\_velocity\_Y()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+integrated\+\_\+gyro\+\_\+velocity\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get y axis angular velocity from gyro-\/integrated rotation vector. (See Ref. Manual 6.\+5.\+44) - -\begin{DoxyReturn}{Returns} -The reported y axis angular velocity. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=337pt]{class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add}\label{class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add} -\index{BNO08x@{BNO08x}!get\_integrated\_gyro\_velocity\_Z@{get\_integrated\_gyro\_velocity\_Z}} -\index{get\_integrated\_gyro\_velocity\_Z@{get\_integrated\_gyro\_velocity\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_integrated\_gyro\_velocity\_Z()}{get\_integrated\_gyro\_velocity\_Z()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+integrated\+\_\+gyro\+\_\+velocity\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get z axis angular velocity from gyro-\/integrated rotation vector. (See Ref. Manual 6.\+5.\+44) - -\begin{DoxyReturn}{Returns} -The reported Z axis angular velocity. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=337pt]{class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46}\label{class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46} -\index{BNO08x@{BNO08x}!get\_linear\_accel@{get\_linear\_accel}} -\index{get\_linear\_accel@{get\_linear\_accel}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_linear\_accel()}{get\_linear\_accel()}} -{\footnotesize\ttfamily void BNO08x\+::get\+\_\+linear\+\_\+accel (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z, }\item[{\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \&}]{accuracy }\end{DoxyParamCaption})} - - - -Get full linear acceleration (acceleration of the device minus gravity, units in m/s\texorpdfstring{$^\wedge$}{\string^}2). - - -\begin{DoxyParams}{Parameters} -{\em x} & Reference variable to save X axis acceleration. \\ -\hline -{\em y} & Reference variable to save Y axis acceleration. \\ -\hline -{\em z} & Reference variable to save Z axis acceleration. \\ -\hline -{\em accuracy} & Reference variable to save reported linear acceleration accuracy.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=318pt]{class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a6114ba3c8967ac8fde06233c81623c80}\label{class_b_n_o08x_a6114ba3c8967ac8fde06233c81623c80} -\index{BNO08x@{BNO08x}!get\_linear\_accel\_accuracy@{get\_linear\_accel\_accuracy}} -\index{get\_linear\_accel\_accuracy@{get\_linear\_accel\_accuracy}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_linear\_accel\_accuracy()}{get\_linear\_accel\_accuracy()}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} BNO08x\+::get\+\_\+linear\+\_\+accel\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get accuracy of linear acceleration. - -\begin{DoxyReturn}{Returns} -Accuracy of linear acceleration. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3}\label{class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3} -\index{BNO08x@{BNO08x}!get\_linear\_accel\_X@{get\_linear\_accel\_X}} -\index{get\_linear\_accel\_X@{get\_linear\_accel\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_linear\_accel\_X()}{get\_linear\_accel\_X()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+linear\+\_\+accel\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get x axis linear acceleration (acceleration of device minus gravity, units in m/s\texorpdfstring{$^\wedge$}{\string^}2) - -\begin{DoxyReturn}{Returns} -The angular reported x axis linear acceleration. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=318pt]{class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191}\label{class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191} -\index{BNO08x@{BNO08x}!get\_linear\_accel\_Y@{get\_linear\_accel\_Y}} -\index{get\_linear\_accel\_Y@{get\_linear\_accel\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_linear\_accel\_Y()}{get\_linear\_accel\_Y()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+linear\+\_\+accel\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get y axis linear acceleration (acceleration of device minus gravity, units in m/s\texorpdfstring{$^\wedge$}{\string^}2) - -\begin{DoxyReturn}{Returns} -The angular reported y axis linear acceleration. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=318pt]{class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84}\label{class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84} -\index{BNO08x@{BNO08x}!get\_linear\_accel\_Z@{get\_linear\_accel\_Z}} -\index{get\_linear\_accel\_Z@{get\_linear\_accel\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_linear\_accel\_Z()}{get\_linear\_accel\_Z()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+linear\+\_\+accel\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get z axis linear acceleration (acceleration of device minus gravity, units in m/s\texorpdfstring{$^\wedge$}{\string^}2) - -\begin{DoxyReturn}{Returns} -The angular reported z axis linear acceleration. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=318pt]{class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb}\label{class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb} -\index{BNO08x@{BNO08x}!get\_magf@{get\_magf}} -\index{get\_magf@{get\_magf}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_magf()}{get\_magf()}} -{\footnotesize\ttfamily void BNO08x\+::get\+\_\+magf (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z, }\item[{\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \&}]{accuracy }\end{DoxyParamCaption})} - - - -Get the full magnetic field vector. - - -\begin{DoxyParams}{Parameters} -{\em x} & Reference variable to save reported x magnitude. \\ -\hline -{\em y} & Reference variable to save reported y magnitude. \\ -\hline -{\em x} & Reference variable to save reported z magnitude. \\ -\hline -{\em accuracy} & Reference variable to save reported accuracy.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=315pt]{class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9}\label{class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9} -\index{BNO08x@{BNO08x}!get\_magf\_accuracy@{get\_magf\_accuracy}} -\index{get\_magf\_accuracy@{get\_magf\_accuracy}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_magf\_accuracy()}{get\_magf\_accuracy()}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} BNO08x\+::get\+\_\+magf\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get accuracy of reported magnetic field vector. - -\begin{DoxyReturn}{Returns} -The accuracy of reported magnetic field vector. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d}\label{class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d} -\index{BNO08x@{BNO08x}!get\_magf\_X@{get\_magf\_X}} -\index{get\_magf\_X@{get\_magf\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_magf\_X()}{get\_magf\_X()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+magf\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get X component of magnetic field vector. - -\begin{DoxyReturn}{Returns} -The reported X component of magnetic field vector. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=326pt]{class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea}\label{class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea} -\index{BNO08x@{BNO08x}!get\_magf\_Y@{get\_magf\_Y}} -\index{get\_magf\_Y@{get\_magf\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_magf\_Y()}{get\_magf\_Y()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+magf\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get Y component of magnetic field vector. - -\begin{DoxyReturn}{Returns} -The reported Y component of magnetic field vector. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=327pt]{class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282}\label{class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282} -\index{BNO08x@{BNO08x}!get\_magf\_Z@{get\_magf\_Z}} -\index{get\_magf\_Z@{get\_magf\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_magf\_Z()}{get\_magf\_Z()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+magf\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get Z component of magnetic field vector. - -\begin{DoxyReturn}{Returns} -The reported Z component of magnetic field vector. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=326pt]{class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3}\label{class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3} -\index{BNO08x@{BNO08x}!get\_pitch@{get\_pitch}} -\index{get\_pitch@{get\_pitch}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_pitch()}{get\_pitch()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+pitch (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the reported rotation about y axis. - -\begin{DoxyReturn}{Returns} -Rotation about the y axis in radians. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=334pt]{class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_af50010400cbd1445e9ddfa259384b412}\label{class_b_n_o08x_af50010400cbd1445e9ddfa259384b412} -\index{BNO08x@{BNO08x}!get\_pitch\_deg@{get\_pitch\_deg}} -\index{get\_pitch\_deg@{get\_pitch\_deg}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_pitch\_deg()}{get\_pitch\_deg()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+pitch\+\_\+deg (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the reported rotation about y axis. - -\begin{DoxyReturn}{Returns} -Rotation about the y axis in degrees. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a4421c43323945946ad605f8422958dcf}\label{class_b_n_o08x_a4421c43323945946ad605f8422958dcf} -\index{BNO08x@{BNO08x}!get\_Q1@{get\_Q1}} -\index{get\_Q1@{get\_Q1}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_Q1()}{get\_Q1()}} -{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+\+Q1 (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID }\end{DoxyParamCaption})} - - - -Gets Q1 point from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system). - -Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. - - -\begin{DoxyParams}{Parameters} -{\em record\+\_\+\+ID} & Which record ID/ sensor to get Q1 value for.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Q1 value for requested sensor. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=326pt]{class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b}\label{class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b} -\index{BNO08x@{BNO08x}!get\_Q2@{get\_Q2}} -\index{get\_Q2@{get\_Q2}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_Q2()}{get\_Q2()}} -{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+\+Q2 (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID }\end{DoxyParamCaption})} - - - -Gets Q2 point from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system). - -Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. - - -\begin{DoxyParams}{Parameters} -{\em record\+\_\+\+ID} & Which record ID/ sensor to get Q2 value for.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Q2 value for requested sensor. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a}\label{class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a} -\index{BNO08x@{BNO08x}!get\_Q3@{get\_Q3}} -\index{get\_Q3@{get\_Q3}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_Q3()}{get\_Q3()}} -{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+\+Q3 (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID }\end{DoxyParamCaption})} - - - -Gets Q3 point from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system). - -Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. - - -\begin{DoxyParams}{Parameters} -{\em record\+\_\+\+ID} & Which record ID/ sensor to get Q3 value for.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Q3 value for requested sensor. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a}\label{class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a} -\index{BNO08x@{BNO08x}!get\_quat@{get\_quat}} -\index{get\_quat@{get\_quat}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_quat()}{get\_quat()}} -{\footnotesize\ttfamily void BNO08x\+::get\+\_\+quat (\begin{DoxyParamCaption}\item[{float \&}]{i, }\item[{float \&}]{j, }\item[{float \&}]{k, }\item[{float \&}]{real, }\item[{float \&}]{rad\+\_\+accuracy, }\item[{\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \&}]{accuracy }\end{DoxyParamCaption})} - - - -Get the full quaternion reading. - - -\begin{DoxyParams}{Parameters} -{\em i} & Reference variable to save reported i component of quaternion. \\ -\hline -{\em j} & Reference variable to save reported j component of quaternion. \\ -\hline -{\em k} & Reference variable to save reported k component of quaternion. \\ -\hline -{\em real} & Reference variable to save reported real component of quaternion. \\ -\hline -{\em rad\+\_\+accuracy} & Reference variable to save reported raw quaternion radian accuracy. \\ -\hline -{\em accuracy} & Reference variable to save reported quaternion accuracy.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=313pt]{class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654}\label{class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654} -\index{BNO08x@{BNO08x}!get\_quat\_accuracy@{get\_quat\_accuracy}} -\index{get\_quat\_accuracy@{get\_quat\_accuracy}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_quat\_accuracy()}{get\_quat\_accuracy()}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} BNO08x\+::get\+\_\+quat\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get accuracy of reported quaternion. - -\begin{DoxyReturn}{Returns} -The accuracy of reported quaternion. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5}\label{class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5} -\index{BNO08x@{BNO08x}!get\_quat\_I@{get\_quat\_I}} -\index{get\_quat\_I@{get\_quat\_I}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_quat\_I()}{get\_quat\_I()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+quat\+\_\+I (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get I component of reported quaternion. - -\begin{DoxyReturn}{Returns} -The I component of reported quaternion. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=321pt]{class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015}\label{class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015} -\index{BNO08x@{BNO08x}!get\_quat\_J@{get\_quat\_J}} -\index{get\_quat\_J@{get\_quat\_J}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_quat\_J()}{get\_quat\_J()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+quat\+\_\+J (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get J component of reported quaternion. - -\begin{DoxyReturn}{Returns} -The J component of reported quaternion. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=323pt]{class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8}\label{class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8} -\index{BNO08x@{BNO08x}!get\_quat\_K@{get\_quat\_K}} -\index{get\_quat\_K@{get\_quat\_K}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_quat\_K()}{get\_quat\_K()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+quat\+\_\+K (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get K component of reported quaternion. - -\begin{DoxyReturn}{Returns} -The K component of reported quaternion. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=325pt]{class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630}\label{class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630} -\index{BNO08x@{BNO08x}!get\_quat\_radian\_accuracy@{get\_quat\_radian\_accuracy}} -\index{get\_quat\_radian\_accuracy@{get\_quat\_radian\_accuracy}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_quat\_radian\_accuracy()}{get\_quat\_radian\_accuracy()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+quat\+\_\+radian\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get radian accuracy of reported quaternion. - -\begin{DoxyReturn}{Returns} -The radian accuracy of reported quaternion. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=345pt]{class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7}\label{class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7} -\index{BNO08x@{BNO08x}!get\_quat\_real@{get\_quat\_real}} -\index{get\_quat\_real@{get\_quat\_real}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_quat\_real()}{get\_quat\_real()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+quat\+\_\+real (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get real component of reported quaternion. - -\begin{DoxyReturn}{Returns} -The real component of reported quaternion. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=334pt]{class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0}\label{class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0} -\index{BNO08x@{BNO08x}!get\_range@{get\_range}} -\index{get\_range@{get\_range}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_range()}{get\_range()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+range (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID }\end{DoxyParamCaption})} - - - -Gets range from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system). - - -\begin{DoxyParams}{Parameters} -{\em record\+\_\+\+ID} & Which record ID/ sensor to get range value for.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The range value for the requested sensor. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_aa6bbad8c9123b4dba5007f72a8806303}\label{class_b_n_o08x_aa6bbad8c9123b4dba5007f72a8806303} -\index{BNO08x@{BNO08x}!get\_raw\_mems\_accel@{get\_raw\_mems\_accel}} -\index{get\_raw\_mems\_accel@{get\_raw\_mems\_accel}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_raw\_mems\_accel()}{get\_raw\_mems\_accel()}} -{\footnotesize\ttfamily void BNO08x\+::get\+\_\+raw\+\_\+mems\+\_\+accel (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \&}]{x, }\item[{uint16\+\_\+t \&}]{y, }\item[{uint16\+\_\+t \&}]{z }\end{DoxyParamCaption})} - - - -Get full raw acceleration from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8). - - -\begin{DoxyParams}{Parameters} -{\em x} & Reference variable to save raw X axis acceleration. \\ -\hline -{\em y} & Reference variable to save raw Y axis acceleration. \\ -\hline -{\em z} & Reference variable to save raw Z axis acceleration.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_a868b24d96cb12f614431a410bcc9e434}\label{class_b_n_o08x_a868b24d96cb12f614431a410bcc9e434} -\index{BNO08x@{BNO08x}!get\_raw\_mems\_accel\_X@{get\_raw\_mems\_accel\_X}} -\index{get\_raw\_mems\_accel\_X@{get\_raw\_mems\_accel\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_raw\_mems\_accel\_X()}{get\_raw\_mems\_accel\_X()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+mems\+\_\+accel\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8) - -\begin{DoxyReturn}{Returns} -Reported raw accelerometer x axis reading from physical MEMs sensor. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_aebcbaf9c3aaf37d85a78d22dc22c614a}\label{class_b_n_o08x_aebcbaf9c3aaf37d85a78d22dc22c614a} -\index{BNO08x@{BNO08x}!get\_raw\_mems\_accel\_Y@{get\_raw\_mems\_accel\_Y}} -\index{get\_raw\_mems\_accel\_Y@{get\_raw\_mems\_accel\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_raw\_mems\_accel\_Y()}{get\_raw\_mems\_accel\_Y()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+mems\+\_\+accel\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8) - -\begin{DoxyReturn}{Returns} -Reported raw accelerometer y axis reading from physical MEMs sensor. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_a85d1331ebe762f6823bde4bf76a33e21}\label{class_b_n_o08x_a85d1331ebe762f6823bde4bf76a33e21} -\index{BNO08x@{BNO08x}!get\_raw\_mems\_accel\_Z@{get\_raw\_mems\_accel\_Z}} -\index{get\_raw\_mems\_accel\_Z@{get\_raw\_mems\_accel\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_raw\_mems\_accel\_Z()}{get\_raw\_mems\_accel\_Z()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+mems\+\_\+accel\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8) - -\begin{DoxyReturn}{Returns} -Reported raw accelerometer z axis reading from physical MEMs sensor. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27}\label{class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27} -\index{BNO08x@{BNO08x}!get\_raw\_mems\_gyro@{get\_raw\_mems\_gyro}} -\index{get\_raw\_mems\_gyro@{get\_raw\_mems\_gyro}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_raw\_mems\_gyro()}{get\_raw\_mems\_gyro()}} -{\footnotesize\ttfamily void BNO08x\+::get\+\_\+raw\+\_\+mems\+\_\+gyro (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \&}]{x, }\item[{uint16\+\_\+t \&}]{y, }\item[{uint16\+\_\+t \&}]{z }\end{DoxyParamCaption})} - - - -Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) - - -\begin{DoxyParams}{Parameters} -{\em x} & Reference variable to save raw X axis data. \\ -\hline -{\em y} & Reference variable to save raw Y axis data. \\ -\hline -{\em z} & Reference variable to save raw Z axis data.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a8872241c73bca2ac1698ae867f7d1913}\label{class_b_n_o08x_a8872241c73bca2ac1698ae867f7d1913} -\index{BNO08x@{BNO08x}!get\_raw\_mems\_gyro\_X@{get\_raw\_mems\_gyro\_X}} -\index{get\_raw\_mems\_gyro\_X@{get\_raw\_mems\_gyro\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_raw\_mems\_gyro\_X()}{get\_raw\_mems\_gyro\_X()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+mems\+\_\+gyro\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) - -\begin{DoxyReturn}{Returns} -Reported raw gyroscope x axis reading from physical MEMs sensor. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_a4bcc58423b5cc7c24080c2ef812d3d86}\label{class_b_n_o08x_a4bcc58423b5cc7c24080c2ef812d3d86} -\index{BNO08x@{BNO08x}!get\_raw\_mems\_gyro\_Y@{get\_raw\_mems\_gyro\_Y}} -\index{get\_raw\_mems\_gyro\_Y@{get\_raw\_mems\_gyro\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_raw\_mems\_gyro\_Y()}{get\_raw\_mems\_gyro\_Y()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+mems\+\_\+gyro\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) - -\begin{DoxyReturn}{Returns} -Reported raw gyroscope y axis reading from physical MEMs sensor. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_ae684dd13ef630dfdbb8de18ee5ea90bb}\label{class_b_n_o08x_ae684dd13ef630dfdbb8de18ee5ea90bb} -\index{BNO08x@{BNO08x}!get\_raw\_mems\_gyro\_Z@{get\_raw\_mems\_gyro\_Z}} -\index{get\_raw\_mems\_gyro\_Z@{get\_raw\_mems\_gyro\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_raw\_mems\_gyro\_Z()}{get\_raw\_mems\_gyro\_Z()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+mems\+\_\+gyro\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) - -\begin{DoxyReturn}{Returns} -Reported raw gyroscope z axis reading from physical MEMs sensor. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_a929ad333f73614fb5830c186e3e03a00}\label{class_b_n_o08x_a929ad333f73614fb5830c186e3e03a00} -\index{BNO08x@{BNO08x}!get\_raw\_mems\_magf@{get\_raw\_mems\_magf}} -\index{get\_raw\_mems\_magf@{get\_raw\_mems\_magf}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_raw\_mems\_magf()}{get\_raw\_mems\_magf()}} -{\footnotesize\ttfamily void BNO08x\+::get\+\_\+raw\+\_\+mems\+\_\+magf (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \&}]{x, }\item[{uint16\+\_\+t \&}]{y, }\item[{uint16\+\_\+t \&}]{z }\end{DoxyParamCaption})} - - - -Get raw magnetometer full reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) - - -\begin{DoxyParams}{Parameters} -{\em x} & Reference variable to save raw X axis data. \\ -\hline -{\em y} & Reference variable to save raw Y axis data. \\ -\hline -{\em z} & Reference variable to save raw Z axis data.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_a347444f461b2fab5ff37de346ba2a595}\label{class_b_n_o08x_a347444f461b2fab5ff37de346ba2a595} -\index{BNO08x@{BNO08x}!get\_raw\_mems\_magf\_X@{get\_raw\_mems\_magf\_X}} -\index{get\_raw\_mems\_magf\_X@{get\_raw\_mems\_magf\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_raw\_mems\_magf\_X()}{get\_raw\_mems\_magf\_X()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+mems\+\_\+magf\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) - -\begin{DoxyReturn}{Returns} -Reported raw magnetometer x axis reading from physical magnetometer sensor. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_ad8a215314ae96b25b59fdc363c52261c}\label{class_b_n_o08x_ad8a215314ae96b25b59fdc363c52261c} -\index{BNO08x@{BNO08x}!get\_raw\_mems\_magf\_Y@{get\_raw\_mems\_magf\_Y}} -\index{get\_raw\_mems\_magf\_Y@{get\_raw\_mems\_magf\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_raw\_mems\_magf\_Y()}{get\_raw\_mems\_magf\_Y()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+mems\+\_\+magf\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) - -\begin{DoxyReturn}{Returns} -Reported raw magnetometer y axis reading from physical magnetometer sensor. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_a780651af54485edb36d197f30c071615}\label{class_b_n_o08x_a780651af54485edb36d197f30c071615} -\index{BNO08x@{BNO08x}!get\_raw\_mems\_magf\_Z@{get\_raw\_mems\_magf\_Z}} -\index{get\_raw\_mems\_magf\_Z@{get\_raw\_mems\_magf\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_raw\_mems\_magf\_Z()}{get\_raw\_mems\_magf\_Z()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+mems\+\_\+magf\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) - -\begin{DoxyReturn}{Returns} -Reported raw magnetometer z axis reading from physical magnetometer sensor. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85}\label{class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85} -\index{BNO08x@{BNO08x}!get\_reset\_reason@{get\_reset\_reason}} -\index{get\_reset\_reason@{get\_reset\_reason}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_reset\_reason()}{get\_reset\_reason()}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_ab2a2ace42f7f438d6a799dfcbc243147}{BNO08x\+Reset\+Reason}} BNO08x\+::get\+\_\+reset\+\_\+reason (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Requests product ID, prints the returned info over serial, and returns the reason for the most resent reset. - -\begin{DoxyReturn}{Returns} -The reason for the most recent recent reset ( 1 = POR (power on reset), 2 = internal reset, 3 = watchdog timer, 4 = external reset 5 = other) -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372}\label{class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372} -\index{BNO08x@{BNO08x}!get\_resolution@{get\_resolution}} -\index{get\_resolution@{get\_resolution}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_resolution()}{get\_resolution()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+resolution (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID }\end{DoxyParamCaption})} - - - -Gets resolution from \doxylink{class_b_n_o08x}{BNO08x} FRS (flash record system). - - -\begin{DoxyParams}{Parameters} -{\em record\+\_\+\+ID} & Which record ID/ sensor to get resolution value for.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The resolution value for the requested sensor. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a89618eba08186ee8e679e7313907ddef}\label{class_b_n_o08x_a89618eba08186ee8e679e7313907ddef} -\index{BNO08x@{BNO08x}!get\_roll@{get\_roll}} -\index{get\_roll@{get\_roll}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_roll()}{get\_roll()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+roll (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the reported rotation about x axis. - -\begin{DoxyReturn}{Returns} -Rotation about the x axis in radians. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=318pt]{class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6}\label{class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6} -\index{BNO08x@{BNO08x}!get\_roll\_deg@{get\_roll\_deg}} -\index{get\_roll\_deg@{get\_roll\_deg}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_roll\_deg()}{get\_roll\_deg()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+roll\+\_\+deg (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the reported rotation about x axis. - -\begin{DoxyReturn}{Returns} -Rotation about the x axis in degrees. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a248544b262582d10d917a687190cb454}\label{class_b_n_o08x_a248544b262582d10d917a687190cb454} -\index{BNO08x@{BNO08x}!get\_stability\_classifier@{get\_stability\_classifier}} -\index{get\_stability\_classifier@{get\_stability\_classifier}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_stability\_classifier()}{get\_stability\_classifier()}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}{BNO08x\+Stability}} BNO08x\+::get\+\_\+stability\+\_\+classifier (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the current stability classifier (Seee Ref. Manual 6.\+5.\+31) - -\begin{DoxyReturn}{Returns} -The current stability (0 = unknown, 1 = on table, 2 = stationary) -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef}\label{class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef} -\index{BNO08x@{BNO08x}!get\_step\_count@{get\_step\_count}} -\index{get\_step\_count@{get\_step\_count}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_step\_count()}{get\_step\_count()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::get\+\_\+step\+\_\+count (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the counted amount of steps. - -\begin{DoxyReturn}{Returns} -The current amount of counted steps. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a4797ec731de4c158716da1a7af9d1602}\label{class_b_n_o08x_a4797ec731de4c158716da1a7af9d1602} -\index{BNO08x@{BNO08x}!get\_tap\_detector@{get\_tap\_detector}} -\index{get\_tap\_detector@{get\_tap\_detector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_tap\_detector()}{get\_tap\_detector()}} -{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::get\+\_\+tap\+\_\+detector (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get if tap has occured. - -\begin{DoxyReturn}{Returns} -7 bit tap code indicated which axis taps have occurred. (See Ref. Manual 6.\+5.\+27) -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_ad9137777271421a58159f3fe5e05ed20}\label{class_b_n_o08x_ad9137777271421a58159f3fe5e05ed20} -\index{BNO08x@{BNO08x}!get\_time\_stamp@{get\_time\_stamp}} -\index{get\_time\_stamp@{get\_time\_stamp}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_time\_stamp()}{get\_time\_stamp()}} -{\footnotesize\ttfamily uint32\+\_\+t BNO08x\+::get\+\_\+time\+\_\+stamp (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Return timestamp of most recent report. - -\begin{DoxyReturn}{Returns} -uint32\+\_\+t containing the timestamp of the most recent report in microseconds. -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b}\label{class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b} -\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_bias\_X@{get\_uncalibrated\_gyro\_bias\_X}} -\index{get\_uncalibrated\_gyro\_bias\_X@{get\_uncalibrated\_gyro\_bias\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_uncalibrated\_gyro\_bias\_X()}{get\_uncalibrated\_gyro\_bias\_X()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+bias\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get uncalibrated gyro x axis drift estimate. - -\begin{DoxyReturn}{Returns} -The angular reported x axis drift estimate. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=347pt]{class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a74725517129dd548c7a3de705d5861bd}\label{class_b_n_o08x_a74725517129dd548c7a3de705d5861bd} -\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_bias\_Y@{get\_uncalibrated\_gyro\_bias\_Y}} -\index{get\_uncalibrated\_gyro\_bias\_Y@{get\_uncalibrated\_gyro\_bias\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_uncalibrated\_gyro\_bias\_Y()}{get\_uncalibrated\_gyro\_bias\_Y()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+bias\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get uncalibrated gyro Y axis drift estimate. - -\begin{DoxyReturn}{Returns} -The angular reported Y axis drift estimate. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=347pt]{class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7}\label{class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7} -\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_bias\_Z@{get\_uncalibrated\_gyro\_bias\_Z}} -\index{get\_uncalibrated\_gyro\_bias\_Z@{get\_uncalibrated\_gyro\_bias\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_uncalibrated\_gyro\_bias\_Z()}{get\_uncalibrated\_gyro\_bias\_Z()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+bias\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get uncalibrated gyro Z axis drift estimate. - -\begin{DoxyReturn}{Returns} -The angular reported Z axis drift estimate. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=347pt]{class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104}\label{class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104} -\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_velocity@{get\_uncalibrated\_gyro\_velocity}} -\index{get\_uncalibrated\_gyro\_velocity@{get\_uncalibrated\_gyro\_velocity}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_uncalibrated\_gyro\_velocity()}{get\_uncalibrated\_gyro\_velocity()}} -{\footnotesize\ttfamily void BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+velocity (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z, }\item[{float \&}]{b\+\_\+x, }\item[{float \&}]{b\+\_\+y, }\item[{float \&}]{b\+\_\+z }\end{DoxyParamCaption})} - - - -Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is given but not applied. - - -\begin{DoxyParams}{Parameters} -{\em x} & Reference variable to save X axis angular velocity \\ -\hline -{\em y} & Reference variable to save Y axis angular velocity \\ -\hline -{\em z} & Reference variable to save Z axis angular velocity \\ -\hline -{\em b\+\_\+x} & Reference variable to save X axis drift estimate \\ -\hline -{\em b\+\_\+y} & Reference variable to save Y axis drift estimate \\ -\hline -{\em b\+\_\+z} & Reference variable to save Z axis drift estimate\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=347pt]{class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486}\label{class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486} -\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_velocity\_X@{get\_uncalibrated\_gyro\_velocity\_X}} -\index{get\_uncalibrated\_gyro\_velocity\_X@{get\_uncalibrated\_gyro\_velocity\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_uncalibrated\_gyro\_velocity\_X()}{get\_uncalibrated\_gyro\_velocity\_X()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+velocity\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get uncalibrated gyro x axis angular velocity measurement. - -\begin{DoxyReturn}{Returns} -The angular reported x axis angular velocity from uncalibrated gyro. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=347pt]{class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de}\label{class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de} -\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_velocity\_Y@{get\_uncalibrated\_gyro\_velocity\_Y}} -\index{get\_uncalibrated\_gyro\_velocity\_Y@{get\_uncalibrated\_gyro\_velocity\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_uncalibrated\_gyro\_velocity\_Y()}{get\_uncalibrated\_gyro\_velocity\_Y()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+velocity\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get uncalibrated gyro Y axis angular velocity measurement. - -\begin{DoxyReturn}{Returns} -The angular reported Y axis angular velocity from uncalibrated gyro. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=347pt]{class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592}\label{class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592} -\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_velocity\_Z@{get\_uncalibrated\_gyro\_velocity\_Z}} -\index{get\_uncalibrated\_gyro\_velocity\_Z@{get\_uncalibrated\_gyro\_velocity\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_uncalibrated\_gyro\_velocity\_Z()}{get\_uncalibrated\_gyro\_velocity\_Z()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+velocity\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get uncalibrated gyro Z axis angular velocity measurement. - -\begin{DoxyReturn}{Returns} -The angular reported Z axis angular velocity from uncalibrated gyro. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=347pt]{class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17}\label{class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17} -\index{BNO08x@{BNO08x}!get\_yaw@{get\_yaw}} -\index{get\_yaw@{get\_yaw}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_yaw()}{get\_yaw()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+yaw (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the reported rotation about z axis. - -\begin{DoxyReturn}{Returns} -Rotation about the z axis in radians. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=327pt]{class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_af80f7795656e695e036d3b1557aed94c}\label{class_b_n_o08x_af80f7795656e695e036d3b1557aed94c} -\index{BNO08x@{BNO08x}!get\_yaw\_deg@{get\_yaw\_deg}} -\index{get\_yaw\_deg@{get\_yaw\_deg}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{get\_yaw\_deg()}{get\_yaw\_deg()}} -{\footnotesize\ttfamily float BNO08x\+::get\+\_\+yaw\+\_\+deg (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Get the reported rotation about z axis. - -\begin{DoxyReturn}{Returns} -Rotation about the z axis in degrees. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a28cd1c0b3477571d87133234e6358503}\label{class_b_n_o08x_a28cd1c0b3477571d87133234e6358503} -\index{BNO08x@{BNO08x}!hard\_reset@{hard\_reset}} -\index{hard\_reset@{hard\_reset}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{hard\_reset()}{hard\_reset()}} -{\footnotesize\ttfamily bool BNO08x\+::hard\+\_\+reset (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Hard resets \doxylink{class_b_n_o08x}{BNO08x} sensor. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7}\label{class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7} -\index{BNO08x@{BNO08x}!hint\_handler@{hint\_handler}} -\index{hint\_handler@{hint\_handler}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{hint\_handler()}{hint\_handler()}} -{\footnotesize\ttfamily void IRAM\+\_\+\+ATTR BNO08x\+::hint\+\_\+handler (\begin{DoxyParamCaption}\item[{void \texorpdfstring{$\ast$}{*}}]{arg }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [private]}} - - - -HINT interrupt service routine, handles falling edge of \doxylink{class_b_n_o08x}{BNO08x} HINT pin. - -ISR that launches SPI task to perform transaction upon assertion of \doxylink{class_b_n_o08x}{BNO08x} interrupt pin. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d}\label{class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d} -\index{BNO08x@{BNO08x}!init\_config\_args@{init\_config\_args}} -\index{init\_config\_args@{init\_config\_args}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{init\_config\_args()}{init\_config\_args()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::init\+\_\+config\+\_\+args (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Initializes required esp-\/idf SPI data structures with values from user passed \doxylink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t} struct. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if initialization was success. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10}\label{class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10} -\index{BNO08x@{BNO08x}!init\_gpio@{init\_gpio}} -\index{init\_gpio@{init\_gpio}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{init\_gpio()}{init\_gpio()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::init\+\_\+gpio (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Initializes required gpio. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if initialization was success. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=343pt]{class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4}\label{class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4} -\index{BNO08x@{BNO08x}!init\_gpio\_inputs@{init\_gpio\_inputs}} -\index{init\_gpio\_inputs@{init\_gpio\_inputs}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{init\_gpio\_inputs()}{init\_gpio\_inputs()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::init\+\_\+gpio\+\_\+inputs (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Initializes required gpio inputs. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if initialization was success. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64}\label{class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64} -\index{BNO08x@{BNO08x}!init\_gpio\_outputs@{init\_gpio\_outputs}} -\index{init\_gpio\_outputs@{init\_gpio\_outputs}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{init\_gpio\_outputs()}{init\_gpio\_outputs()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::init\+\_\+gpio\+\_\+outputs (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Initializes required gpio outputs. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if initialization was success. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61}\label{class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61} -\index{BNO08x@{BNO08x}!init\_hint\_isr@{init\_hint\_isr}} -\index{init\_hint\_isr@{init\_hint\_isr}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{init\_hint\_isr()}{init\_hint\_isr()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::init\+\_\+hint\+\_\+isr (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Initializes host interrupt ISR. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if initialization was success. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=336pt]{class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81}\label{class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81} -\index{BNO08x@{BNO08x}!init\_spi@{init\_spi}} -\index{init\_spi@{init\_spi}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{init\_spi()}{init\_spi()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::init\+\_\+spi (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Initializes SPI. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if initialization was success. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798}\label{class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798} -\index{BNO08x@{BNO08x}!initialize@{initialize}} -\index{initialize@{initialize}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{initialize()}{initialize()}} -{\footnotesize\ttfamily bool BNO08x\+::initialize (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Initializes \doxylink{class_b_n_o08x}{BNO08x} sensor. - -Resets sensor and goes through initialization process. Configures GPIO, required ISRs, and launches two tasks, one to manage SPI transactions, another to process any received data. - -\begin{DoxyReturn}{Returns} -True if initialization was success, false if otherwise. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=282pt]{class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0}\label{class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0} -\index{BNO08x@{BNO08x}!kill\_all\_tasks@{kill\_all\_tasks}} -\index{kill\_all\_tasks@{kill\_all\_tasks}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{kill\_all\_tasks()}{kill\_all\_tasks()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::kill\+\_\+all\+\_\+tasks (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Deletes spi\+\_\+task and data\+\_\+proc\+\_\+task safely on deconstructor call. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if tasks successfully deleted. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=333pt]{class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be}\label{class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be} -\index{BNO08x@{BNO08x}!launch\_tasks@{launch\_tasks}} -\index{launch\_tasks@{launch\_tasks}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{launch\_tasks()}{launch\_tasks()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::launch\+\_\+tasks (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Launches spi\+\_\+task and data\+\_\+proc\+\_\+task on constructor call. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if tasks successfully created. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698}\label{class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698} -\index{BNO08x@{BNO08x}!mode\_on@{mode\_on}} -\index{mode\_on@{mode\_on}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{mode\_on()}{mode\_on()}} -{\footnotesize\ttfamily bool BNO08x\+::mode\+\_\+on (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Turns on/ brings \doxylink{class_b_n_o08x}{BNO08x} sensor out of sleep mode using executable channel. - -\begin{DoxyReturn}{Returns} -True if exiting sleep mode was success. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b}\label{class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b} -\index{BNO08x@{BNO08x}!mode\_sleep@{mode\_sleep}} -\index{mode\_sleep@{mode\_sleep}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{mode\_sleep()}{mode\_sleep()}} -{\footnotesize\ttfamily bool BNO08x\+::mode\+\_\+sleep (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Puts \doxylink{class_b_n_o08x}{BNO08x} sensor into sleep/low power mode using executable channel. - -\begin{DoxyReturn}{Returns} -True if entering sleep mode was success. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7}\label{class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7} -\index{BNO08x@{BNO08x}!parse\_command\_report@{parse\_command\_report}} -\index{parse\_command\_report@{parse\_command\_report}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{parse\_command\_report()}{parse\_command\_report()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::parse\+\_\+command\+\_\+report (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Parses received command report sent by \doxylink{class_b_n_o08x}{BNO08x} (See Ref. Manual 6.\+3.\+9) - -\begin{DoxyReturn}{Returns} -The command report ID, 0 if invalid. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981}\label{class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981} -\index{BNO08x@{BNO08x}!parse\_feature\_get\_response\_report@{parse\_feature\_get\_response\_report}} -\index{parse\_feature\_get\_response\_report@{parse\_feature\_get\_response\_report}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{parse\_feature\_get\_response\_report()}{parse\_feature\_get\_response\_report()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::parse\+\_\+feature\+\_\+get\+\_\+response\+\_\+report (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Parses get feature request report received from \doxylink{class_b_n_o08x}{BNO08x}. - -Note there is no means in this library currently to request feature reports, this is simply to handle the unsolicited get feature request reports that come with report rate changes (ie when a report is disabled by setting it 0) such that they aren\textquotesingle{}t detected as invalid packets. - -"{}6.\+5.\+5 of SH-\/2 Ref manual\+: "{}Note that SH-\/2 protocol version 1.\+0.\+1 and higher will send Get Feature Response messages unsolicited if a sensor’s rate changes (e.\+g. due to change in the rate of a related sensor."{} - - -\begin{DoxyParams}{Parameters} -{\em packet} & bno8x\+\_\+rx\+\_\+packet\+\_\+t containing the get feature request report to parse.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The report ID of the respective sensor, for ex. SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+ACCELEROMETER, 0 if invalid. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a51b360d795563b55559f11efb40be36a}\label{class_b_n_o08x_a51b360d795563b55559f11efb40be36a} -\index{BNO08x@{BNO08x}!parse\_frs\_read\_response\_report@{parse\_frs\_read\_response\_report}} -\index{parse\_frs\_read\_response\_report@{parse\_frs\_read\_response\_report}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{parse\_frs\_read\_response\_report()}{parse\_frs\_read\_response\_report()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::parse\+\_\+frs\+\_\+read\+\_\+response\+\_\+report (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Sends packet to be parsed to meta data function call (\doxylink{class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1}{FRS\+\_\+read\+\_\+data()}) through queue. - - -\begin{DoxyParams}{Parameters} -{\em packet} & The packet containing the frs read report.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -1, always valid, parsing for this happens in frs\+\_\+read\+\_\+word() -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d}\label{class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d} -\index{BNO08x@{BNO08x}!parse\_gyro\_integrated\_rotation\_vector\_report@{parse\_gyro\_integrated\_rotation\_vector\_report}} -\index{parse\_gyro\_integrated\_rotation\_vector\_report@{parse\_gyro\_integrated\_rotation\_vector\_report}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{parse\_gyro\_integrated\_rotation\_vector\_report()}{parse\_gyro\_integrated\_rotation\_vector\_report()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::parse\+\_\+gyro\+\_\+integrated\+\_\+rotation\+\_\+vector\+\_\+report (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Parses received gyro integrated rotation vector report sent by \doxylink{class_b_n_o08x}{BNO08x}. - -Unit responds with packet that contains the following\+: - -packet-\/\texorpdfstring{$>$}{>}header\mbox{[}0\+:3\mbox{]}\+: First, a 4 byte header packet-\/\texorpdfstring{$>$}{>}body\mbox{[}0\+:1\mbox{]}\+: Raw quaternion component I packet-\/\texorpdfstring{$>$}{>}body\mbox{[}2\+:3\mbox{]}\+: Raw quaternion component J packet-\/\texorpdfstring{$>$}{>}body\mbox{[}4\+:5\mbox{]}\+: Raw quaternion component K packet-\/\texorpdfstring{$>$}{>}body\mbox{[}6\+:7\mbox{]}\+: Raw quaternion real component packet-\/\texorpdfstring{$>$}{>}body\mbox{[}8\+:9\mbox{]}\+: Raw gyroscope angular velocity in X axis packet-\/\texorpdfstring{$>$}{>}body\mbox{[}10\+:11\mbox{]}\+: Raw gyroscope angular velocity in Y axis packet-\/\texorpdfstring{$>$}{>}body\mbox{[}12\+:13\mbox{]}\+: Raw gyroscope angular velocity in Z axis - - -\begin{DoxyParams}{Parameters} -{\em packet} & bno8x\+\_\+rx\+\_\+packet\+\_\+t containing the gyro integrated rotation vector report report to parse\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Integrated rotation vector report ID (always valid) -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d}\label{class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d} -\index{BNO08x@{BNO08x}!parse\_input\_report@{parse\_input\_report}} -\index{parse\_input\_report@{parse\_input\_report}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{parse\_input\_report()}{parse\_input\_report()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::parse\+\_\+input\+\_\+report (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Parses received input report sent by \doxylink{class_b_n_o08x}{BNO08x}. - -Unit responds with packet that contains the following\+: - -packet-\/\texorpdfstring{$>$}{>}header\mbox{[}0\+:3\mbox{]}\+: First, a 4 byte header packet-\/\texorpdfstring{$>$}{>}body\mbox{[}0\+:4\mbox{]}\+: Then a 5 byte timestamp of microsecond ticks since reading was taken packet-\/\texorpdfstring{$>$}{>}body\mbox{[}5 + 0\mbox{]}\+: Then a feature report ID (0x01 for Accel, 0x05 for Rotation Vector, etc...) packet-\/\texorpdfstring{$>$}{>}body\mbox{[}5 + 1\mbox{]}\+: Sequence number (See Ref.\+Manual 6.\+5.\+8.\+2) packet-\/\texorpdfstring{$>$}{>}body\mbox{[}5 + 2\mbox{]}\+: Status packet-\/\texorpdfstring{$>$}{>}body\mbox{[}3\mbox{]}\+: Delay packet-\/\texorpdfstring{$>$}{>}body\mbox{[}4\+:5\mbox{]}\+: i/accel x/gyro x/etc packet-\/\texorpdfstring{$>$}{>}body\mbox{[}6\+:7\mbox{]}\+: j/accel y/gyro y/etc packet-\/\texorpdfstring{$>$}{>}body\mbox{[}8\+:9\mbox{]}\+: k/accel z/gyro z/etc packet-\/\texorpdfstring{$>$}{>}body\mbox{[}10\+:11\mbox{]}\+: real/gyro temp/etc packet-\/\texorpdfstring{$>$}{>}body\mbox{[}12\+:13\mbox{]}\+: Accuracy estimate - - -\begin{DoxyParams}{Parameters} -{\em packet} & bno8x\+\_\+rx\+\_\+packet\+\_\+t containing the input report to parse\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The report ID of the respective sensor, for ex. SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+ACCELEROMETER, 0 if invalid. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55}\label{class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55} -\index{BNO08x@{BNO08x}!parse\_input\_report\_data@{parse\_input\_report\_data}} -\index{parse\_input\_report\_data@{parse\_input\_report\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{parse\_input\_report\_data()}{parse\_input\_report\_data()}} -{\footnotesize\ttfamily void BNO08x\+::parse\+\_\+input\+\_\+report\+\_\+data (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet, }\item[{uint16\+\_\+t \texorpdfstring{$\ast$}{*}}]{data, }\item[{uint16\+\_\+t}]{data\+\_\+length }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Parses data from received input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & bno8x\+\_\+rx\+\_\+packet\+\_\+t containing the input report to parse \\ -\hline -{\em data} & uint16\+\_\+t array to store parsed data in \\ -\hline -{\em data\+\_\+length} & length of data in bytes parsed from packet header\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924}\label{class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924} -\index{BNO08x@{BNO08x}!parse\_packet@{parse\_packet}} -\index{parse\_packet@{parse\_packet}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{parse\_packet()}{parse\_packet()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::parse\+\_\+packet (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet, }\item[{bool \&}]{notify\+\_\+users }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Parses a packet received from bno08x, updating any data according to received reports. - - -\begin{DoxyParams}{Parameters} -{\em packet} & The packet to be parsed. \\ -\hline -{\em notify\+\_\+users} & Bool reference that is set to true if users should be notified of new data through callbacks/polling, false if packet is valid but users don\textquotesingle{}t need to be notified.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -0 if invalid packet, non-\/zero if otherwise. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036}\label{class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036} -\index{BNO08x@{BNO08x}!parse\_product\_id\_report@{parse\_product\_id\_report}} -\index{parse\_product\_id\_report@{parse\_product\_id\_report}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{parse\_product\_id\_report()}{parse\_product\_id\_report()}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::parse\+\_\+product\+\_\+id\+\_\+report (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Parses product id report and prints device info. - - -\begin{DoxyParams}{Parameters} -{\em packet} & The packet containing product id report.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -1, always valid. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a35856c108a47de8b3b38c4395aabb4eb}\label{class_b_n_o08x_a35856c108a47de8b3b38c4395aabb4eb} -\index{BNO08x@{BNO08x}!print\_header@{print\_header}} -\index{print\_header@{print\_header}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{print\_header()}{print\_header()}} -{\footnotesize\ttfamily void BNO08x\+::print\+\_\+header (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Prints the header of the passed SHTP packet to serial console with ESP\+\_\+\+LOG statement. - - -\begin{DoxyParams}{Parameters} -{\em packet} & The packet containing the header to be printed. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49}\label{class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49} -\index{BNO08x@{BNO08x}!print\_packet@{print\_packet}} -\index{print\_packet@{print\_packet}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{print\_packet()}{print\_packet()}} -{\footnotesize\ttfamily void BNO08x\+::print\+\_\+packet (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Prints the passed SHTP packet to serial console with ESP\+\_\+\+LOG statement. - - -\begin{DoxyParams}{Parameters} -{\em packet} & The packet to be printed. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9}\label{class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9} -\index{BNO08x@{BNO08x}!q\_to\_float@{q\_to\_float}} -\index{q\_to\_float@{q\_to\_float}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{q\_to\_float()}{q\_to\_float()}} -{\footnotesize\ttfamily float BNO08x\+::q\+\_\+to\+\_\+float (\begin{DoxyParamCaption}\item[{int16\+\_\+t}]{fixed\+\_\+point\+\_\+value, }\item[{uint8\+\_\+t}]{q\+\_\+point }\end{DoxyParamCaption})} - - - -Converts a register value to a float using its associated Q point. (See \href{https://en.wikipedia.org/wiki/Q_(number_format)}{\texttt{ https\+://en.\+wikipedia.\+org/wiki/\+Q\+\_\+(number\+\_\+format)}}) - - -\begin{DoxyParams}{Parameters} -{\em q\+\_\+point} & Q point value associated with register. \\ -\hline -{\em fixed\+\_\+point\+\_\+value} & The fixed point value to convert.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91}\label{class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91} -\index{BNO08x@{BNO08x}!queue\_calibrate\_command@{queue\_calibrate\_command}} -\index{queue\_calibrate\_command@{queue\_calibrate\_command}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{queue\_calibrate\_command()}{queue\_calibrate\_command()}} -{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+calibrate\+\_\+command (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{sensor\+\_\+to\+\_\+calibrate }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Queues a packet containing a command to calibrate the specified sensor. - - -\begin{DoxyParams}{Parameters} -{\em sensor\+\_\+to\+\_\+calibrate} & The sensor to calibrate.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9}\label{class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9} -\index{BNO08x@{BNO08x}!queue\_command@{queue\_command}} -\index{queue\_command@{queue\_command}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{queue\_command()}{queue\_command()}} -{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+command (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{command, }\item[{uint8\+\_\+t \texorpdfstring{$\ast$}{*}}]{commands }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Queues a packet containing a command. - - -\begin{DoxyParams}{Parameters} -{\em command} & The command to be sent. \\ -\hline -{\em commands} & Command data array, pre-\/packed with exception of first 3 elements (command info)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3}\label{class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3} -\index{BNO08x@{BNO08x}!queue\_feature\_command@{queue\_feature\_command}} -\index{queue\_feature\_command@{queue\_feature\_command}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{queue\_feature\_command()}{queue\_feature\_command()}} -{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+feature\+\_\+command (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{report\+\_\+\+ID, }\item[{uint32\+\_\+t}]{time\+\_\+between\+\_\+reports, }\item[{uint32\+\_\+t}]{specific\+\_\+config = {\ttfamily 0} }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.\+5.\+4) - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+\+ID} & ID of sensor report to be enabled. \\ -\hline -{\em time\+\_\+between\+\_\+reports} & Desired time between reports in microseconds. \\ -\hline -{\em specific\+\_\+config} & Specific config word (used with personal activity classifier)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f}\label{class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f} -\index{BNO08x@{BNO08x}!queue\_packet@{queue\_packet}} -\index{queue\_packet@{queue\_packet}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{queue\_packet()}{queue\_packet()}} -{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+packet (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{channel\+\_\+number, }\item[{uint8\+\_\+t}]{data\+\_\+length, }\item[{uint8\+\_\+t \texorpdfstring{$\ast$}{*}}]{commands }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Queues an SHTP packet to be sent via SPI. - - -\begin{DoxyParams}{Parameters} -{\em SHTP} & channel number \\ -\hline -{\em data\+\_\+length} & data length in bytes \\ -\hline -{\em commands} & array containing data to be sent\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1}\label{class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1} -\index{BNO08x@{BNO08x}!queue\_request\_product\_id\_command@{queue\_request\_product\_id\_command}} -\index{queue\_request\_product\_id\_command@{queue\_request\_product\_id\_command}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{queue\_request\_product\_id\_command()}{queue\_request\_product\_id\_command()}} -{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+request\+\_\+product\+\_\+id\+\_\+command (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Queues a packet containing the request product ID command. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2}\label{class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2} -\index{BNO08x@{BNO08x}!queue\_tare\_command@{queue\_tare\_command}} -\index{queue\_tare\_command@{queue\_tare\_command}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{queue\_tare\_command()}{queue\_tare\_command()}} -{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+tare\+\_\+command (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{command, }\item[{uint8\+\_\+t}]{axis = {\ttfamily \mbox{\hyperlink{class_b_n_o08x_a1ef13f6f330810934416ad5fe0ee55b2}{TARE\+\_\+\+AXIS\+\_\+\+ALL}}}, }\item[{uint8\+\_\+t}]{rotation\+\_\+vector\+\_\+basis = {\ttfamily \mbox{\hyperlink{class_b_n_o08x_a8e2cfc25d0e34ae53a762b88cc3ac3c8}{TARE\+\_\+\+ROTATION\+\_\+\+VECTOR}}} }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Queues a packet containing a command related to zeroing sensor\textquotesingle{}s axes. (See Ref. Manual 6.\+4.\+4.\+1) - - -\begin{DoxyParams}{Parameters} -{\em command} & Tare command to be sent. \\ -\hline -{\em axis} & Specified axis (can be z or all at once) \\ -\hline -{\em rotation\+\_\+vector\+\_\+basis} & Which rotation vector type to zero axes of, \doxylink{class_b_n_o08x}{BNO08x} saves seperate data for Rotation Vector, Gaming Rotation Vector, etc..)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=324pt]{class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638}\label{class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638} -\index{BNO08x@{BNO08x}!receive\_packet@{receive\_packet}} -\index{receive\_packet@{receive\_packet}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{receive\_packet()}{receive\_packet()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::receive\+\_\+packet (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Receives a SHTP packet via SPI and sends it to \doxylink{class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8}{data\+\_\+proc\+\_\+task()} - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c}\label{class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c} -\index{BNO08x@{BNO08x}!receive\_packet\_body@{receive\_packet\_body}} -\index{receive\_packet\_body@{receive\_packet\_body}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{receive\_packet\_body()}{receive\_packet\_body()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::receive\+\_\+packet\+\_\+body (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Receives a SHTP packet body via SPI. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to \doxylink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t} to save body to.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if receive was success. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_acb246769719351e02bf2aff06d039475}\label{class_b_n_o08x_acb246769719351e02bf2aff06d039475} -\index{BNO08x@{BNO08x}!receive\_packet\_header@{receive\_packet\_header}} -\index{receive\_packet\_header@{receive\_packet\_header}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{receive\_packet\_header()}{receive\_packet\_header()}} -{\footnotesize\ttfamily esp\+\_\+err\+\_\+t BNO08x\+::receive\+\_\+packet\+\_\+header (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Receives a SHTP packet header via SPI. - - -\begin{DoxyParams}{Parameters} -{\em packet} & Pointer to \doxylink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t} to save header to.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if receive was success. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a06bb0c70305421b5357e64f31579fdc7}\label{class_b_n_o08x_a06bb0c70305421b5357e64f31579fdc7} -\index{BNO08x@{BNO08x}!register\_cb@{register\_cb}} -\index{register\_cb@{register\_cb}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{register\_cb()}{register\_cb()}} -{\footnotesize\ttfamily void BNO08x\+::register\+\_\+cb (\begin{DoxyParamCaption}\item[{std\+::function$<$ void()$>$}]{cb\+\_\+fxn }\end{DoxyParamCaption})} - - - -Registers a callback to execute when new data from a report is received. - - -\begin{DoxyParams}{Parameters} -{\em cb\+\_\+fxn} & Pointer to the call-\/back function should be of void return type and void input parameters.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa}\label{class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa} -\index{BNO08x@{BNO08x}!report\_ID\_to\_report\_period\_tracker\_idx@{report\_ID\_to\_report\_period\_tracker\_idx}} -\index{report\_ID\_to\_report\_period\_tracker\_idx@{report\_ID\_to\_report\_period\_tracker\_idx}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{report\_ID\_to\_report\_period\_tracker\_idx()}{report\_ID\_to\_report\_period\_tracker\_idx()}} -{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::report\+\_\+\+ID\+\_\+to\+\_\+report\+\_\+period\+\_\+tracker\+\_\+idx (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{report\+\_\+\+ID }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [private]}} - - - -Converts report id to respective index in report\+\_\+period\+\_\+trackers. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+\+ID} & report ID to return index for. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -Index in report\+\_\+period\+\_\+trackers corresponding to passed report ID. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11}\label{class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11} -\index{BNO08x@{BNO08x}!request\_calibration\_status@{request\_calibration\_status}} -\index{request\_calibration\_status@{request\_calibration\_status}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{request\_calibration\_status()}{request\_calibration\_status()}} -{\footnotesize\ttfamily void BNO08x\+::request\+\_\+calibration\+\_\+status (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Requests ME calibration status from \doxylink{class_b_n_o08x}{BNO08x} (see Ref. Manual 6.\+4.\+7.\+2) - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61}\label{class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61} -\index{BNO08x@{BNO08x}!reset\_all\_data\_to\_defaults@{reset\_all\_data\_to\_defaults}} -\index{reset\_all\_data\_to\_defaults@{reset\_all\_data\_to\_defaults}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{reset\_all\_data\_to\_defaults()}{reset\_all\_data\_to\_defaults()}} -{\footnotesize\ttfamily void BNO08x\+::reset\+\_\+all\+\_\+data\+\_\+to\+\_\+defaults (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Resets all data returned by public getter APIs to initial values of 0 and low accuracy. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a}\label{class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a} -\index{BNO08x@{BNO08x}!run\_full\_calibration\_routine@{run\_full\_calibration\_routine}} -\index{run\_full\_calibration\_routine@{run\_full\_calibration\_routine}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{run\_full\_calibration\_routine()}{run\_full\_calibration\_routine()}} -{\footnotesize\ttfamily bool BNO08x\+::run\+\_\+full\+\_\+calibration\+\_\+routine (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Runs full calibration routine. - -Enables game rotation vector and magnetometer, starts ME calibration process. Waits for accuracy of returned quaternions and magnetic field vectors to be high, then saves calibration data and returns. - -\begin{DoxyReturn}{Returns} -True if calibration succeeded, false if otherwise. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54}\label{class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54} -\index{BNO08x@{BNO08x}!save\_calibration@{save\_calibration}} -\index{save\_calibration@{save\_calibration}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{save\_calibration()}{save\_calibration()}} -{\footnotesize\ttfamily void BNO08x\+::save\+\_\+calibration (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to save internal calibration data (See Ref. Manual 6.\+4.\+7). - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2}\label{class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2} -\index{BNO08x@{BNO08x}!save\_tare@{save\_tare}} -\index{save\_tare@{save\_tare}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{save\_tare()}{save\_tare()}} -{\footnotesize\ttfamily void BNO08x\+::save\+\_\+tare (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Sends command to save tare into non-\/volatile memory of \doxylink{class_b_n_o08x}{BNO08x} (See Ref. Manual 6.\+4.\+4.\+2) - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a}\label{class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a} -\index{BNO08x@{BNO08x}!send\_packet@{send\_packet}} -\index{send\_packet@{send\_packet}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{send\_packet()}{send\_packet()}} -{\footnotesize\ttfamily void BNO08x\+::send\+\_\+packet (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__tx__packet__t}{bno08x\+\_\+tx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Sends a queued SHTP packet via SPI. - - -\begin{DoxyParams}{Parameters} -{\em packet} & The packet queued to be sent.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e}\label{class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e} -\index{BNO08x@{BNO08x}!soft\_reset@{soft\_reset}} -\index{soft\_reset@{soft\_reset}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{soft\_reset()}{soft\_reset()}} -{\footnotesize\ttfamily bool BNO08x\+::soft\+\_\+reset (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} - - - -Soft resets \doxylink{class_b_n_o08x}{BNO08x} sensor using executable channel. - -\begin{DoxyReturn}{Returns} -True if reset was success. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf}\label{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf} -\index{BNO08x@{BNO08x}!spi\_task@{spi\_task}} -\index{spi\_task@{spi\_task}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{spi\_task()}{spi\_task()}} -{\footnotesize\ttfamily void BNO08x\+::spi\+\_\+task (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Task responsible for SPI transactions. Executed when HINT in is asserted by \doxylink{class_b_n_o08x}{BNO08x}. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74}\label{class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74} -\index{BNO08x@{BNO08x}!spi\_task\_trampoline@{spi\_task\_trampoline}} -\index{spi\_task\_trampoline@{spi\_task\_trampoline}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{spi\_task\_trampoline()}{spi\_task\_trampoline()}} -{\footnotesize\ttfamily void BNO08x\+::spi\+\_\+task\+\_\+trampoline (\begin{DoxyParamCaption}\item[{void \texorpdfstring{$\ast$}{*}}]{arg }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [private]}} - - - -Static function used to launch spi task. - -Used such that \doxylink{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf}{spi\+\_\+task()} can be non-\/static class member. - - -\begin{DoxyParams}{Parameters} -{\em arg} & void pointer to \doxylink{class_b_n_o08x}{BNO08x} imu object \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f}\label{class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f} -\index{BNO08x@{BNO08x}!tare\_now@{tare\_now}} -\index{tare\_now@{tare\_now}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{tare\_now()}{tare\_now()}} -{\footnotesize\ttfamily void BNO08x\+::tare\+\_\+now (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{axis\+\_\+sel = {\ttfamily \mbox{\hyperlink{class_b_n_o08x_a1ef13f6f330810934416ad5fe0ee55b2}{TARE\+\_\+\+AXIS\+\_\+\+ALL}}}, }\item[{uint8\+\_\+t}]{rotation\+\_\+vector\+\_\+basis = {\ttfamily \mbox{\hyperlink{class_b_n_o08x_a8e2cfc25d0e34ae53a762b88cc3ac3c8}{TARE\+\_\+\+ROTATION\+\_\+\+VECTOR}}} }\end{DoxyParamCaption})} - - - -Sends command to tare an axis (See Ref. Manual 6.\+4.\+4.\+1) - - -\begin{DoxyParams}{Parameters} -{\em axis\+\_\+sel} & Which axes to zero, can be TARE\+\_\+\+AXIS\+\_\+\+ALL (all axes) or TARE\+\_\+\+AXIS\+\_\+Z (only yaw) \\ -\hline -{\em rotation\+\_\+vector\+\_\+basis} & Which rotation vector type to zero axes can be TARE\+\_\+\+ROTATION\+\_\+\+VECTOR, TARE\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR, TARE\+\_\+\+GEOMAGNETIC\+\_\+\+ROTATION\+\_\+\+VECTOR, etc.. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_afe588fbd0055193d3bc08984d7732354}\label{class_b_n_o08x_afe588fbd0055193d3bc08984d7732354} -\index{BNO08x@{BNO08x}!update\_accelerometer\_data@{update\_accelerometer\_data}} -\index{update\_accelerometer\_data@{update\_accelerometer\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_accelerometer\_data()}{update\_accelerometer\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+accelerometer\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \texorpdfstring{$\ast$}{*}}]{data, }\item[{uint8\+\_\+t}]{status }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates accelerometer data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em data} & uint16\+\_\+t array containing parsed input report data. \\ -\hline -{\em status} & uint8\+\_\+t containing parsed status bits (represents accuracy)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab}\label{class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab} -\index{BNO08x@{BNO08x}!update\_calibrated\_gyro\_data@{update\_calibrated\_gyro\_data}} -\index{update\_calibrated\_gyro\_data@{update\_calibrated\_gyro\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_calibrated\_gyro\_data()}{update\_calibrated\_gyro\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+calibrated\+\_\+gyro\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \texorpdfstring{$\ast$}{*}}]{data, }\item[{uint8\+\_\+t}]{status }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates linear gyro data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em data} & uint16\+\_\+t array containing parsed input report data. \\ -\hline -{\em status} & uint8\+\_\+t containing parsed status bits (represents accuracy)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c}\label{class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c} -\index{BNO08x@{BNO08x}!update\_command\_data@{update\_command\_data}} -\index{update\_command\_data@{update\_command\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_command\_data()}{update\_command\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+command\+\_\+data (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates command data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & \doxylink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t} containing the packet with command response report.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e}\label{class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e} -\index{BNO08x@{BNO08x}!update\_gravity\_data@{update\_gravity\_data}} -\index{update\_gravity\_data@{update\_gravity\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_gravity\_data()}{update\_gravity\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+gravity\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \texorpdfstring{$\ast$}{*}}]{data, }\item[{uint8\+\_\+t}]{status }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates gravity data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em data} & uint16\+\_\+t array containing parsed input report data. \\ -\hline -{\em status} & uint8\+\_\+t containing parsed status bits (represents accuracy)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab}\label{class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab} -\index{BNO08x@{BNO08x}!update\_integrated\_gyro\_rotation\_vector\_data@{update\_integrated\_gyro\_rotation\_vector\_data}} -\index{update\_integrated\_gyro\_rotation\_vector\_data@{update\_integrated\_gyro\_rotation\_vector\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_integrated\_gyro\_rotation\_vector\_data()}{update\_integrated\_gyro\_rotation\_vector\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+integrated\+\_\+gyro\+\_\+rotation\+\_\+vector\+\_\+data (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates integrated gyro rotation vector data from SHTP channel 5 (CHANNEL\+\_\+\+GYRO) special report data. - - -\begin{DoxyParams}{Parameters} -{\em packet} & \doxylink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t} containing the packet with command response report.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708}\label{class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708} -\index{BNO08x@{BNO08x}!update\_lin\_accelerometer\_data@{update\_lin\_accelerometer\_data}} -\index{update\_lin\_accelerometer\_data@{update\_lin\_accelerometer\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_lin\_accelerometer\_data()}{update\_lin\_accelerometer\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+lin\+\_\+accelerometer\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \texorpdfstring{$\ast$}{*}}]{data, }\item[{uint8\+\_\+t}]{status }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates linear accelerometer data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em data} & uint16\+\_\+t array containing parsed input report data. \\ -\hline -{\em status} & uint8\+\_\+t containing parsed status bits (represents accuracy)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88}\label{class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88} -\index{BNO08x@{BNO08x}!update\_magf\_data@{update\_magf\_data}} -\index{update\_magf\_data@{update\_magf\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_magf\_data()}{update\_magf\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+magf\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \texorpdfstring{$\ast$}{*}}]{data, }\item[{uint8\+\_\+t}]{status }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates magnetic field data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em data} & uint16\+\_\+t array containing parsed input report data. \\ -\hline -{\em status} & uint8\+\_\+t containing parsed status bits (represents accuracy)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0}\label{class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0} -\index{BNO08x@{BNO08x}!update\_personal\_activity\_classifier\_data@{update\_personal\_activity\_classifier\_data}} -\index{update\_personal\_activity\_classifier\_data@{update\_personal\_activity\_classifier\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_personal\_activity\_classifier\_data()}{update\_personal\_activity\_classifier\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+personal\+\_\+activity\+\_\+classifier\+\_\+data (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates activity classifier data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & \doxylink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t} containing the packet with activity classifier report.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22}\label{class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22} -\index{BNO08x@{BNO08x}!update\_raw\_accelerometer\_data@{update\_raw\_accelerometer\_data}} -\index{update\_raw\_accelerometer\_data@{update\_raw\_accelerometer\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_raw\_accelerometer\_data()}{update\_raw\_accelerometer\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+raw\+\_\+accelerometer\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \texorpdfstring{$\ast$}{*}}]{data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates raw accelerometer data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em data} & uint16\+\_\+t array containing parsed input report data.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea}\label{class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea} -\index{BNO08x@{BNO08x}!update\_raw\_gyro\_data@{update\_raw\_gyro\_data}} -\index{update\_raw\_gyro\_data@{update\_raw\_gyro\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_raw\_gyro\_data()}{update\_raw\_gyro\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+raw\+\_\+gyro\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \texorpdfstring{$\ast$}{*}}]{data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates raw gyro data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em data} & uint16\+\_\+t array containing parsed input report data.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245}\label{class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245} -\index{BNO08x@{BNO08x}!update\_raw\_magf\_data@{update\_raw\_magf\_data}} -\index{update\_raw\_magf\_data@{update\_raw\_magf\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_raw\_magf\_data()}{update\_raw\_magf\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+raw\+\_\+magf\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \texorpdfstring{$\ast$}{*}}]{data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates raw magnetic field data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em data} & uint16\+\_\+t array containing parsed input report data.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64}\label{class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64} -\index{BNO08x@{BNO08x}!update\_report\_period\_trackers@{update\_report\_period\_trackers}} -\index{update\_report\_period\_trackers@{update\_report\_period\_trackers}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_report\_period\_trackers()}{update\_report\_period\_trackers()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+report\+\_\+period\+\_\+trackers (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{report\+\_\+\+ID, }\item[{uint32\+\_\+t}]{new\+\_\+period }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates period of respective report in report\+\_\+period\+\_\+trackers and recalculates host\+\_\+int\+\_\+timeout\+\_\+ms according to next longest report period. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+\+ID} & report ID to update period of. \\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b}\label{class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b} -\index{BNO08x@{BNO08x}!update\_rotation\_vector\_data@{update\_rotation\_vector\_data}} -\index{update\_rotation\_vector\_data@{update\_rotation\_vector\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_rotation\_vector\_data()}{update\_rotation\_vector\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+rotation\+\_\+vector\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \texorpdfstring{$\ast$}{*}}]{data, }\item[{uint8\+\_\+t}]{status }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates roation vector data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em data} & uint16\+\_\+t array containing parsed input report data. \\ -\hline -{\em status} & uint8\+\_\+t containing parsed status bits (represents accuracy)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a358316b883928c50dd381f024e6b0645}\label{class_b_n_o08x_a358316b883928c50dd381f024e6b0645} -\index{BNO08x@{BNO08x}!update\_stability\_classifier\_data@{update\_stability\_classifier\_data}} -\index{update\_stability\_classifier\_data@{update\_stability\_classifier\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_stability\_classifier\_data()}{update\_stability\_classifier\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+stability\+\_\+classifier\+\_\+data (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates stability classifier data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & \doxylink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t} containing the packet with stability classifier report.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f}\label{class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f} -\index{BNO08x@{BNO08x}!update\_step\_counter\_data@{update\_step\_counter\_data}} -\index{update\_step\_counter\_data@{update\_step\_counter\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_step\_counter\_data()}{update\_step\_counter\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+step\+\_\+counter\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \texorpdfstring{$\ast$}{*}}]{data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates step counter data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em data} & uint16\+\_\+t array containing parsed input report data.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1}\label{class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1} -\index{BNO08x@{BNO08x}!update\_tap\_detector\_data@{update\_tap\_detector\_data}} -\index{update\_tap\_detector\_data@{update\_tap\_detector\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_tap\_detector\_data()}{update\_tap\_detector\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+tap\+\_\+detector\+\_\+data (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{packet }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates tap detector data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em packet} & \doxylink{struct_b_n_o08x_1_1bno08x__rx__packet__t}{bno08x\+\_\+rx\+\_\+packet\+\_\+t} containing the packet with tap detector report.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e}\label{class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e} -\index{BNO08x@{BNO08x}!update\_uncalibrated\_gyro\_data@{update\_uncalibrated\_gyro\_data}} -\index{update\_uncalibrated\_gyro\_data@{update\_uncalibrated\_gyro\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{update\_uncalibrated\_gyro\_data()}{update\_uncalibrated\_gyro\_data()}} -{\footnotesize\ttfamily void BNO08x\+::update\+\_\+uncalibrated\+\_\+gyro\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t \texorpdfstring{$\ast$}{*}}]{data, }\item[{uint8\+\_\+t}]{status }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Updates uncalibrated gyro data from parsed input report. - - -\begin{DoxyParams}{Parameters} -{\em data} & uint16\+\_\+t array containing parsed input report data. \\ -\hline -{\em status} & uint8\+\_\+t containing parsed status bits (represents accuracy)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf}\label{class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf} -\index{BNO08x@{BNO08x}!wait\_for\_data@{wait\_for\_data}} -\index{wait\_for\_data@{wait\_for\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{wait\_for\_data()}{wait\_for\_data()}} -{\footnotesize\ttfamily bool BNO08x\+::wait\+\_\+for\+\_\+data (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Waits for a valid or invalid packet to be received or host\+\_\+int\+\_\+timeout\+\_\+ms to elapse. - -If no reports are currently enabled the hint pin interrupt will be re-\/enabled by this function. - -\begin{DoxyReturn}{Returns} -True if valid packet has been received within host\+\_\+int\+\_\+timeout\+\_\+ms, false if otherwise. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e}\label{class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e} -\index{BNO08x@{BNO08x}!wait\_for\_rx\_done@{wait\_for\_rx\_done}} -\index{wait\_for\_rx\_done@{wait\_for\_rx\_done}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{wait\_for\_rx\_done()}{wait\_for\_rx\_done()}} -{\footnotesize\ttfamily bool BNO08x\+::wait\+\_\+for\+\_\+rx\+\_\+done (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Waits for data to be received over SPI, or host\+\_\+int\+\_\+timeout\+\_\+ms to elapse. - -If no reports are currently enabled the hint pin interrupt will be re-\/enabled by this function. This function is for when the validity of packets is not a concern, it is for flushing packets we do not care about. - -\begin{DoxyReturn}{Returns} -True if data has been received over SPI within host\+\_\+int\+\_\+timeout\+\_\+ms. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773}\label{class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773} -\index{BNO08x@{BNO08x}!wait\_for\_tx\_done@{wait\_for\_tx\_done}} -\index{wait\_for\_tx\_done@{wait\_for\_tx\_done}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{wait\_for\_tx\_done()}{wait\_for\_tx\_done()}} -{\footnotesize\ttfamily bool BNO08x\+::wait\+\_\+for\+\_\+tx\+\_\+done (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} - - - -Waits for a queued packet to be sent or host\+\_\+int\+\_\+timeout\+\_\+ms to elapse. - -If no reports are currently enabled the hint pin interrupt will be re-\/enabled by this function. - -\begin{DoxyReturn}{Returns} -True if packet was sent within host\+\_\+int\+\_\+timeout\+\_\+ms, false if otherwise. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph} -\end{center} -\end{figure} - - -\doxysubsection{Friends And Related Symbol Documentation} -\Hypertarget{class_b_n_o08x_a190775b71c35d8007faae7dd6a9f1030}\label{class_b_n_o08x_a190775b71c35d8007faae7dd6a9f1030} -\index{BNO08x@{BNO08x}!BNO08xTestHelper@{BNO08xTestHelper}} -\index{BNO08xTestHelper@{BNO08xTestHelper}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{BNO08xTestHelper}{BNO08xTestHelper}} -{\footnotesize\ttfamily friend class \mbox{\hyperlink{class_b_n_o08x_test_helper}{BNO08x\+Test\+Helper}}\hspace{0.3cm}{\ttfamily [friend]}} - - - -\doxysubsection{Member Data Documentation} -\Hypertarget{class_b_n_o08x_a3365b7ebde01e284274e655c60343df9}\label{class_b_n_o08x_a3365b7ebde01e284274e655c60343df9} -\index{BNO08x@{BNO08x}!accel\_accuracy@{accel\_accuracy}} -\index{accel\_accuracy@{accel\_accuracy}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{accel\_accuracy}{accel\_accuracy}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::accel\+\_\+accuracy\hspace{0.3cm}{\ttfamily [private]}} - - - -Raw acceleration readings (See SH-\/2 Ref. Manual 6.\+5.\+8) - -\Hypertarget{class_b_n_o08x_a35e1635ef5edde8fc8640f978c6f2e3c}\label{class_b_n_o08x_a35e1635ef5edde8fc8640f978c6f2e3c} -\index{BNO08x@{BNO08x}!accel\_lin\_accuracy@{accel\_lin\_accuracy}} -\index{accel\_lin\_accuracy@{accel\_lin\_accuracy}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{accel\_lin\_accuracy}{accel\_lin\_accuracy}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::accel\+\_\+lin\+\_\+accuracy\hspace{0.3cm}{\ttfamily [private]}} - - - -Raw linear acceleration (See SH-\/2 Ref. Manual 6.\+5.\+10) - -\Hypertarget{class_b_n_o08x_a0564aaf5b20dc42b54db4fb3115ac1c7}\label{class_b_n_o08x_a0564aaf5b20dc42b54db4fb3115ac1c7} -\index{BNO08x@{BNO08x}!ACCELEROMETER\_Q1@{ACCELEROMETER\_Q1}} -\index{ACCELEROMETER\_Q1@{ACCELEROMETER\_Q1}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{ACCELEROMETER\_Q1}{ACCELEROMETER\_Q1}} -{\footnotesize\ttfamily const constexpr int16\+\_\+t BNO08x\+::\+ACCELEROMETER\+\_\+\+Q1 = 8\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Acceleration Q point (See SH-\/2 Ref. Manual 6.\+5.\+9) - -\Hypertarget{class_b_n_o08x_a75cea49c1c08ca28d9fa7e5ed61c6e7b}\label{class_b_n_o08x_a75cea49c1c08ca28d9fa7e5ed61c6e7b} -\index{BNO08x@{BNO08x}!activity\_classifier@{activity\_classifier}} -\index{activity\_classifier@{activity\_classifier}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{activity\_classifier}{activity\_classifier}} -{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::activity\+\_\+classifier\hspace{0.3cm}{\ttfamily [private]}} - - - -BNO08x\+Activity status reading (See SH-\/2 Ref. Manual 6.\+5.\+36) - -\Hypertarget{class_b_n_o08x_af96e8cd070459f945ffbf01b98106e13}\label{class_b_n_o08x_af96e8cd070459f945ffbf01b98106e13} -\index{BNO08x@{BNO08x}!activity\_confidences@{activity\_confidences}} -\index{activity\_confidences@{activity\_confidences}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{activity\_confidences}{activity\_confidences}} -{\footnotesize\ttfamily uint8\+\_\+t\texorpdfstring{$\ast$}{*} BNO08x\+::activity\+\_\+confidences = nullptr\hspace{0.3cm}{\ttfamily [private]}} - - - -Confidence of read activities (See SH-\/2 Ref. Manual 6.\+5.\+36) - -\Hypertarget{class_b_n_o08x_aafe117561fe9138800073a04a778b4ce}\label{class_b_n_o08x_aafe117561fe9138800073a04a778b4ce} -\index{BNO08x@{BNO08x}!ANGULAR\_VELOCITY\_Q1@{ANGULAR\_VELOCITY\_Q1}} -\index{ANGULAR\_VELOCITY\_Q1@{ANGULAR\_VELOCITY\_Q1}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{ANGULAR\_VELOCITY\_Q1}{ANGULAR\_VELOCITY\_Q1}} -{\footnotesize\ttfamily const constexpr int16\+\_\+t BNO08x\+::\+ANGULAR\+\_\+\+VELOCITY\+\_\+\+Q1 = 10\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Angular velocity Q point (See SH-\/2 Ref. Manual 6.\+5.\+44) - -\Hypertarget{class_b_n_o08x_a982f065df42f00e53fd87c840efdb0f1}\label{class_b_n_o08x_a982f065df42f00e53fd87c840efdb0f1} -\index{BNO08x@{BNO08x}!bus\_config@{bus\_config}} -\index{bus\_config@{bus\_config}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{bus\_config}{bus\_config}} -{\footnotesize\ttfamily spi\+\_\+bus\+\_\+config\+\_\+t BNO08x\+::bus\+\_\+config \{\}\hspace{0.3cm}{\ttfamily [private]}} - - - -SPI bus GPIO configuration settings. - -\Hypertarget{class_b_n_o08x_acd5b44d705af1f9aaa271a59a9d2d595}\label{class_b_n_o08x_acd5b44d705af1f9aaa271a59a9d2d595} -\index{BNO08x@{BNO08x}!CALIBRATE\_ACCEL@{CALIBRATE\_ACCEL}} -\index{CALIBRATE\_ACCEL@{CALIBRATE\_ACCEL}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{CALIBRATE\_ACCEL}{CALIBRATE\_ACCEL}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+CALIBRATE\+\_\+\+ACCEL = 0U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Calibrate accelerometer command used by queue\+\_\+calibrate\+\_\+command. - -\Hypertarget{class_b_n_o08x_af53d9e99f163d97ef92fe989b1dd25cc}\label{class_b_n_o08x_af53d9e99f163d97ef92fe989b1dd25cc} -\index{BNO08x@{BNO08x}!CALIBRATE\_ACCEL\_GYRO\_MAG@{CALIBRATE\_ACCEL\_GYRO\_MAG}} -\index{CALIBRATE\_ACCEL\_GYRO\_MAG@{CALIBRATE\_ACCEL\_GYRO\_MAG}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{CALIBRATE\_ACCEL\_GYRO\_MAG}{CALIBRATE\_ACCEL\_GYRO\_MAG}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+CALIBRATE\+\_\+\+ACCEL\+\_\+\+GYRO\+\_\+\+MAG\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 4U} - -\end{DoxyCode} - - -Calibrate accelerometer, gyro, \& magnetometer command used by queue\+\_\+calibrate\+\_\+command. - -\Hypertarget{class_b_n_o08x_aeac84719a1cc0f9c8d5a9a749391d4db}\label{class_b_n_o08x_aeac84719a1cc0f9c8d5a9a749391d4db} -\index{BNO08x@{BNO08x}!CALIBRATE\_GYRO@{CALIBRATE\_GYRO}} -\index{CALIBRATE\_GYRO@{CALIBRATE\_GYRO}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{CALIBRATE\_GYRO}{CALIBRATE\_GYRO}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+CALIBRATE\+\_\+\+GYRO = 1U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Calibrate gyro command used by queue\+\_\+calibrate\+\_\+command. - -\Hypertarget{class_b_n_o08x_ac00e8b59ae8d710cf79956eaafa97ddb}\label{class_b_n_o08x_ac00e8b59ae8d710cf79956eaafa97ddb} -\index{BNO08x@{BNO08x}!CALIBRATE\_MAG@{CALIBRATE\_MAG}} -\index{CALIBRATE\_MAG@{CALIBRATE\_MAG}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{CALIBRATE\_MAG}{CALIBRATE\_MAG}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+CALIBRATE\+\_\+\+MAG = 2U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Calibrate magnetometer command used by queue\+\_\+calibrate\+\_\+command. - -\Hypertarget{class_b_n_o08x_a955dcb60da150490e17367a871b3a3d2}\label{class_b_n_o08x_a955dcb60da150490e17367a871b3a3d2} -\index{BNO08x@{BNO08x}!CALIBRATE\_PLANAR\_ACCEL@{CALIBRATE\_PLANAR\_ACCEL}} -\index{CALIBRATE\_PLANAR\_ACCEL@{CALIBRATE\_PLANAR\_ACCEL}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{CALIBRATE\_PLANAR\_ACCEL}{CALIBRATE\_PLANAR\_ACCEL}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+CALIBRATE\+\_\+\+PLANAR\+\_\+\+ACCEL = 3U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Calibrate planar acceleration command used by queue\+\_\+calibrate\+\_\+command. - -\Hypertarget{class_b_n_o08x_a584bfa04a39feb93279ee673c340db54}\label{class_b_n_o08x_a584bfa04a39feb93279ee673c340db54} -\index{BNO08x@{BNO08x}!CALIBRATE\_STOP@{CALIBRATE\_STOP}} -\index{CALIBRATE\_STOP@{CALIBRATE\_STOP}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{CALIBRATE\_STOP}{CALIBRATE\_STOP}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+CALIBRATE\+\_\+\+STOP = 5U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Stop calibration command used by queue\+\_\+calibrate\+\_\+command. - -\Hypertarget{class_b_n_o08x_ad212b5028a31e857e76d251ced2724e1}\label{class_b_n_o08x_ad212b5028a31e857e76d251ced2724e1} -\index{BNO08x@{BNO08x}!calibration\_status@{calibration\_status}} -\index{calibration\_status@{calibration\_status}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{calibration\_status}{calibration\_status}} -{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::calibration\+\_\+status\hspace{0.3cm}{\ttfamily [private]}} - - - -Calibration status of device (See SH-\/2 Ref. Manual 6.\+4.\+7.\+1 \& 6.\+4.\+7.\+2) - -\Hypertarget{class_b_n_o08x_a6a15e3a64dd71ea61f0448afcce96409}\label{class_b_n_o08x_a6a15e3a64dd71ea61f0448afcce96409} -\index{BNO08x@{BNO08x}!cb\_list@{cb\_list}} -\index{cb\_list@{cb\_list}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{cb\_list}{cb\_list}} -{\footnotesize\ttfamily std\+::vector$<$std\+::function$<$void()$>$ $>$ BNO08x\+::cb\+\_\+list\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a38e31bdb22afdfe05372ffcd5eabfdd2}\label{class_b_n_o08x_a38e31bdb22afdfe05372ffcd5eabfdd2} -\index{BNO08x@{BNO08x}!CMD\_EXECUTION\_DELAY\_MS@{CMD\_EXECUTION\_DELAY\_MS}} -\index{CMD\_EXECUTION\_DELAY\_MS@{CMD\_EXECUTION\_DELAY\_MS}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{CMD\_EXECUTION\_DELAY\_MS}{CMD\_EXECUTION\_DELAY\_MS}} -{\footnotesize\ttfamily const constexpr Tick\+Type\+\_\+t BNO08x\+::\+CMD\+\_\+\+EXECUTION\+\_\+\+DELAY\+\_\+\+MS\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 10UL\ /} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ portTICK\_PERIOD\_MS} - -\end{DoxyCode} - - -How long to delay after queueing command to allow it to execute (for ex. after sending command to enable report). - -\Hypertarget{class_b_n_o08x_a4f580b3cb232a762ea7019ee7b04d419}\label{class_b_n_o08x_a4f580b3cb232a762ea7019ee7b04d419} -\index{BNO08x@{BNO08x}!COMMAND\_CLEAR\_DCD@{COMMAND\_CLEAR\_DCD}} -\index{COMMAND\_CLEAR\_DCD@{COMMAND\_CLEAR\_DCD}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{COMMAND\_CLEAR\_DCD}{COMMAND\_CLEAR\_DCD}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+COMMAND\+\_\+\+CLEAR\+\_\+\+DCD = 11U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Clear DCD \& Reset command (See SH2 Ref. Manual 6.\+4) - -\Hypertarget{class_b_n_o08x_a93dd073c0cc1f3ccfde552649f6ebccc}\label{class_b_n_o08x_a93dd073c0cc1f3ccfde552649f6ebccc} -\index{BNO08x@{BNO08x}!COMMAND\_COUNTER@{COMMAND\_COUNTER}} -\index{COMMAND\_COUNTER@{COMMAND\_COUNTER}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{COMMAND\_COUNTER}{COMMAND\_COUNTER}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+COMMAND\+\_\+\+COUNTER = 2U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_af124a6c1d8b871f3181b6c85f1099cb2}\label{class_b_n_o08x_af124a6c1d8b871f3181b6c85f1099cb2} -\index{BNO08x@{BNO08x}!COMMAND\_DCD@{COMMAND\_DCD}} -\index{COMMAND\_DCD@{COMMAND\_DCD}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{COMMAND\_DCD}{COMMAND\_DCD}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+COMMAND\+\_\+\+DCD = 6U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Save DCD command (See SH2 Ref. Manual 6.\+4.\+7) - -\Hypertarget{class_b_n_o08x_a7a246989c94cd87f68166b20b7ad4c8b}\label{class_b_n_o08x_a7a246989c94cd87f68166b20b7ad4c8b} -\index{BNO08x@{BNO08x}!COMMAND\_DCD\_PERIOD\_SAVE@{COMMAND\_DCD\_PERIOD\_SAVE}} -\index{COMMAND\_DCD\_PERIOD\_SAVE@{COMMAND\_DCD\_PERIOD\_SAVE}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{COMMAND\_DCD\_PERIOD\_SAVE}{COMMAND\_DCD\_PERIOD\_SAVE}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+COMMAND\+\_\+\+DCD\+\_\+\+PERIOD\+\_\+\+SAVE = 9U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Configure DCD periodic saving (See SH2 Ref. Manual 6.\+4) - -\Hypertarget{class_b_n_o08x_a384a1efc9857ad938be3bb44f871539b}\label{class_b_n_o08x_a384a1efc9857ad938be3bb44f871539b} -\index{BNO08x@{BNO08x}!COMMAND\_ERRORS@{COMMAND\_ERRORS}} -\index{COMMAND\_ERRORS@{COMMAND\_ERRORS}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{COMMAND\_ERRORS}{COMMAND\_ERRORS}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+COMMAND\+\_\+\+ERRORS = 1U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a30eb6d305a187d4d36546841e12176b9}\label{class_b_n_o08x_a30eb6d305a187d4d36546841e12176b9} -\index{BNO08x@{BNO08x}!COMMAND\_INITIALIZE@{COMMAND\_INITIALIZE}} -\index{COMMAND\_INITIALIZE@{COMMAND\_INITIALIZE}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{COMMAND\_INITIALIZE}{COMMAND\_INITIALIZE}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+COMMAND\+\_\+\+INITIALIZE = 4U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Reinitialize sensor hub components See (SH2 Ref. Manual 6.\+4.\+5) - -\Hypertarget{class_b_n_o08x_a8381dfe403ddff522f172cb16780731a}\label{class_b_n_o08x_a8381dfe403ddff522f172cb16780731a} -\index{BNO08x@{BNO08x}!COMMAND\_ME\_CALIBRATE@{COMMAND\_ME\_CALIBRATE}} -\index{COMMAND\_ME\_CALIBRATE@{COMMAND\_ME\_CALIBRATE}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{COMMAND\_ME\_CALIBRATE}{COMMAND\_ME\_CALIBRATE}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+COMMAND\+\_\+\+ME\+\_\+\+CALIBRATE = 7U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Command and response to configure ME calibration (See SH2 Ref. Manual 6.\+4.\+7) - -\Hypertarget{class_b_n_o08x_a308c8b5307d93a67b5b9066d44494aa5}\label{class_b_n_o08x_a308c8b5307d93a67b5b9066d44494aa5} -\index{BNO08x@{BNO08x}!COMMAND\_OSCILLATOR@{COMMAND\_OSCILLATOR}} -\index{COMMAND\_OSCILLATOR@{COMMAND\_OSCILLATOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{COMMAND\_OSCILLATOR}{COMMAND\_OSCILLATOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+COMMAND\+\_\+\+OSCILLATOR = 10U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Retrieve oscillator type command (See SH2 Ref. Manual 6.\+4) - -\Hypertarget{class_b_n_o08x_a0a1756bc16ba3eac45f4229b1e350107}\label{class_b_n_o08x_a0a1756bc16ba3eac45f4229b1e350107} -\index{BNO08x@{BNO08x}!COMMAND\_TARE@{COMMAND\_TARE}} -\index{COMMAND\_TARE@{COMMAND\_TARE}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{COMMAND\_TARE}{COMMAND\_TARE}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+COMMAND\+\_\+\+TARE = 3U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Command and response to tare command (See Sh2 Ref. Manual 6.\+4.\+4) - -\Hypertarget{class_b_n_o08x_ae2e8382b5ff8d0ca3375a10b6e273f0c}\label{class_b_n_o08x_ae2e8382b5ff8d0ca3375a10b6e273f0c} -\index{BNO08x@{BNO08x}!current\_slowest\_report\_ID@{current\_slowest\_report\_ID}} -\index{current\_slowest\_report\_ID@{current\_slowest\_report\_ID}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{current\_slowest\_report\_ID}{current\_slowest\_report\_ID}} -{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::current\+\_\+slowest\+\_\+report\+\_\+\+ID\hspace{0.3cm}{\ttfamily [private]}} - - - -ID of the currently enabled report with the largest sample period. - -\Hypertarget{class_b_n_o08x_af9b6fbf35e7cd55d517d30c6429a21a4}\label{class_b_n_o08x_af9b6fbf35e7cd55d517d30c6429a21a4} -\index{BNO08x@{BNO08x}!data\_proc\_task\_hdl@{data\_proc\_task\_hdl}} -\index{data\_proc\_task\_hdl@{data\_proc\_task\_hdl}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{data\_proc\_task\_hdl}{data\_proc\_task\_hdl}} -{\footnotesize\ttfamily Task\+Handle\+\_\+t BNO08x\+::data\+\_\+proc\+\_\+task\+\_\+hdl\hspace{0.3cm}{\ttfamily [private]}} - - - -\doxylink{class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8}{data\+\_\+proc\+\_\+task()} task handle - -\Hypertarget{class_b_n_o08x_a63eb6c8be6f3bc943a86bb0496871275}\label{class_b_n_o08x_a63eb6c8be6f3bc943a86bb0496871275} -\index{BNO08x@{BNO08x}!evt\_grp\_report\_en@{evt\_grp\_report\_en}} -\index{evt\_grp\_report\_en@{evt\_grp\_report\_en}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{evt\_grp\_report\_en}{evt\_grp\_report\_en}} -{\footnotesize\ttfamily Event\+Group\+Handle\+\_\+t BNO08x\+::evt\+\_\+grp\+\_\+report\+\_\+en\hspace{0.3cm}{\ttfamily [private]}} - - - -Event group for indicating which reports are currently enabled. - -\Hypertarget{class_b_n_o08x_a17b19c32d4dfbc9ae2761a0cdd873314}\label{class_b_n_o08x_a17b19c32d4dfbc9ae2761a0cdd873314} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_ACCELEROMETER\_BIT@{EVT\_GRP\_RPT\_ACCELEROMETER\_BIT}} -\index{EVT\_GRP\_RPT\_ACCELEROMETER\_BIT@{EVT\_GRP\_RPT\_ACCELEROMETER\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_ACCELEROMETER\_BIT}{EVT\_GRP\_RPT\_ACCELEROMETER\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+ACCELEROMETER\+\_\+\+BIT = (1U $<$$<$ 5U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, accelerometer reports are active. - -\Hypertarget{class_b_n_o08x_a96eb1b1bfe1266791fd424b3ce402c56}\label{class_b_n_o08x_a96eb1b1bfe1266791fd424b3ce402c56} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_ACTIVITY\_CLASSIFIER\_BIT@{EVT\_GRP\_RPT\_ACTIVITY\_CLASSIFIER\_BIT}} -\index{EVT\_GRP\_RPT\_ACTIVITY\_CLASSIFIER\_BIT@{EVT\_GRP\_RPT\_ACTIVITY\_CLASSIFIER\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_ACTIVITY\_CLASSIFIER\_BIT}{EVT\_GRP\_RPT\_ACTIVITY\_CLASSIFIER\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+ACTIVITY\+\_\+\+CLASSIFIER\+\_\+\+BIT = (1U $<$$<$ 14U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, activity classifier reports are active. - -\Hypertarget{class_b_n_o08x_a89399e8a68a53bc2a269ab73625a2da2}\label{class_b_n_o08x_a89399e8a68a53bc2a269ab73625a2da2} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_ALL\_BITS@{EVT\_GRP\_RPT\_ALL\_BITS}} -\index{EVT\_GRP\_RPT\_ALL\_BITS@{EVT\_GRP\_RPT\_ALL\_BITS}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_ALL\_BITS}{EVT\_GRP\_RPT\_ALL\_BITS}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+ALL\+\_\+\+BITS\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a198da2ee3cd9cfa459c3c41c4f8c44b7}{EVT\_GRP\_RPT\_ROTATION\_VECTOR\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a0f3f33d93b72ba6564f9d5fa93c24f98}{EVT\_GRP\_RPT\_GAME\_ROTATION\_VECTOR\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_aa9703cee46912a545b5e85e671f08e4b}{EVT\_GRP\_RPT\_ARVR\_S\_ROTATION\_VECTOR\_BIT}}\ |} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a79d3fff1e0f19467cad231b22edafa0f}{EVT\_GRP\_RPT\_ARVR\_S\_GAME\_ROTATION\_VECTOR\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a541155dc4544193451cf102e2a992da9}{EVT\_GRP\_RPT\_GYRO\_ROTATION\_VECTOR\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a17b19c32d4dfbc9ae2761a0cdd873314}{EVT\_GRP\_RPT\_ACCELEROMETER\_BIT}}\ |} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ad93161968a53ff53a6bb74ab7c34fbff}{EVT\_GRP\_RPT\_LINEAR\_ACCELEROMETER\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_ab94a8f69673a3db7556ba67775c5ea93}{EVT\_GRP\_RPT\_GRAVITY\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a3a8b12ea9b75f97191785a60d1aa962a}{EVT\_GRP\_RPT\_GYRO\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_af86821bc0f1e7f5897de20b5e47a85bd}{EVT\_GRP\_RPT\_GYRO\_UNCALIBRATED\_BIT}}\ |} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a901af6f2d552f197ee830d0a1c06679c}{EVT\_GRP\_RPT\_MAGNETOMETER\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a665464f781fe891b9179478d0174af47}{EVT\_GRP\_RPT\_TAP\_DETECTOR\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_ab264b65a3aa5a9a74ed11b8977164a73}{EVT\_GRP\_RPT\_STEP\_COUNTER\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a7d6ee23222f55dbe9f70e04b36d9add2}{EVT\_GRP\_RPT\_STABILITY\_CLASSIFIER\_BIT}}\ |} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_a96eb1b1bfe1266791fd424b3ce402c56}{EVT\_GRP\_RPT\_ACTIVITY\_CLASSIFIER\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a3e56d12435f7be81956d68196f1a46b4}{EVT\_GRP\_RPT\_RAW\_ACCELEROMETER\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_a6be7b240e4447c2c643e706954093aa0}{EVT\_GRP\_RPT\_RAW\_GYRO\_BIT}}\ |\ \mbox{\hyperlink{class_b_n_o08x_ac28553b40b82c7cb409938681afe6cec}{EVT\_GRP\_RPT\_RAW\_MAGNETOMETER\_BIT}}} - -\end{DoxyCode} -\Hypertarget{class_b_n_o08x_a79d3fff1e0f19467cad231b22edafa0f}\label{class_b_n_o08x_a79d3fff1e0f19467cad231b22edafa0f} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_ARVR\_S\_GAME\_ROTATION\_VECTOR\_BIT@{EVT\_GRP\_RPT\_ARVR\_S\_GAME\_ROTATION\_VECTOR\_BIT}} -\index{EVT\_GRP\_RPT\_ARVR\_S\_GAME\_ROTATION\_VECTOR\_BIT@{EVT\_GRP\_RPT\_ARVR\_S\_GAME\_ROTATION\_VECTOR\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_ARVR\_S\_GAME\_ROTATION\_VECTOR\_BIT}{EVT\_GRP\_RPT\_ARVR\_S\_GAME\_ROTATION\_VECTOR\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+ARVR\+\_\+\+S\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR\+\_\+\+BIT\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 3U)} - -\end{DoxyCode} - - -When set, ARVR stabilized game rotation vector reports are active. - -\Hypertarget{class_b_n_o08x_aa9703cee46912a545b5e85e671f08e4b}\label{class_b_n_o08x_aa9703cee46912a545b5e85e671f08e4b} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_ARVR\_S\_ROTATION\_VECTOR\_BIT@{EVT\_GRP\_RPT\_ARVR\_S\_ROTATION\_VECTOR\_BIT}} -\index{EVT\_GRP\_RPT\_ARVR\_S\_ROTATION\_VECTOR\_BIT@{EVT\_GRP\_RPT\_ARVR\_S\_ROTATION\_VECTOR\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_ARVR\_S\_ROTATION\_VECTOR\_BIT}{EVT\_GRP\_RPT\_ARVR\_S\_ROTATION\_VECTOR\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+ARVR\+\_\+\+S\+\_\+\+ROTATION\+\_\+\+VECTOR\+\_\+\+BIT\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 2U)} - -\end{DoxyCode} - - -When set, ARVR stabilized rotation vector reports are active. - -\Hypertarget{class_b_n_o08x_a0f3f33d93b72ba6564f9d5fa93c24f98}\label{class_b_n_o08x_a0f3f33d93b72ba6564f9d5fa93c24f98} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_GAME\_ROTATION\_VECTOR\_BIT@{EVT\_GRP\_RPT\_GAME\_ROTATION\_VECTOR\_BIT}} -\index{EVT\_GRP\_RPT\_GAME\_ROTATION\_VECTOR\_BIT@{EVT\_GRP\_RPT\_GAME\_ROTATION\_VECTOR\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_GAME\_ROTATION\_VECTOR\_BIT}{EVT\_GRP\_RPT\_GAME\_ROTATION\_VECTOR\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR\+\_\+\+BIT = (1 $<$$<$ 1)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, game rotation vector reports are active. - -\Hypertarget{class_b_n_o08x_ab94a8f69673a3db7556ba67775c5ea93}\label{class_b_n_o08x_ab94a8f69673a3db7556ba67775c5ea93} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_GRAVITY\_BIT@{EVT\_GRP\_RPT\_GRAVITY\_BIT}} -\index{EVT\_GRP\_RPT\_GRAVITY\_BIT@{EVT\_GRP\_RPT\_GRAVITY\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_GRAVITY\_BIT}{EVT\_GRP\_RPT\_GRAVITY\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+GRAVITY\+\_\+\+BIT = (1U $<$$<$ 7U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, gravity reports are active. - -\Hypertarget{class_b_n_o08x_a3a8b12ea9b75f97191785a60d1aa962a}\label{class_b_n_o08x_a3a8b12ea9b75f97191785a60d1aa962a} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_GYRO\_BIT@{EVT\_GRP\_RPT\_GYRO\_BIT}} -\index{EVT\_GRP\_RPT\_GYRO\_BIT@{EVT\_GRP\_RPT\_GYRO\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_GYRO\_BIT}{EVT\_GRP\_RPT\_GYRO\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+GYRO\+\_\+\+BIT = (1U $<$$<$ 8U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, gyro reports are active. - -\Hypertarget{class_b_n_o08x_a541155dc4544193451cf102e2a992da9}\label{class_b_n_o08x_a541155dc4544193451cf102e2a992da9} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_GYRO\_ROTATION\_VECTOR\_BIT@{EVT\_GRP\_RPT\_GYRO\_ROTATION\_VECTOR\_BIT}} -\index{EVT\_GRP\_RPT\_GYRO\_ROTATION\_VECTOR\_BIT@{EVT\_GRP\_RPT\_GYRO\_ROTATION\_VECTOR\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_GYRO\_ROTATION\_VECTOR\_BIT}{EVT\_GRP\_RPT\_GYRO\_ROTATION\_VECTOR\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+GYRO\+\_\+\+ROTATION\+\_\+\+VECTOR\+\_\+\+BIT\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 4U)} - -\end{DoxyCode} - - -When set, gyro integrator rotation vector reports are active. - -\Hypertarget{class_b_n_o08x_af86821bc0f1e7f5897de20b5e47a85bd}\label{class_b_n_o08x_af86821bc0f1e7f5897de20b5e47a85bd} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_GYRO\_UNCALIBRATED\_BIT@{EVT\_GRP\_RPT\_GYRO\_UNCALIBRATED\_BIT}} -\index{EVT\_GRP\_RPT\_GYRO\_UNCALIBRATED\_BIT@{EVT\_GRP\_RPT\_GYRO\_UNCALIBRATED\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_GYRO\_UNCALIBRATED\_BIT}{EVT\_GRP\_RPT\_GYRO\_UNCALIBRATED\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+GYRO\+\_\+\+UNCALIBRATED\+\_\+\+BIT = (1U $<$$<$ 9U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, uncalibrated gyro reports are active. - -\Hypertarget{class_b_n_o08x_ad93161968a53ff53a6bb74ab7c34fbff}\label{class_b_n_o08x_ad93161968a53ff53a6bb74ab7c34fbff} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_LINEAR\_ACCELEROMETER\_BIT@{EVT\_GRP\_RPT\_LINEAR\_ACCELEROMETER\_BIT}} -\index{EVT\_GRP\_RPT\_LINEAR\_ACCELEROMETER\_BIT@{EVT\_GRP\_RPT\_LINEAR\_ACCELEROMETER\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_LINEAR\_ACCELEROMETER\_BIT}{EVT\_GRP\_RPT\_LINEAR\_ACCELEROMETER\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+LINEAR\+\_\+\+ACCELEROMETER\+\_\+\+BIT = (1U $<$$<$ 6U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, linear accelerometer reports are active. - -\Hypertarget{class_b_n_o08x_a901af6f2d552f197ee830d0a1c06679c}\label{class_b_n_o08x_a901af6f2d552f197ee830d0a1c06679c} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_MAGNETOMETER\_BIT@{EVT\_GRP\_RPT\_MAGNETOMETER\_BIT}} -\index{EVT\_GRP\_RPT\_MAGNETOMETER\_BIT@{EVT\_GRP\_RPT\_MAGNETOMETER\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_MAGNETOMETER\_BIT}{EVT\_GRP\_RPT\_MAGNETOMETER\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+MAGNETOMETER\+\_\+\+BIT = (1U $<$$<$ 10U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, magnetometer reports are active. - -\Hypertarget{class_b_n_o08x_a3e56d12435f7be81956d68196f1a46b4}\label{class_b_n_o08x_a3e56d12435f7be81956d68196f1a46b4} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_RAW\_ACCELEROMETER\_BIT@{EVT\_GRP\_RPT\_RAW\_ACCELEROMETER\_BIT}} -\index{EVT\_GRP\_RPT\_RAW\_ACCELEROMETER\_BIT@{EVT\_GRP\_RPT\_RAW\_ACCELEROMETER\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_RAW\_ACCELEROMETER\_BIT}{EVT\_GRP\_RPT\_RAW\_ACCELEROMETER\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+RAW\+\_\+\+ACCELEROMETER\+\_\+\+BIT = (1U $<$$<$ 15U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, raw accelerometer reports are active. - -\Hypertarget{class_b_n_o08x_a6be7b240e4447c2c643e706954093aa0}\label{class_b_n_o08x_a6be7b240e4447c2c643e706954093aa0} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_RAW\_GYRO\_BIT@{EVT\_GRP\_RPT\_RAW\_GYRO\_BIT}} -\index{EVT\_GRP\_RPT\_RAW\_GYRO\_BIT@{EVT\_GRP\_RPT\_RAW\_GYRO\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_RAW\_GYRO\_BIT}{EVT\_GRP\_RPT\_RAW\_GYRO\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+RAW\+\_\+\+GYRO\+\_\+\+BIT = (1U $<$$<$ 16U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, raw gyro reports are active. - -\Hypertarget{class_b_n_o08x_ac28553b40b82c7cb409938681afe6cec}\label{class_b_n_o08x_ac28553b40b82c7cb409938681afe6cec} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_RAW\_MAGNETOMETER\_BIT@{EVT\_GRP\_RPT\_RAW\_MAGNETOMETER\_BIT}} -\index{EVT\_GRP\_RPT\_RAW\_MAGNETOMETER\_BIT@{EVT\_GRP\_RPT\_RAW\_MAGNETOMETER\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_RAW\_MAGNETOMETER\_BIT}{EVT\_GRP\_RPT\_RAW\_MAGNETOMETER\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+RAW\+\_\+\+MAGNETOMETER\+\_\+\+BIT = (1U $<$$<$ 17U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, raw magnetometer reports are active. - -\Hypertarget{class_b_n_o08x_a198da2ee3cd9cfa459c3c41c4f8c44b7}\label{class_b_n_o08x_a198da2ee3cd9cfa459c3c41c4f8c44b7} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_ROTATION\_VECTOR\_BIT@{EVT\_GRP\_RPT\_ROTATION\_VECTOR\_BIT}} -\index{EVT\_GRP\_RPT\_ROTATION\_VECTOR\_BIT@{EVT\_GRP\_RPT\_ROTATION\_VECTOR\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_ROTATION\_VECTOR\_BIT}{EVT\_GRP\_RPT\_ROTATION\_VECTOR\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+ROTATION\+\_\+\+VECTOR\+\_\+\+BIT = (1 $<$$<$ 0)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, rotation vector reports are active. - -\Hypertarget{class_b_n_o08x_a7d6ee23222f55dbe9f70e04b36d9add2}\label{class_b_n_o08x_a7d6ee23222f55dbe9f70e04b36d9add2} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_STABILITY\_CLASSIFIER\_BIT@{EVT\_GRP\_RPT\_STABILITY\_CLASSIFIER\_BIT}} -\index{EVT\_GRP\_RPT\_STABILITY\_CLASSIFIER\_BIT@{EVT\_GRP\_RPT\_STABILITY\_CLASSIFIER\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_STABILITY\_CLASSIFIER\_BIT}{EVT\_GRP\_RPT\_STABILITY\_CLASSIFIER\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+STABILITY\+\_\+\+CLASSIFIER\+\_\+\+BIT = (1U $<$$<$ 13U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, stability classifier reports are active. - -\Hypertarget{class_b_n_o08x_ab264b65a3aa5a9a74ed11b8977164a73}\label{class_b_n_o08x_ab264b65a3aa5a9a74ed11b8977164a73} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_STEP\_COUNTER\_BIT@{EVT\_GRP\_RPT\_STEP\_COUNTER\_BIT}} -\index{EVT\_GRP\_RPT\_STEP\_COUNTER\_BIT@{EVT\_GRP\_RPT\_STEP\_COUNTER\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_STEP\_COUNTER\_BIT}{EVT\_GRP\_RPT\_STEP\_COUNTER\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+STEP\+\_\+\+COUNTER\+\_\+\+BIT = (1U $<$$<$ 12U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, step counter reports are active. - -\Hypertarget{class_b_n_o08x_a665464f781fe891b9179478d0174af47}\label{class_b_n_o08x_a665464f781fe891b9179478d0174af47} -\index{BNO08x@{BNO08x}!EVT\_GRP\_RPT\_TAP\_DETECTOR\_BIT@{EVT\_GRP\_RPT\_TAP\_DETECTOR\_BIT}} -\index{EVT\_GRP\_RPT\_TAP\_DETECTOR\_BIT@{EVT\_GRP\_RPT\_TAP\_DETECTOR\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_RPT\_TAP\_DETECTOR\_BIT}{EVT\_GRP\_RPT\_TAP\_DETECTOR\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+RPT\+\_\+\+TAP\+\_\+\+DETECTOR\+\_\+\+BIT = (1U $<$$<$ 11U)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When set, tap detector reports are active. - -\Hypertarget{class_b_n_o08x_aa2b4442b5cc63ebf0c495e6fb537c85e}\label{class_b_n_o08x_aa2b4442b5cc63ebf0c495e6fb537c85e} -\index{BNO08x@{BNO08x}!evt\_grp\_spi@{evt\_grp\_spi}} -\index{evt\_grp\_spi@{evt\_grp\_spi}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{evt\_grp\_spi}{evt\_grp\_spi}} -{\footnotesize\ttfamily Event\+Group\+Handle\+\_\+t BNO08x\+::evt\+\_\+grp\+\_\+spi\hspace{0.3cm}{\ttfamily [private]}} - - - -Event group for indicating when bno08x hint pin has triggered and when new data has been processed. Used by calls to sending or receiving functions. - -\Hypertarget{class_b_n_o08x_a32cffd8f78881925d22d5a7cb55f2bbc}\label{class_b_n_o08x_a32cffd8f78881925d22d5a7cb55f2bbc} -\index{BNO08x@{BNO08x}!EVT\_GRP\_SPI\_RX\_DONE\_BIT@{EVT\_GRP\_SPI\_RX\_DONE\_BIT}} -\index{EVT\_GRP\_SPI\_RX\_DONE\_BIT@{EVT\_GRP\_SPI\_RX\_DONE\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_SPI\_RX\_DONE\_BIT}{EVT\_GRP\_SPI\_RX\_DONE\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+SPI\+\_\+\+RX\+\_\+\+DONE\+\_\+\+BIT\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 0U)} - -\end{DoxyCode} - - -When this bit is set it indicates a receive procedure has completed. - -\Hypertarget{class_b_n_o08x_a15e3f92812f8fe70b30966b73a7cb5b2}\label{class_b_n_o08x_a15e3f92812f8fe70b30966b73a7cb5b2} -\index{BNO08x@{BNO08x}!EVT\_GRP\_SPI\_RX\_INVALID\_PACKET\_BIT@{EVT\_GRP\_SPI\_RX\_INVALID\_PACKET\_BIT}} -\index{EVT\_GRP\_SPI\_RX\_INVALID\_PACKET\_BIT@{EVT\_GRP\_SPI\_RX\_INVALID\_PACKET\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_SPI\_RX\_INVALID\_PACKET\_BIT}{EVT\_GRP\_SPI\_RX\_INVALID\_PACKET\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+SPI\+\_\+\+RX\+\_\+\+INVALID\+\_\+\+PACKET\+\_\+\+BIT\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 2U)} - -\end{DoxyCode} - - -When this bit is set, it indicates an invalid packet has been received. - -\Hypertarget{class_b_n_o08x_a96342b0182f339d5a8d6cac1214ce174}\label{class_b_n_o08x_a96342b0182f339d5a8d6cac1214ce174} -\index{BNO08x@{BNO08x}!EVT\_GRP\_SPI\_RX\_VALID\_PACKET\_BIT@{EVT\_GRP\_SPI\_RX\_VALID\_PACKET\_BIT}} -\index{EVT\_GRP\_SPI\_RX\_VALID\_PACKET\_BIT@{EVT\_GRP\_SPI\_RX\_VALID\_PACKET\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_SPI\_RX\_VALID\_PACKET\_BIT}{EVT\_GRP\_SPI\_RX\_VALID\_PACKET\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+SPI\+\_\+\+RX\+\_\+\+VALID\+\_\+\+PACKET\+\_\+\+BIT\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 1U)} - -\end{DoxyCode} - - -When this bit is set, it indicates a valid packet has been received and processed. - -\Hypertarget{class_b_n_o08x_adf2c292674e428c3b65c846cfab4deb7}\label{class_b_n_o08x_adf2c292674e428c3b65c846cfab4deb7} -\index{BNO08x@{BNO08x}!EVT\_GRP\_SPI\_TX\_DONE\_BIT@{EVT\_GRP\_SPI\_TX\_DONE\_BIT}} -\index{EVT\_GRP\_SPI\_TX\_DONE\_BIT@{EVT\_GRP\_SPI\_TX\_DONE\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_SPI\_TX\_DONE\_BIT}{EVT\_GRP\_SPI\_TX\_DONE\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+SPI\+\_\+\+TX\+\_\+\+DONE\+\_\+\+BIT = (1 $<$$<$ 3)\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -When this bit is set, it indicates a queued packet has been sent. - -\Hypertarget{class_b_n_o08x_ac4b1fae7a1155c8b93b645b4eb6eb0f1}\label{class_b_n_o08x_ac4b1fae7a1155c8b93b645b4eb6eb0f1} -\index{BNO08x@{BNO08x}!evt\_grp\_task\_flow@{evt\_grp\_task\_flow}} -\index{evt\_grp\_task\_flow@{evt\_grp\_task\_flow}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{evt\_grp\_task\_flow}{evt\_grp\_task\_flow}} -{\footnotesize\ttfamily Event\+Group\+Handle\+\_\+t BNO08x\+::evt\+\_\+grp\+\_\+task\+\_\+flow\hspace{0.3cm}{\ttfamily [private]}} - - - -Event group for indicating when tasks should complete and self-\/delete (on deconstructor call) - -\Hypertarget{class_b_n_o08x_a5fc8c8969043c5d08fce80eb1d74a761}\label{class_b_n_o08x_a5fc8c8969043c5d08fce80eb1d74a761} -\index{BNO08x@{BNO08x}!EVT\_GRP\_TSK\_FLW\_RUNNING\_BIT@{EVT\_GRP\_TSK\_FLW\_RUNNING\_BIT}} -\index{EVT\_GRP\_TSK\_FLW\_RUNNING\_BIT@{EVT\_GRP\_TSK\_FLW\_RUNNING\_BIT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{EVT\_GRP\_TSK\_FLW\_RUNNING\_BIT}{EVT\_GRP\_TSK\_FLW\_RUNNING\_BIT}} -{\footnotesize\ttfamily const constexpr Event\+Bits\+\_\+t BNO08x\+::\+EVT\+\_\+\+GRP\+\_\+\+TSK\+\_\+\+FLW\+\_\+\+RUNNING\+\_\+\+BIT\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ (1U\ <<\ 0U)} - -\end{DoxyCode} - - -When set, data\+\_\+proc\+\_\+task and spi\+\_\+task are active, when 0 they are pending deletion or deleted. - -\Hypertarget{class_b_n_o08x_ae4670fed6de963a087ab58f95fda319b}\label{class_b_n_o08x_ae4670fed6de963a087ab58f95fda319b} -\index{BNO08x@{BNO08x}!first\_boot@{first\_boot}} -\index{first\_boot@{first\_boot}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{first\_boot}{first\_boot}} -{\footnotesize\ttfamily bool BNO08x\+::first\+\_\+boot = true\hspace{0.3cm}{\ttfamily [private]}} - - - -true only for first execution of \doxylink{class_b_n_o08x_a28cd1c0b3477571d87133234e6358503}{hard\+\_\+reset()}, used to suppress the printing of product ID report. - -\Hypertarget{class_b_n_o08x_ad7ef7d7068af5f92239c12022dbeb16d}\label{class_b_n_o08x_ad7ef7d7068af5f92239c12022dbeb16d} -\index{BNO08x@{BNO08x}!FRS\_RECORD\_ID\_ACCELEROMETER@{FRS\_RECORD\_ID\_ACCELEROMETER}} -\index{FRS\_RECORD\_ID\_ACCELEROMETER@{FRS\_RECORD\_ID\_ACCELEROMETER}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{FRS\_RECORD\_ID\_ACCELEROMETER}{FRS\_RECORD\_ID\_ACCELEROMETER}} -{\footnotesize\ttfamily const constexpr uint16\+\_\+t BNO08x\+::\+FRS\+\_\+\+RECORD\+\_\+\+ID\+\_\+\+ACCELEROMETER\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 0xE302U} - -\end{DoxyCode} - - -Accelerometer record ID, to be passed in metadata functions like \doxylink{class_b_n_o08x_a4421c43323945946ad605f8422958dcf}{get\+\_\+\+Q1()} - -\Hypertarget{class_b_n_o08x_a35d8f641e73c308f92a5a0a772f90f48}\label{class_b_n_o08x_a35d8f641e73c308f92a5a0a772f90f48} -\index{BNO08x@{BNO08x}!FRS\_RECORD\_ID\_GYROSCOPE\_CALIBRATED@{FRS\_RECORD\_ID\_GYROSCOPE\_CALIBRATED}} -\index{FRS\_RECORD\_ID\_GYROSCOPE\_CALIBRATED@{FRS\_RECORD\_ID\_GYROSCOPE\_CALIBRATED}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{FRS\_RECORD\_ID\_GYROSCOPE\_CALIBRATED}{FRS\_RECORD\_ID\_GYROSCOPE\_CALIBRATED}} -{\footnotesize\ttfamily const constexpr uint16\+\_\+t BNO08x\+::\+FRS\+\_\+\+RECORD\+\_\+\+ID\+\_\+\+GYROSCOPE\+\_\+\+CALIBRATED\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 0xE306U} - -\end{DoxyCode} - - -Calirated gyroscope record ID, to be passed in metadata functions like \doxylink{class_b_n_o08x_a4421c43323945946ad605f8422958dcf}{get\+\_\+\+Q1()} - -\Hypertarget{class_b_n_o08x_a0992d77f9bae0b8e3c8d9331fe84fe24}\label{class_b_n_o08x_a0992d77f9bae0b8e3c8d9331fe84fe24} -\index{BNO08x@{BNO08x}!FRS\_RECORD\_ID\_MAGNETIC\_FIELD\_CALIBRATED@{FRS\_RECORD\_ID\_MAGNETIC\_FIELD\_CALIBRATED}} -\index{FRS\_RECORD\_ID\_MAGNETIC\_FIELD\_CALIBRATED@{FRS\_RECORD\_ID\_MAGNETIC\_FIELD\_CALIBRATED}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{FRS\_RECORD\_ID\_MAGNETIC\_FIELD\_CALIBRATED}{FRS\_RECORD\_ID\_MAGNETIC\_FIELD\_CALIBRATED}} -{\footnotesize\ttfamily const constexpr uint16\+\_\+t BNO08x\+::\+FRS\+\_\+\+RECORD\+\_\+\+ID\+\_\+\+MAGNETIC\+\_\+\+FIELD\+\_\+\+CALIBRATED\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 0xE309U} - -\end{DoxyCode} - - -Calibrated magnetometer record ID, to be passed in metadata functions like \doxylink{class_b_n_o08x_a4421c43323945946ad605f8422958dcf}{get\+\_\+\+Q1()} - -\Hypertarget{class_b_n_o08x_a9f35840b19c8ad11fd1b4622c3269250}\label{class_b_n_o08x_a9f35840b19c8ad11fd1b4622c3269250} -\index{BNO08x@{BNO08x}!FRS\_RECORD\_ID\_ROTATION\_VECTOR@{FRS\_RECORD\_ID\_ROTATION\_VECTOR}} -\index{FRS\_RECORD\_ID\_ROTATION\_VECTOR@{FRS\_RECORD\_ID\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{FRS\_RECORD\_ID\_ROTATION\_VECTOR}{FRS\_RECORD\_ID\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint16\+\_\+t BNO08x\+::\+FRS\+\_\+\+RECORD\+\_\+\+ID\+\_\+\+ROTATION\+\_\+\+VECTOR\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 0xE30BU} - -\end{DoxyCode} - - -Rotation vector record ID, to be passed in metadata functions like \doxylink{class_b_n_o08x_a4421c43323945946ad605f8422958dcf}{get\+\_\+\+Q1()} - -\Hypertarget{class_b_n_o08x_ae01698d287ea999179a11e2244902022}\label{class_b_n_o08x_ae01698d287ea999179a11e2244902022} -\index{BNO08x@{BNO08x}!gravity\_accuracy@{gravity\_accuracy}} -\index{gravity\_accuracy@{gravity\_accuracy}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{gravity\_accuracy}{gravity\_accuracy}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::gravity\+\_\+accuracy\hspace{0.3cm}{\ttfamily [private]}} - - - -Gravity reading in m/s\texorpdfstring{$^\wedge$}{\string^}2 (See SH-\/2 Ref. Manual 6.\+5.\+11) - -\Hypertarget{class_b_n_o08x_ae10722334dfce9635e76519598e165a2}\label{class_b_n_o08x_ae10722334dfce9635e76519598e165a2} -\index{BNO08x@{BNO08x}!GRAVITY\_Q1@{GRAVITY\_Q1}} -\index{GRAVITY\_Q1@{GRAVITY\_Q1}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{GRAVITY\_Q1}{GRAVITY\_Q1}} -{\footnotesize\ttfamily const constexpr int16\+\_\+t BNO08x\+::\+GRAVITY\+\_\+\+Q1 = 8\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Gravity Q point (See SH-\/2 Ref. Manual 6.\+5.\+11) - -\Hypertarget{class_b_n_o08x_af45016be9ea523d80be8467b2907b499}\label{class_b_n_o08x_af45016be9ea523d80be8467b2907b499} -\index{BNO08x@{BNO08x}!gravity\_X@{gravity\_X}} -\index{gravity\_X@{gravity\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{gravity\_X}{gravity\_X}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::gravity\+\_\+X\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_af20dcd487a9fe8fa6243817d51e37be5}\label{class_b_n_o08x_af20dcd487a9fe8fa6243817d51e37be5} -\index{BNO08x@{BNO08x}!gravity\_Y@{gravity\_Y}} -\index{gravity\_Y@{gravity\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{gravity\_Y}{gravity\_Y}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::gravity\+\_\+Y\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_afa1cf5c3afbb258d97c55c5fb187f2d6}\label{class_b_n_o08x_afa1cf5c3afbb258d97c55c5fb187f2d6} -\index{BNO08x@{BNO08x}!gravity\_Z@{gravity\_Z}} -\index{gravity\_Z@{gravity\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{gravity\_Z}{gravity\_Z}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::gravity\+\_\+Z\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_aa3bec8effefa61cec6fa170e9d02c4dd}\label{class_b_n_o08x_aa3bec8effefa61cec6fa170e9d02c4dd} -\index{BNO08x@{BNO08x}!GYRO\_Q1@{GYRO\_Q1}} -\index{GYRO\_Q1@{GYRO\_Q1}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{GYRO\_Q1}{GYRO\_Q1}} -{\footnotesize\ttfamily const constexpr int16\+\_\+t BNO08x\+::\+GYRO\+\_\+\+Q1 = 9\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Gyro Q point (See SH-\/2 Ref. Manual 6.\+5.\+13) - -\Hypertarget{class_b_n_o08x_aa07e329d693eb8d9270a7f9ad6f1d94b}\label{class_b_n_o08x_aa07e329d693eb8d9270a7f9ad6f1d94b} -\index{BNO08x@{BNO08x}!HARD\_RESET\_DELAY\_MS@{HARD\_RESET\_DELAY\_MS}} -\index{HARD\_RESET\_DELAY\_MS@{HARD\_RESET\_DELAY\_MS}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{HARD\_RESET\_DELAY\_MS}{HARD\_RESET\_DELAY\_MS}} -{\footnotesize\ttfamily const constexpr Tick\+Type\+\_\+t BNO08x\+::\+HARD\+\_\+\+RESET\+\_\+\+DELAY\+\_\+\+MS\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 100UL\ /} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ portTICK\_PERIOD\_MS} - -\end{DoxyCode} - - -How long RST pin is held low during hard reset (min 10ns according to datasheet, but should be longer for stable operation) - -\Hypertarget{class_b_n_o08x_ae51d4e3228a91ee407d5866e604804c4}\label{class_b_n_o08x_ae51d4e3228a91ee407d5866e604804c4} -\index{BNO08x@{BNO08x}!HOST\_INT\_TIMEOUT\_DEFAULT\_MS@{HOST\_INT\_TIMEOUT\_DEFAULT\_MS}} -\index{HOST\_INT\_TIMEOUT\_DEFAULT\_MS@{HOST\_INT\_TIMEOUT\_DEFAULT\_MS}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{HOST\_INT\_TIMEOUT\_DEFAULT\_MS}{HOST\_INT\_TIMEOUT\_DEFAULT\_MS}} -{\footnotesize\ttfamily const constexpr Tick\+Type\+\_\+t BNO08x\+::\+HOST\+\_\+\+INT\+\_\+\+TIMEOUT\+\_\+\+DEFAULT\+\_\+\+MS\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 3000UL\ /} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ portTICK\_PERIOD\_MS} - -\end{DoxyCode} - - -Max wait between HINT being asserted by \doxylink{class_b_n_o08x}{BNO08x} before transaction is considered failed (in miliseconds), when no reports are enabled (ie during reset) - -\Hypertarget{class_b_n_o08x_ab0c1b4ef4dbcc05a2a6cf37ee039ba0e}\label{class_b_n_o08x_ab0c1b4ef4dbcc05a2a6cf37ee039ba0e} -\index{BNO08x@{BNO08x}!host\_int\_timeout\_ms@{host\_int\_timeout\_ms}} -\index{host\_int\_timeout\_ms@{host\_int\_timeout\_ms}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{host\_int\_timeout\_ms}{host\_int\_timeout\_ms}} -{\footnotesize\ttfamily Tick\+Type\+\_\+t BNO08x\+::host\+\_\+int\+\_\+timeout\+\_\+ms\hspace{0.3cm}{\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \mbox{\hyperlink{class_b_n_o08x_ae51d4e3228a91ee407d5866e604804c4}{HOST\_INT\_TIMEOUT\_DEFAULT\_MS}}} - -\end{DoxyCode} - - -Max wait between HINT being asserted by \doxylink{class_b_n_o08x}{BNO08x} before transaction is considered failed (in miliseconds), determined by enabled report with longest period. - -\Hypertarget{class_b_n_o08x_aeda443e9f608fccfec0e6770edc90c82}\label{class_b_n_o08x_aeda443e9f608fccfec0e6770edc90c82} -\index{BNO08x@{BNO08x}!imu\_config@{imu\_config}} -\index{imu\_config@{imu\_config}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{imu\_config}{imu\_config}} -{\footnotesize\ttfamily \mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}} BNO08x\+::imu\+\_\+config \{\}\hspace{0.3cm}{\ttfamily [private]}} - - - -IMU configuration settings. - -\Hypertarget{class_b_n_o08x_a425a1f5a9f3232aadc685caaf4c2f82e}\label{class_b_n_o08x_a425a1f5a9f3232aadc685caaf4c2f82e} -\index{BNO08x@{BNO08x}!imu\_spi\_config@{imu\_spi\_config}} -\index{imu\_spi\_config@{imu\_spi\_config}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{imu\_spi\_config}{imu\_spi\_config}} -{\footnotesize\ttfamily spi\+\_\+device\+\_\+interface\+\_\+config\+\_\+t BNO08x\+::imu\+\_\+spi\+\_\+config \{\}\hspace{0.3cm}{\ttfamily [private]}} - - - -SPI slave device settings. - -\Hypertarget{class_b_n_o08x_a4520fc3e1dec6389d470945786680013}\label{class_b_n_o08x_a4520fc3e1dec6389d470945786680013} -\index{BNO08x@{BNO08x}!init\_status@{init\_status}} -\index{init\_status@{init\_status}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{init\_status}{init\_status}} -{\footnotesize\ttfamily \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t}{bno08x\+\_\+init\+\_\+status\+\_\+t}} BNO08x\+::init\+\_\+status\hspace{0.3cm}{\ttfamily [private]}} - - - -Initialization status of various functionality, used by deconstructor during cleanup, set during initialization. - -\Hypertarget{class_b_n_o08x_a6537ed69245cf71cad6a6a44480dddaa}\label{class_b_n_o08x_a6537ed69245cf71cad6a6a44480dddaa} -\index{BNO08x@{BNO08x}!integrated\_gyro\_velocity\_X@{integrated\_gyro\_velocity\_X}} -\index{integrated\_gyro\_velocity\_X@{integrated\_gyro\_velocity\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{integrated\_gyro\_velocity\_X}{integrated\_gyro\_velocity\_X}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::integrated\+\_\+gyro\+\_\+velocity\+\_\+X\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a00b39e22ea9fe306e88aaed490ee0a51}\label{class_b_n_o08x_a00b39e22ea9fe306e88aaed490ee0a51} -\index{BNO08x@{BNO08x}!integrated\_gyro\_velocity\_Y@{integrated\_gyro\_velocity\_Y}} -\index{integrated\_gyro\_velocity\_Y@{integrated\_gyro\_velocity\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{integrated\_gyro\_velocity\_Y}{integrated\_gyro\_velocity\_Y}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::integrated\+\_\+gyro\+\_\+velocity\+\_\+Y\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_ad112beb64badd22a2e1d717e1ee921c8}\label{class_b_n_o08x_ad112beb64badd22a2e1d717e1ee921c8} -\index{BNO08x@{BNO08x}!integrated\_gyro\_velocity\_Z@{integrated\_gyro\_velocity\_Z}} -\index{integrated\_gyro\_velocity\_Z@{integrated\_gyro\_velocity\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{integrated\_gyro\_velocity\_Z}{integrated\_gyro\_velocity\_Z}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::integrated\+\_\+gyro\+\_\+velocity\+\_\+Z\hspace{0.3cm}{\ttfamily [private]}} - - - -Raw gyro angular velocity reading from integrated gyro rotation vector (See SH-\/2 Ref. Manual 6.\+5.\+44) - -\Hypertarget{class_b_n_o08x_a7ffc2875b3dff21a827052e4faf273b7}\label{class_b_n_o08x_a7ffc2875b3dff21a827052e4faf273b7} -\index{BNO08x@{BNO08x}!largest\_sample\_period\_us@{largest\_sample\_period\_us}} -\index{largest\_sample\_period\_us@{largest\_sample\_period\_us}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{largest\_sample\_period\_us}{largest\_sample\_period\_us}} -{\footnotesize\ttfamily uint32\+\_\+t BNO08x\+::largest\+\_\+sample\+\_\+period\+\_\+us\hspace{0.3cm}{\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 0} - -\end{DoxyCode} - - -Current largest sample period of any enabled report in microseconds (used to determine timeout for hint ISR). - -\Hypertarget{class_b_n_o08x_ad0d37fe07ced24f2c9afc21145a74e7b}\label{class_b_n_o08x_ad0d37fe07ced24f2c9afc21145a74e7b} -\index{BNO08x@{BNO08x}!LINEAR\_ACCELEROMETER\_Q1@{LINEAR\_ACCELEROMETER\_Q1}} -\index{LINEAR\_ACCELEROMETER\_Q1@{LINEAR\_ACCELEROMETER\_Q1}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{LINEAR\_ACCELEROMETER\_Q1}{LINEAR\_ACCELEROMETER\_Q1}} -{\footnotesize\ttfamily const constexpr int16\+\_\+t BNO08x\+::\+LINEAR\+\_\+\+ACCELEROMETER\+\_\+\+Q1 = 8\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Linear acceleration Q point (See SH-\/2 Ref. Manual 6.\+5.\+10) - -\Hypertarget{class_b_n_o08x_ac5d4e151690774687efa951ca41c16ae}\label{class_b_n_o08x_ac5d4e151690774687efa951ca41c16ae} -\index{BNO08x@{BNO08x}!magf\_accuracy@{magf\_accuracy}} -\index{magf\_accuracy@{magf\_accuracy}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{magf\_accuracy}{magf\_accuracy}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::magf\+\_\+accuracy\hspace{0.3cm}{\ttfamily [private]}} - - - -Calibrated magnetic field reading in u\+Tesla (See SH-\/2 Ref. Manual 6.\+5.\+16) - -\Hypertarget{class_b_n_o08x_a9fac9b811b7c2117675a784cb4df204c}\label{class_b_n_o08x_a9fac9b811b7c2117675a784cb4df204c} -\index{BNO08x@{BNO08x}!MAGNETOMETER\_Q1@{MAGNETOMETER\_Q1}} -\index{MAGNETOMETER\_Q1@{MAGNETOMETER\_Q1}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{MAGNETOMETER\_Q1}{MAGNETOMETER\_Q1}} -{\footnotesize\ttfamily const constexpr int16\+\_\+t BNO08x\+::\+MAGNETOMETER\+\_\+\+Q1 = 4\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Magnetometer Q point (See SH-\/2 Ref. Manual 6.\+5.\+16) - -\Hypertarget{class_b_n_o08x_a2a5b978233eab4c103ab01cfc33a1750}\label{class_b_n_o08x_a2a5b978233eab4c103ab01cfc33a1750} -\index{BNO08x@{BNO08x}!MAX\_METADATA\_LENGTH@{MAX\_METADATA\_LENGTH}} -\index{MAX\_METADATA\_LENGTH@{MAX\_METADATA\_LENGTH}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{MAX\_METADATA\_LENGTH}{MAX\_METADATA\_LENGTH}} -{\footnotesize\ttfamily const constexpr uint16\+\_\+t BNO08x\+::\+MAX\+\_\+\+METADATA\+\_\+\+LENGTH = 9U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -max length of metadata used in frs read operations - -\Hypertarget{class_b_n_o08x_a937cbdc4edaac72c8cad041d79de5701}\label{class_b_n_o08x_a937cbdc4edaac72c8cad041d79de5701} -\index{BNO08x@{BNO08x}!mems\_raw\_accel\_X@{mems\_raw\_accel\_X}} -\index{mems\_raw\_accel\_X@{mems\_raw\_accel\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{mems\_raw\_accel\_X}{mems\_raw\_accel\_X}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::mems\+\_\+raw\+\_\+accel\+\_\+X\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_ad83cecb8a5d2be01db6792755b6057e9}\label{class_b_n_o08x_ad83cecb8a5d2be01db6792755b6057e9} -\index{BNO08x@{BNO08x}!mems\_raw\_accel\_Y@{mems\_raw\_accel\_Y}} -\index{mems\_raw\_accel\_Y@{mems\_raw\_accel\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{mems\_raw\_accel\_Y}{mems\_raw\_accel\_Y}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::mems\+\_\+raw\+\_\+accel\+\_\+Y\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a59a4d75f1302ab693b1b26e9ccaa5341}\label{class_b_n_o08x_a59a4d75f1302ab693b1b26e9ccaa5341} -\index{BNO08x@{BNO08x}!mems\_raw\_accel\_Z@{mems\_raw\_accel\_Z}} -\index{mems\_raw\_accel\_Z@{mems\_raw\_accel\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{mems\_raw\_accel\_Z}{mems\_raw\_accel\_Z}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::mems\+\_\+raw\+\_\+accel\+\_\+Z\hspace{0.3cm}{\ttfamily [private]}} - - - -Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.\+5.\+8) - -\Hypertarget{class_b_n_o08x_a3d6b6257462951ea023af7076c80f6dd}\label{class_b_n_o08x_a3d6b6257462951ea023af7076c80f6dd} -\index{BNO08x@{BNO08x}!mems\_raw\_gyro\_X@{mems\_raw\_gyro\_X}} -\index{mems\_raw\_gyro\_X@{mems\_raw\_gyro\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{mems\_raw\_gyro\_X}{mems\_raw\_gyro\_X}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::mems\+\_\+raw\+\_\+gyro\+\_\+X\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_ab6b142416912a096886dd63ad0beb865}\label{class_b_n_o08x_ab6b142416912a096886dd63ad0beb865} -\index{BNO08x@{BNO08x}!mems\_raw\_gyro\_Y@{mems\_raw\_gyro\_Y}} -\index{mems\_raw\_gyro\_Y@{mems\_raw\_gyro\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{mems\_raw\_gyro\_Y}{mems\_raw\_gyro\_Y}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::mems\+\_\+raw\+\_\+gyro\+\_\+Y\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_ac35d5b12721ab876eaeb1f714a9b3b1d}\label{class_b_n_o08x_ac35d5b12721ab876eaeb1f714a9b3b1d} -\index{BNO08x@{BNO08x}!mems\_raw\_gyro\_Z@{mems\_raw\_gyro\_Z}} -\index{mems\_raw\_gyro\_Z@{mems\_raw\_gyro\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{mems\_raw\_gyro\_Z}{mems\_raw\_gyro\_Z}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::mems\+\_\+raw\+\_\+gyro\+\_\+Z\hspace{0.3cm}{\ttfamily [private]}} - - - -Raw gyro readings from MEMS sensor (See SH-\/2 Ref. Manual 6.\+5.\+12) - -\Hypertarget{class_b_n_o08x_ab587cdf991342b69b7fff3b33f537eb5}\label{class_b_n_o08x_ab587cdf991342b69b7fff3b33f537eb5} -\index{BNO08x@{BNO08x}!mems\_raw\_magf\_X@{mems\_raw\_magf\_X}} -\index{mems\_raw\_magf\_X@{mems\_raw\_magf\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{mems\_raw\_magf\_X}{mems\_raw\_magf\_X}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::mems\+\_\+raw\+\_\+magf\+\_\+X\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_aad926054c81818fff611e10ed913706a}\label{class_b_n_o08x_aad926054c81818fff611e10ed913706a} -\index{BNO08x@{BNO08x}!mems\_raw\_magf\_Y@{mems\_raw\_magf\_Y}} -\index{mems\_raw\_magf\_Y@{mems\_raw\_magf\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{mems\_raw\_magf\_Y}{mems\_raw\_magf\_Y}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::mems\+\_\+raw\+\_\+magf\+\_\+Y\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a90f0cdf11decc276006f76a494d42ce3}\label{class_b_n_o08x_a90f0cdf11decc276006f76a494d42ce3} -\index{BNO08x@{BNO08x}!mems\_raw\_magf\_Z@{mems\_raw\_magf\_Z}} -\index{mems\_raw\_magf\_Z@{mems\_raw\_magf\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{mems\_raw\_magf\_Z}{mems\_raw\_magf\_Z}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::mems\+\_\+raw\+\_\+magf\+\_\+Z\hspace{0.3cm}{\ttfamily [private]}} - - - -Raw magnetometer (compass) readings from MEMS sensor (See SH-\/2 Ref. Manual 6.\+5.\+15) - -\Hypertarget{class_b_n_o08x_a7bd032712a975e73e66bd72a3502baba}\label{class_b_n_o08x_a7bd032712a975e73e66bd72a3502baba} -\index{BNO08x@{BNO08x}!meta\_data@{meta\_data}} -\index{meta\_data@{meta\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{meta\_data}{meta\_data}} -{\footnotesize\ttfamily uint32\+\_\+t BNO08x\+::meta\+\_\+data\mbox{[}9\mbox{]}\hspace{0.3cm}{\ttfamily [private]}} - - - -First 9 bytes of meta data returned from FRS read operation (we don\textquotesingle{}t really need the rest) (See Ref. Manual 5.\+1) - -\Hypertarget{class_b_n_o08x_a36223f7124751fa71e860b2ef55dd2ac}\label{class_b_n_o08x_a36223f7124751fa71e860b2ef55dd2ac} -\index{BNO08x@{BNO08x}!quat\_accuracy@{quat\_accuracy}} -\index{quat\_accuracy@{quat\_accuracy}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{quat\_accuracy}{quat\_accuracy}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::quat\+\_\+accuracy\hspace{0.3cm}{\ttfamily [private]}} - - - -Raw quaternion reading (See SH-\/2 Ref. Manual 6.\+5.\+44) - -\Hypertarget{class_b_n_o08x_a9a1c851e8fa5633e11f6abee293d7e9b}\label{class_b_n_o08x_a9a1c851e8fa5633e11f6abee293d7e9b} -\index{BNO08x@{BNO08x}!queue\_frs\_read\_data@{queue\_frs\_read\_data}} -\index{queue\_frs\_read\_data@{queue\_frs\_read\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{queue\_frs\_read\_data}{queue\_frs\_read\_data}} -{\footnotesize\ttfamily Queue\+Handle\+\_\+t BNO08x\+::queue\+\_\+frs\+\_\+read\+\_\+data\hspace{0.3cm}{\ttfamily [private]}} - - - -Queue used to send packet body from data\+\_\+proc\+\_\+task to frs read functions. - -\Hypertarget{class_b_n_o08x_a84b3639cc159262e0137adb0db5cf9aa}\label{class_b_n_o08x_a84b3639cc159262e0137adb0db5cf9aa} -\index{BNO08x@{BNO08x}!queue\_reset\_reason@{queue\_reset\_reason}} -\index{queue\_reset\_reason@{queue\_reset\_reason}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{queue\_reset\_reason}{queue\_reset\_reason}} -{\footnotesize\ttfamily Queue\+Handle\+\_\+t BNO08x\+::queue\+\_\+reset\+\_\+reason\hspace{0.3cm}{\ttfamily [private]}} - - - -Queue used to send reset reason from product id report to reset\+\_\+reason() function. - -\Hypertarget{class_b_n_o08x_a7d4661d3aae56013caa8f2bff0f67c08}\label{class_b_n_o08x_a7d4661d3aae56013caa8f2bff0f67c08} -\index{BNO08x@{BNO08x}!queue\_rx\_data@{queue\_rx\_data}} -\index{queue\_rx\_data@{queue\_rx\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{queue\_rx\_data}{queue\_rx\_data}} -{\footnotesize\ttfamily Queue\+Handle\+\_\+t BNO08x\+::queue\+\_\+rx\+\_\+data\hspace{0.3cm}{\ttfamily [private]}} - - - -Packet queue used to send data received from bno08x from spi\+\_\+task to data\+\_\+proc\+\_\+task. - -\Hypertarget{class_b_n_o08x_a4d5c5eee87a578de9c8318cd294b3a22}\label{class_b_n_o08x_a4d5c5eee87a578de9c8318cd294b3a22} -\index{BNO08x@{BNO08x}!queue\_tx\_data@{queue\_tx\_data}} -\index{queue\_tx\_data@{queue\_tx\_data}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{queue\_tx\_data}{queue\_tx\_data}} -{\footnotesize\ttfamily Queue\+Handle\+\_\+t BNO08x\+::queue\+\_\+tx\+\_\+data\hspace{0.3cm}{\ttfamily [private]}} - - - -Packet queue used to send data to be sent over SPI from sending functions to spi\+\_\+task. - -\Hypertarget{class_b_n_o08x_a75fb2f06c5bbe26e3f3c794934ef954c}\label{class_b_n_o08x_a75fb2f06c5bbe26e3f3c794934ef954c} -\index{BNO08x@{BNO08x}!raw\_accel\_X@{raw\_accel\_X}} -\index{raw\_accel\_X@{raw\_accel\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_accel\_X}{raw\_accel\_X}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+accel\+\_\+X\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_ab56e2ba505fa293d03e955137625c562}\label{class_b_n_o08x_ab56e2ba505fa293d03e955137625c562} -\index{BNO08x@{BNO08x}!raw\_accel\_Y@{raw\_accel\_Y}} -\index{raw\_accel\_Y@{raw\_accel\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_accel\_Y}{raw\_accel\_Y}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+accel\+\_\+Y\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_af254d245b368027df6952b7d7522bd35}\label{class_b_n_o08x_af254d245b368027df6952b7d7522bd35} -\index{BNO08x@{BNO08x}!raw\_accel\_Z@{raw\_accel\_Z}} -\index{raw\_accel\_Z@{raw\_accel\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_accel\_Z}{raw\_accel\_Z}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+accel\+\_\+Z\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a8a2667f668317cee0a9fc4ef0accc3f5}\label{class_b_n_o08x_a8a2667f668317cee0a9fc4ef0accc3f5} -\index{BNO08x@{BNO08x}!raw\_bias\_X@{raw\_bias\_X}} -\index{raw\_bias\_X@{raw\_bias\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_bias\_X}{raw\_bias\_X}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+bias\+\_\+X\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_ac38ff5eb93d3c3db0af2504ba02fd93c}\label{class_b_n_o08x_ac38ff5eb93d3c3db0af2504ba02fd93c} -\index{BNO08x@{BNO08x}!raw\_bias\_Y@{raw\_bias\_Y}} -\index{raw\_bias\_Y@{raw\_bias\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_bias\_Y}{raw\_bias\_Y}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+bias\+\_\+Y\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a0968eaed9b3d979a2caa1aba6e6b417a}\label{class_b_n_o08x_a0968eaed9b3d979a2caa1aba6e6b417a} -\index{BNO08x@{BNO08x}!raw\_bias\_Z@{raw\_bias\_Z}} -\index{raw\_bias\_Z@{raw\_bias\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_bias\_Z}{raw\_bias\_Z}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+bias\+\_\+Z\hspace{0.3cm}{\ttfamily [private]}} - - - -Uncalibrated gyro reading (See SH-\/2 Ref. Manual 6.\+5.\+14) - -\Hypertarget{class_b_n_o08x_a87faca2c8c71ff46bf2e6ad4ba271b3a}\label{class_b_n_o08x_a87faca2c8c71ff46bf2e6ad4ba271b3a} -\index{BNO08x@{BNO08x}!raw\_calib\_gyro\_X@{raw\_calib\_gyro\_X}} -\index{raw\_calib\_gyro\_X@{raw\_calib\_gyro\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_calib\_gyro\_X}{raw\_calib\_gyro\_X}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+calib\+\_\+gyro\+\_\+X\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a66c48af1d4162a9ec25c3a1c95660fe4}\label{class_b_n_o08x_a66c48af1d4162a9ec25c3a1c95660fe4} -\index{BNO08x@{BNO08x}!raw\_calib\_gyro\_Y@{raw\_calib\_gyro\_Y}} -\index{raw\_calib\_gyro\_Y@{raw\_calib\_gyro\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_calib\_gyro\_Y}{raw\_calib\_gyro\_Y}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+calib\+\_\+gyro\+\_\+Y\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_af5450d1a9c20c2a5c62c960e3df11c0e}\label{class_b_n_o08x_af5450d1a9c20c2a5c62c960e3df11c0e} -\index{BNO08x@{BNO08x}!raw\_calib\_gyro\_Z@{raw\_calib\_gyro\_Z}} -\index{raw\_calib\_gyro\_Z@{raw\_calib\_gyro\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_calib\_gyro\_Z}{raw\_calib\_gyro\_Z}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+calib\+\_\+gyro\+\_\+Z\hspace{0.3cm}{\ttfamily [private]}} - - - -Raw gyro reading (See SH-\/2 Ref. Manual 6.\+5.\+13) - -\Hypertarget{class_b_n_o08x_ae1f71a432cb15e75f522fa18f29f4d50}\label{class_b_n_o08x_ae1f71a432cb15e75f522fa18f29f4d50} -\index{BNO08x@{BNO08x}!raw\_lin\_accel\_X@{raw\_lin\_accel\_X}} -\index{raw\_lin\_accel\_X@{raw\_lin\_accel\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_lin\_accel\_X}{raw\_lin\_accel\_X}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+lin\+\_\+accel\+\_\+X\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_aff3a5590471d1c9fc485a5610433915f}\label{class_b_n_o08x_aff3a5590471d1c9fc485a5610433915f} -\index{BNO08x@{BNO08x}!raw\_lin\_accel\_Y@{raw\_lin\_accel\_Y}} -\index{raw\_lin\_accel\_Y@{raw\_lin\_accel\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_lin\_accel\_Y}{raw\_lin\_accel\_Y}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+lin\+\_\+accel\+\_\+Y\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_abc8add47f1babc66c812a015614143d3}\label{class_b_n_o08x_abc8add47f1babc66c812a015614143d3} -\index{BNO08x@{BNO08x}!raw\_lin\_accel\_Z@{raw\_lin\_accel\_Z}} -\index{raw\_lin\_accel\_Z@{raw\_lin\_accel\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_lin\_accel\_Z}{raw\_lin\_accel\_Z}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+lin\+\_\+accel\+\_\+Z\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_aa5bdf740161b7c37adcac0154a410118}\label{class_b_n_o08x_aa5bdf740161b7c37adcac0154a410118} -\index{BNO08x@{BNO08x}!raw\_magf\_X@{raw\_magf\_X}} -\index{raw\_magf\_X@{raw\_magf\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_magf\_X}{raw\_magf\_X}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+magf\+\_\+X\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_acd365418f24a6da61122c66d82086639}\label{class_b_n_o08x_acd365418f24a6da61122c66d82086639} -\index{BNO08x@{BNO08x}!raw\_magf\_Y@{raw\_magf\_Y}} -\index{raw\_magf\_Y@{raw\_magf\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_magf\_Y}{raw\_magf\_Y}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+magf\+\_\+Y\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_ab4862de31d0874b44b6745678e1c905e}\label{class_b_n_o08x_ab4862de31d0874b44b6745678e1c905e} -\index{BNO08x@{BNO08x}!raw\_magf\_Z@{raw\_magf\_Z}} -\index{raw\_magf\_Z@{raw\_magf\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_magf\_Z}{raw\_magf\_Z}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+magf\+\_\+Z\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a69dc7e97875060213085ba964b3bd987}\label{class_b_n_o08x_a69dc7e97875060213085ba964b3bd987} -\index{BNO08x@{BNO08x}!raw\_quat\_I@{raw\_quat\_I}} -\index{raw\_quat\_I@{raw\_quat\_I}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_quat\_I}{raw\_quat\_I}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+quat\+\_\+I\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a61ae05dc5572b326541bf8099f0c2a54}\label{class_b_n_o08x_a61ae05dc5572b326541bf8099f0c2a54} -\index{BNO08x@{BNO08x}!raw\_quat\_J@{raw\_quat\_J}} -\index{raw\_quat\_J@{raw\_quat\_J}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_quat\_J}{raw\_quat\_J}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+quat\+\_\+J\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a7720c44ed1c0f1a0663d2adc5e1a1ea1}\label{class_b_n_o08x_a7720c44ed1c0f1a0663d2adc5e1a1ea1} -\index{BNO08x@{BNO08x}!raw\_quat\_K@{raw\_quat\_K}} -\index{raw\_quat\_K@{raw\_quat\_K}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_quat\_K}{raw\_quat\_K}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+quat\+\_\+K\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a033d6cb1aa137743b69cc3e401df67b7}\label{class_b_n_o08x_a033d6cb1aa137743b69cc3e401df67b7} -\index{BNO08x@{BNO08x}!raw\_quat\_radian\_accuracy@{raw\_quat\_radian\_accuracy}} -\index{raw\_quat\_radian\_accuracy@{raw\_quat\_radian\_accuracy}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_quat\_radian\_accuracy}{raw\_quat\_radian\_accuracy}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+quat\+\_\+radian\+\_\+accuracy\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a867354267253ae828be4fae15c062db3}\label{class_b_n_o08x_a867354267253ae828be4fae15c062db3} -\index{BNO08x@{BNO08x}!raw\_quat\_real@{raw\_quat\_real}} -\index{raw\_quat\_real@{raw\_quat\_real}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_quat\_real}{raw\_quat\_real}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+quat\+\_\+real\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_afdc5cdb65bd0b36528b5b671b9d27053}\label{class_b_n_o08x_afdc5cdb65bd0b36528b5b671b9d27053} -\index{BNO08x@{BNO08x}!raw\_uncalib\_gyro\_X@{raw\_uncalib\_gyro\_X}} -\index{raw\_uncalib\_gyro\_X@{raw\_uncalib\_gyro\_X}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_uncalib\_gyro\_X}{raw\_uncalib\_gyro\_X}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+uncalib\+\_\+gyro\+\_\+X\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_acc2c66e2985975266a286385ea855117}\label{class_b_n_o08x_acc2c66e2985975266a286385ea855117} -\index{BNO08x@{BNO08x}!raw\_uncalib\_gyro\_Y@{raw\_uncalib\_gyro\_Y}} -\index{raw\_uncalib\_gyro\_Y@{raw\_uncalib\_gyro\_Y}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_uncalib\_gyro\_Y}{raw\_uncalib\_gyro\_Y}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+uncalib\+\_\+gyro\+\_\+Y\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_afac9dd4161f4c0051255293680c9082b}\label{class_b_n_o08x_afac9dd4161f4c0051255293680c9082b} -\index{BNO08x@{BNO08x}!raw\_uncalib\_gyro\_Z@{raw\_uncalib\_gyro\_Z}} -\index{raw\_uncalib\_gyro\_Z@{raw\_uncalib\_gyro\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{raw\_uncalib\_gyro\_Z}{raw\_uncalib\_gyro\_Z}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::raw\+\_\+uncalib\+\_\+gyro\+\_\+Z\hspace{0.3cm}{\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_a9658c821658ab51fe6831a83d8903a53}\label{class_b_n_o08x_a9658c821658ab51fe6831a83d8903a53} -\index{BNO08x@{BNO08x}!REPORT\_CNT@{REPORT\_CNT}} -\index{REPORT\_CNT@{REPORT\_CNT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{REPORT\_CNT}{REPORT\_CNT}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+REPORT\+\_\+\+CNT = 19\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Total unique reports that can be returned by \doxylink{class_b_n_o08x}{BNO08x}. - -\Hypertarget{class_b_n_o08x_ae3750acb4578ccdd7fcf20abcd8e0904}\label{class_b_n_o08x_ae3750acb4578ccdd7fcf20abcd8e0904} -\index{BNO08x@{BNO08x}!report\_period\_trackers@{report\_period\_trackers}} -\index{report\_period\_trackers@{report\_period\_trackers}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{report\_period\_trackers}{report\_period\_trackers}} -{\footnotesize\ttfamily \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__report__period__tracker__t}{bno08x\+\_\+report\+\_\+period\+\_\+tracker\+\_\+t}} BNO08x\+::report\+\_\+period\+\_\+trackers\mbox{[}\mbox{\hyperlink{class_b_n_o08x_a9658c821658ab51fe6831a83d8903a53}{REPORT\+\_\+\+CNT}}\mbox{]}\hspace{0.3cm}{\ttfamily [private]}} - -{\bfseries Initial value\+:} -\begin{DoxyCode}{0} -\DoxyCodeLine{=\ \{\{\mbox{\hyperlink{class_b_n_o08x_a354eaff2218eb382a1851537a75badcc}{SENSOR\_REPORT\_ID\_ACCELEROMETER}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_a224fb8f833806dd530c5f16e7ab5bc7a}{SENSOR\_REPORT\_ID\_GYROSCOPE}},\ 0\},} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_a06058a84d6604054aa66ee008ac64aa9}{SENSOR\_REPORT\_ID\_MAGNETIC\_FIELD}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_ace7720a02c9f4ef38e319849f6c36a0b}{SENSOR\_REPORT\_ID\_LINEAR\_ACCELERATION}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_a37c91f995c385556486df5fbbce8a3d5}{SENSOR\_REPORT\_ID\_ROTATION\_VECTOR}},\ 0\},} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_a6730acb92053d44decb690a7b7234032}{SENSOR\_REPORT\_ID\_GRAVITY}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_acb8e83fbb0645d4e98a96120ce9f431c}{SENSOR\_REPORT\_ID\_UNCALIBRATED\_GYRO}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_ada7dbda9f7a0bfb0894a787ce0ff9cef}{SENSOR\_REPORT\_ID\_GAME\_ROTATION\_VECTOR}},\ 0\},} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_abb6d0586a5a87b7b34f4c65ae52965a4}{SENSOR\_REPORT\_ID\_GEOMAGNETIC\_ROTATION\_VECTOR}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_acd0fc6ffa70dd2761cba0ac0b88c234f}{SENSOR\_REPORT\_ID\_GYRO\_INTEGRATED\_ROTATION\_VECTOR}},\ 0\},} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_a8114460c50e84b0ac750293ab72868c8}{SENSOR\_REPORT\_ID\_TAP\_DETECTOR}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_a2a10161bb564067a07f3fcf4021e00bb}{SENSOR\_REPORT\_ID\_STEP\_COUNTER}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_ab5c29f31714b4755c0edbce7156652f7}{SENSOR\_REPORT\_ID\_STABILITY\_CLASSIFIER}},\ 0\},} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_a80ea70c4787dea6c3eabb48f583f1916}{SENSOR\_REPORT\_ID\_RAW\_ACCELEROMETER}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_a03b3000424e6d966b80655443ec546bc}{SENSOR\_REPORT\_ID\_RAW\_GYROSCOPE}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_a9e9a7578b7584e7eb2ad562b29565fa7}{SENSOR\_REPORT\_ID\_RAW\_MAGNETOMETER}},\ 0\},} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_a7274f6d3bda04da0bb304386b4e8d603}{SENSOR\_REPORT\_ID\_PERSONAL\_ACTIVITY\_CLASSIFIER}},\ 0\},\ \{\mbox{\hyperlink{class_b_n_o08x_a8d4b91149cfc1a3cd615f60a4ad2275e}{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_ROTATION\_VECTOR}},\ 0\},} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \{\mbox{\hyperlink{class_b_n_o08x_aeb51ebb6c82158cd7e23bd682c08c4e0}{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR}},} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ 0\}\}} - -\end{DoxyCode} - - -Current sample period of each report in microseconds linked to report ID (0 if not enabled). - -\Hypertarget{class_b_n_o08x_a923d65d8568cc31873ad56a3908e1939}\label{class_b_n_o08x_a923d65d8568cc31873ad56a3908e1939} -\index{BNO08x@{BNO08x}!ROTATION\_VECTOR\_ACCURACY\_Q1@{ROTATION\_VECTOR\_ACCURACY\_Q1}} -\index{ROTATION\_VECTOR\_ACCURACY\_Q1@{ROTATION\_VECTOR\_ACCURACY\_Q1}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{ROTATION\_VECTOR\_ACCURACY\_Q1}{ROTATION\_VECTOR\_ACCURACY\_Q1}} -{\footnotesize\ttfamily const constexpr int16\+\_\+t BNO08x\+::\+ROTATION\+\_\+\+VECTOR\+\_\+\+ACCURACY\+\_\+\+Q1 = 12\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Rotation vector accuracy estimate Q point (See SH-\/2 Ref. Manual 6.\+5.\+18) - -\Hypertarget{class_b_n_o08x_a0b19c8f2de2b2bfe033da7f93cdd2608}\label{class_b_n_o08x_a0b19c8f2de2b2bfe033da7f93cdd2608} -\index{BNO08x@{BNO08x}!ROTATION\_VECTOR\_Q1@{ROTATION\_VECTOR\_Q1}} -\index{ROTATION\_VECTOR\_Q1@{ROTATION\_VECTOR\_Q1}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{ROTATION\_VECTOR\_Q1}{ROTATION\_VECTOR\_Q1}} -{\footnotesize\ttfamily const constexpr int16\+\_\+t BNO08x\+::\+ROTATION\+\_\+\+VECTOR\+\_\+\+Q1 = 14\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Rotation vector Q point (See SH-\/2 Ref. Manual 6.\+5.\+18) - -\Hypertarget{class_b_n_o08x_a1a037bda37493cde56732cc6fdc7884b}\label{class_b_n_o08x_a1a037bda37493cde56732cc6fdc7884b} -\index{BNO08x@{BNO08x}!RX\_DATA\_LENGTH@{RX\_DATA\_LENGTH}} -\index{RX\_DATA\_LENGTH@{RX\_DATA\_LENGTH}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{RX\_DATA\_LENGTH}{RX\_DATA\_LENGTH}} -{\footnotesize\ttfamily const constexpr uint16\+\_\+t BNO08x\+::\+RX\+\_\+\+DATA\+\_\+\+LENGTH = 300U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -length buffer containing data received over spi - -\Hypertarget{class_b_n_o08x_a031976dacd97917d9d72edccb607160c}\label{class_b_n_o08x_a031976dacd97917d9d72edccb607160c} -\index{BNO08x@{BNO08x}!SCLK\_MAX\_SPEED@{SCLK\_MAX\_SPEED}} -\index{SCLK\_MAX\_SPEED@{SCLK\_MAX\_SPEED}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SCLK\_MAX\_SPEED}{SCLK\_MAX\_SPEED}} -{\footnotesize\ttfamily const constexpr uint32\+\_\+t BNO08x\+::\+SCLK\+\_\+\+MAX\+\_\+\+SPEED = 3000000\+UL\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Max SPI SCLK speed \doxylink{class_b_n_o08x}{BNO08x} is capable of. - -\Hypertarget{class_b_n_o08x_aa92ff86d82a097a565ed2a2b9000b571}\label{class_b_n_o08x_aa92ff86d82a097a565ed2a2b9000b571} -\index{BNO08x@{BNO08x}!sem\_kill\_tasks@{sem\_kill\_tasks}} -\index{sem\_kill\_tasks@{sem\_kill\_tasks}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{sem\_kill\_tasks}{sem\_kill\_tasks}} -{\footnotesize\ttfamily Semaphore\+Handle\+\_\+t BNO08x\+::sem\+\_\+kill\+\_\+tasks\hspace{0.3cm}{\ttfamily [private]}} - - - -semaphore to count amount of killed tasks - -\Hypertarget{class_b_n_o08x_a354eaff2218eb382a1851537a75badcc}\label{class_b_n_o08x_a354eaff2218eb382a1851537a75badcc} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_ACCELEROMETER@{SENSOR\_REPORT\_ID\_ACCELEROMETER}} -\index{SENSOR\_REPORT\_ID\_ACCELEROMETER@{SENSOR\_REPORT\_ID\_ACCELEROMETER}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_ACCELEROMETER}{SENSOR\_REPORT\_ID\_ACCELEROMETER}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+ACCELEROMETER = 0x01U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+9. - -\Hypertarget{class_b_n_o08x_aeb51ebb6c82158cd7e23bd682c08c4e0}\label{class_b_n_o08x_aeb51ebb6c82158cd7e23bd682c08c4e0} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR@{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR}} -\index{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR@{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR}{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+ARVR\+\_\+\+STABILIZED\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR = 0x29U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+43. - -\Hypertarget{class_b_n_o08x_a8d4b91149cfc1a3cd615f60a4ad2275e}\label{class_b_n_o08x_a8d4b91149cfc1a3cd615f60a4ad2275e} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_ROTATION\_VECTOR@{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_ROTATION\_VECTOR}} -\index{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_ROTATION\_VECTOR@{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_ROTATION\_VECTOR}{SENSOR\_REPORT\_ID\_ARVR\_STABILIZED\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+ARVR\+\_\+\+STABILIZED\+\_\+\+ROTATION\+\_\+\+VECTOR = 0x28U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+42. - -\Hypertarget{class_b_n_o08x_ada7dbda9f7a0bfb0894a787ce0ff9cef}\label{class_b_n_o08x_ada7dbda9f7a0bfb0894a787ce0ff9cef} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_GAME\_ROTATION\_VECTOR@{SENSOR\_REPORT\_ID\_GAME\_ROTATION\_VECTOR}} -\index{SENSOR\_REPORT\_ID\_GAME\_ROTATION\_VECTOR@{SENSOR\_REPORT\_ID\_GAME\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_GAME\_ROTATION\_VECTOR}{SENSOR\_REPORT\_ID\_GAME\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR = 0x08U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+19. - -\Hypertarget{class_b_n_o08x_abb6d0586a5a87b7b34f4c65ae52965a4}\label{class_b_n_o08x_abb6d0586a5a87b7b34f4c65ae52965a4} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_GEOMAGNETIC\_ROTATION\_VECTOR@{SENSOR\_REPORT\_ID\_GEOMAGNETIC\_ROTATION\_VECTOR}} -\index{SENSOR\_REPORT\_ID\_GEOMAGNETIC\_ROTATION\_VECTOR@{SENSOR\_REPORT\_ID\_GEOMAGNETIC\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_GEOMAGNETIC\_ROTATION\_VECTOR}{SENSOR\_REPORT\_ID\_GEOMAGNETIC\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+GEOMAGNETIC\+\_\+\+ROTATION\+\_\+\+VECTOR = 0x09U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+20. - -\Hypertarget{class_b_n_o08x_a6730acb92053d44decb690a7b7234032}\label{class_b_n_o08x_a6730acb92053d44decb690a7b7234032} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_GRAVITY@{SENSOR\_REPORT\_ID\_GRAVITY}} -\index{SENSOR\_REPORT\_ID\_GRAVITY@{SENSOR\_REPORT\_ID\_GRAVITY}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_GRAVITY}{SENSOR\_REPORT\_ID\_GRAVITY}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+GRAVITY = 0x06U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+11. - -\Hypertarget{class_b_n_o08x_acd0fc6ffa70dd2761cba0ac0b88c234f}\label{class_b_n_o08x_acd0fc6ffa70dd2761cba0ac0b88c234f} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_GYRO\_INTEGRATED\_ROTATION\_VECTOR@{SENSOR\_REPORT\_ID\_GYRO\_INTEGRATED\_ROTATION\_VECTOR}} -\index{SENSOR\_REPORT\_ID\_GYRO\_INTEGRATED\_ROTATION\_VECTOR@{SENSOR\_REPORT\_ID\_GYRO\_INTEGRATED\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_GYRO\_INTEGRATED\_ROTATION\_VECTOR}{SENSOR\_REPORT\_ID\_GYRO\_INTEGRATED\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+GYRO\+\_\+\+INTEGRATED\+\_\+\+ROTATION\+\_\+\+VECTOR = 0x2\+AU\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+44. - -\Hypertarget{class_b_n_o08x_a224fb8f833806dd530c5f16e7ab5bc7a}\label{class_b_n_o08x_a224fb8f833806dd530c5f16e7ab5bc7a} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_GYROSCOPE@{SENSOR\_REPORT\_ID\_GYROSCOPE}} -\index{SENSOR\_REPORT\_ID\_GYROSCOPE@{SENSOR\_REPORT\_ID\_GYROSCOPE}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_GYROSCOPE}{SENSOR\_REPORT\_ID\_GYROSCOPE}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+GYROSCOPE = 0x02U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+13. - -\Hypertarget{class_b_n_o08x_ace7720a02c9f4ef38e319849f6c36a0b}\label{class_b_n_o08x_ace7720a02c9f4ef38e319849f6c36a0b} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_LINEAR\_ACCELERATION@{SENSOR\_REPORT\_ID\_LINEAR\_ACCELERATION}} -\index{SENSOR\_REPORT\_ID\_LINEAR\_ACCELERATION@{SENSOR\_REPORT\_ID\_LINEAR\_ACCELERATION}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_LINEAR\_ACCELERATION}{SENSOR\_REPORT\_ID\_LINEAR\_ACCELERATION}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+LINEAR\+\_\+\+ACCELERATION = 0x04U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+10. - -\Hypertarget{class_b_n_o08x_a06058a84d6604054aa66ee008ac64aa9}\label{class_b_n_o08x_a06058a84d6604054aa66ee008ac64aa9} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_MAGNETIC\_FIELD@{SENSOR\_REPORT\_ID\_MAGNETIC\_FIELD}} -\index{SENSOR\_REPORT\_ID\_MAGNETIC\_FIELD@{SENSOR\_REPORT\_ID\_MAGNETIC\_FIELD}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_MAGNETIC\_FIELD}{SENSOR\_REPORT\_ID\_MAGNETIC\_FIELD}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+MAGNETIC\+\_\+\+FIELD = 0x03U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+16. - -\Hypertarget{class_b_n_o08x_a7274f6d3bda04da0bb304386b4e8d603}\label{class_b_n_o08x_a7274f6d3bda04da0bb304386b4e8d603} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_PERSONAL\_ACTIVITY\_CLASSIFIER@{SENSOR\_REPORT\_ID\_PERSONAL\_ACTIVITY\_CLASSIFIER}} -\index{SENSOR\_REPORT\_ID\_PERSONAL\_ACTIVITY\_CLASSIFIER@{SENSOR\_REPORT\_ID\_PERSONAL\_ACTIVITY\_CLASSIFIER}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_PERSONAL\_ACTIVITY\_CLASSIFIER}{SENSOR\_REPORT\_ID\_PERSONAL\_ACTIVITY\_CLASSIFIER}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+PERSONAL\+\_\+\+ACTIVITY\+\_\+\+CLASSIFIER = 0x1\+EU\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+36. - -\Hypertarget{class_b_n_o08x_a80ea70c4787dea6c3eabb48f583f1916}\label{class_b_n_o08x_a80ea70c4787dea6c3eabb48f583f1916} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_RAW\_ACCELEROMETER@{SENSOR\_REPORT\_ID\_RAW\_ACCELEROMETER}} -\index{SENSOR\_REPORT\_ID\_RAW\_ACCELEROMETER@{SENSOR\_REPORT\_ID\_RAW\_ACCELEROMETER}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_RAW\_ACCELEROMETER}{SENSOR\_REPORT\_ID\_RAW\_ACCELEROMETER}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+RAW\+\_\+\+ACCELEROMETER = 0x14U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+8. - -\Hypertarget{class_b_n_o08x_a03b3000424e6d966b80655443ec546bc}\label{class_b_n_o08x_a03b3000424e6d966b80655443ec546bc} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_RAW\_GYROSCOPE@{SENSOR\_REPORT\_ID\_RAW\_GYROSCOPE}} -\index{SENSOR\_REPORT\_ID\_RAW\_GYROSCOPE@{SENSOR\_REPORT\_ID\_RAW\_GYROSCOPE}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_RAW\_GYROSCOPE}{SENSOR\_REPORT\_ID\_RAW\_GYROSCOPE}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+RAW\+\_\+\+GYROSCOPE = 0x15U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+12. - -\Hypertarget{class_b_n_o08x_a9e9a7578b7584e7eb2ad562b29565fa7}\label{class_b_n_o08x_a9e9a7578b7584e7eb2ad562b29565fa7} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_RAW\_MAGNETOMETER@{SENSOR\_REPORT\_ID\_RAW\_MAGNETOMETER}} -\index{SENSOR\_REPORT\_ID\_RAW\_MAGNETOMETER@{SENSOR\_REPORT\_ID\_RAW\_MAGNETOMETER}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_RAW\_MAGNETOMETER}{SENSOR\_REPORT\_ID\_RAW\_MAGNETOMETER}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+RAW\+\_\+\+MAGNETOMETER = 0x16U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+15. - -\Hypertarget{class_b_n_o08x_a37c91f995c385556486df5fbbce8a3d5}\label{class_b_n_o08x_a37c91f995c385556486df5fbbce8a3d5} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_ROTATION\_VECTOR@{SENSOR\_REPORT\_ID\_ROTATION\_VECTOR}} -\index{SENSOR\_REPORT\_ID\_ROTATION\_VECTOR@{SENSOR\_REPORT\_ID\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_ROTATION\_VECTOR}{SENSOR\_REPORT\_ID\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+ROTATION\+\_\+\+VECTOR = 0x05U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+18. - -\Hypertarget{class_b_n_o08x_ab5c29f31714b4755c0edbce7156652f7}\label{class_b_n_o08x_ab5c29f31714b4755c0edbce7156652f7} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_STABILITY\_CLASSIFIER@{SENSOR\_REPORT\_ID\_STABILITY\_CLASSIFIER}} -\index{SENSOR\_REPORT\_ID\_STABILITY\_CLASSIFIER@{SENSOR\_REPORT\_ID\_STABILITY\_CLASSIFIER}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_STABILITY\_CLASSIFIER}{SENSOR\_REPORT\_ID\_STABILITY\_CLASSIFIER}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+STABILITY\+\_\+\+CLASSIFIER = 0x13U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+31. - -\Hypertarget{class_b_n_o08x_a2a10161bb564067a07f3fcf4021e00bb}\label{class_b_n_o08x_a2a10161bb564067a07f3fcf4021e00bb} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_STEP\_COUNTER@{SENSOR\_REPORT\_ID\_STEP\_COUNTER}} -\index{SENSOR\_REPORT\_ID\_STEP\_COUNTER@{SENSOR\_REPORT\_ID\_STEP\_COUNTER}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_STEP\_COUNTER}{SENSOR\_REPORT\_ID\_STEP\_COUNTER}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+STEP\+\_\+\+COUNTER = 0x11U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+29. - -\Hypertarget{class_b_n_o08x_a8114460c50e84b0ac750293ab72868c8}\label{class_b_n_o08x_a8114460c50e84b0ac750293ab72868c8} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_TAP\_DETECTOR@{SENSOR\_REPORT\_ID\_TAP\_DETECTOR}} -\index{SENSOR\_REPORT\_ID\_TAP\_DETECTOR@{SENSOR\_REPORT\_ID\_TAP\_DETECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_TAP\_DETECTOR}{SENSOR\_REPORT\_ID\_TAP\_DETECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+TAP\+\_\+\+DETECTOR = 0x10U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+27. - -\Hypertarget{class_b_n_o08x_acb8e83fbb0645d4e98a96120ce9f431c}\label{class_b_n_o08x_acb8e83fbb0645d4e98a96120ce9f431c} -\index{BNO08x@{BNO08x}!SENSOR\_REPORT\_ID\_UNCALIBRATED\_GYRO@{SENSOR\_REPORT\_ID\_UNCALIBRATED\_GYRO}} -\index{SENSOR\_REPORT\_ID\_UNCALIBRATED\_GYRO@{SENSOR\_REPORT\_ID\_UNCALIBRATED\_GYRO}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SENSOR\_REPORT\_ID\_UNCALIBRATED\_GYRO}{SENSOR\_REPORT\_ID\_UNCALIBRATED\_GYRO}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SENSOR\+\_\+\+REPORT\+\_\+\+ID\+\_\+\+UNCALIBRATED\+\_\+\+GYRO = 0x07U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+14. - -\Hypertarget{class_b_n_o08x_ae37d6f8431c8c465bfb0c662772b5cb9}\label{class_b_n_o08x_ae37d6f8431c8c465bfb0c662772b5cb9} -\index{BNO08x@{BNO08x}!SHTP\_REPORT\_BASE\_TIMESTAMP@{SHTP\_REPORT\_BASE\_TIMESTAMP}} -\index{SHTP\_REPORT\_BASE\_TIMESTAMP@{SHTP\_REPORT\_BASE\_TIMESTAMP}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SHTP\_REPORT\_BASE\_TIMESTAMP}{SHTP\_REPORT\_BASE\_TIMESTAMP}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SHTP\+\_\+\+REPORT\+\_\+\+BASE\+\_\+\+TIMESTAMP = 0x\+FBU\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 7.\+2.\+1. - -\Hypertarget{class_b_n_o08x_ab04695dd189412092254e52bd6e5a75a}\label{class_b_n_o08x_ab04695dd189412092254e52bd6e5a75a} -\index{BNO08x@{BNO08x}!SHTP\_REPORT\_COMMAND\_REQUEST@{SHTP\_REPORT\_COMMAND\_REQUEST}} -\index{SHTP\_REPORT\_COMMAND\_REQUEST@{SHTP\_REPORT\_COMMAND\_REQUEST}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SHTP\_REPORT\_COMMAND\_REQUEST}{SHTP\_REPORT\_COMMAND\_REQUEST}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SHTP\+\_\+\+REPORT\+\_\+\+COMMAND\+\_\+\+REQUEST = 0x\+F2U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+3.\+8. - -\Hypertarget{class_b_n_o08x_a1e5b64caa514b7e4fe64ab214758b875}\label{class_b_n_o08x_a1e5b64caa514b7e4fe64ab214758b875} -\index{BNO08x@{BNO08x}!SHTP\_REPORT\_COMMAND\_RESPONSE@{SHTP\_REPORT\_COMMAND\_RESPONSE}} -\index{SHTP\_REPORT\_COMMAND\_RESPONSE@{SHTP\_REPORT\_COMMAND\_RESPONSE}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SHTP\_REPORT\_COMMAND\_RESPONSE}{SHTP\_REPORT\_COMMAND\_RESPONSE}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SHTP\+\_\+\+REPORT\+\_\+\+COMMAND\+\_\+\+RESPONSE = 0x\+F1U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+3.\+9. - -\Hypertarget{class_b_n_o08x_a74af7eacc35cc825940b647c2de0d368}\label{class_b_n_o08x_a74af7eacc35cc825940b647c2de0d368} -\index{BNO08x@{BNO08x}!SHTP\_REPORT\_FRS\_READ\_REQUEST@{SHTP\_REPORT\_FRS\_READ\_REQUEST}} -\index{SHTP\_REPORT\_FRS\_READ\_REQUEST@{SHTP\_REPORT\_FRS\_READ\_REQUEST}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SHTP\_REPORT\_FRS\_READ\_REQUEST}{SHTP\_REPORT\_FRS\_READ\_REQUEST}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SHTP\+\_\+\+REPORT\+\_\+\+FRS\+\_\+\+READ\+\_\+\+REQUEST = 0x\+F4U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+3.\+6. - -\Hypertarget{class_b_n_o08x_aeb760b095dcf808a413ef696f2608e43}\label{class_b_n_o08x_aeb760b095dcf808a413ef696f2608e43} -\index{BNO08x@{BNO08x}!SHTP\_REPORT\_FRS\_READ\_RESPONSE@{SHTP\_REPORT\_FRS\_READ\_RESPONSE}} -\index{SHTP\_REPORT\_FRS\_READ\_RESPONSE@{SHTP\_REPORT\_FRS\_READ\_RESPONSE}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SHTP\_REPORT\_FRS\_READ\_RESPONSE}{SHTP\_REPORT\_FRS\_READ\_RESPONSE}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SHTP\+\_\+\+REPORT\+\_\+\+FRS\+\_\+\+READ\+\_\+\+RESPONSE = 0x\+F3U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+3.\+7. - -\Hypertarget{class_b_n_o08x_ad09312802cf5b8b5115362c86b53858b}\label{class_b_n_o08x_ad09312802cf5b8b5115362c86b53858b} -\index{BNO08x@{BNO08x}!SHTP\_REPORT\_GET\_FEATURE\_RESPONSE@{SHTP\_REPORT\_GET\_FEATURE\_RESPONSE}} -\index{SHTP\_REPORT\_GET\_FEATURE\_RESPONSE@{SHTP\_REPORT\_GET\_FEATURE\_RESPONSE}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SHTP\_REPORT\_GET\_FEATURE\_RESPONSE}{SHTP\_REPORT\_GET\_FEATURE\_RESPONSE}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SHTP\+\_\+\+REPORT\+\_\+\+GET\+\_\+\+FEATURE\+\_\+\+RESPONSE = 0x\+FCU\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+5. - -\Hypertarget{class_b_n_o08x_a542405639c28bd56bc4361b922763c95}\label{class_b_n_o08x_a542405639c28bd56bc4361b922763c95} -\index{BNO08x@{BNO08x}!SHTP\_REPORT\_PRODUCT\_ID\_REQUEST@{SHTP\_REPORT\_PRODUCT\_ID\_REQUEST}} -\index{SHTP\_REPORT\_PRODUCT\_ID\_REQUEST@{SHTP\_REPORT\_PRODUCT\_ID\_REQUEST}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SHTP\_REPORT\_PRODUCT\_ID\_REQUEST}{SHTP\_REPORT\_PRODUCT\_ID\_REQUEST}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SHTP\+\_\+\+REPORT\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REQUEST = 0x\+F9U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+3.\+1. - -\Hypertarget{class_b_n_o08x_a0177134162e116501bc9483c6e4b76c3}\label{class_b_n_o08x_a0177134162e116501bc9483c6e4b76c3} -\index{BNO08x@{BNO08x}!SHTP\_REPORT\_PRODUCT\_ID\_RESPONSE@{SHTP\_REPORT\_PRODUCT\_ID\_RESPONSE}} -\index{SHTP\_REPORT\_PRODUCT\_ID\_RESPONSE@{SHTP\_REPORT\_PRODUCT\_ID\_RESPONSE}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SHTP\_REPORT\_PRODUCT\_ID\_RESPONSE}{SHTP\_REPORT\_PRODUCT\_ID\_RESPONSE}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SHTP\+\_\+\+REPORT\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+RESPONSE = 0x\+F8U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+3.\+2. - -\Hypertarget{class_b_n_o08x_a1d3bff4e20c2c3d47db322c9e34ef338}\label{class_b_n_o08x_a1d3bff4e20c2c3d47db322c9e34ef338} -\index{BNO08x@{BNO08x}!SHTP\_REPORT\_SET\_FEATURE\_COMMAND@{SHTP\_REPORT\_SET\_FEATURE\_COMMAND}} -\index{SHTP\_REPORT\_SET\_FEATURE\_COMMAND@{SHTP\_REPORT\_SET\_FEATURE\_COMMAND}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{SHTP\_REPORT\_SET\_FEATURE\_COMMAND}{SHTP\_REPORT\_SET\_FEATURE\_COMMAND}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+SHTP\+\_\+\+REPORT\+\_\+\+SET\+\_\+\+FEATURE\+\_\+\+COMMAND = 0x\+FDU\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+5.\+4. - -\Hypertarget{class_b_n_o08x_acc0ea091465fc9a5736f5e0c6a0ce8ef}\label{class_b_n_o08x_acc0ea091465fc9a5736f5e0c6a0ce8ef} -\index{BNO08x@{BNO08x}!spi\_hdl@{spi\_hdl}} -\index{spi\_hdl@{spi\_hdl}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{spi\_hdl}{spi\_hdl}} -{\footnotesize\ttfamily spi\+\_\+device\+\_\+handle\+\_\+t BNO08x\+::spi\+\_\+hdl \{\}\hspace{0.3cm}{\ttfamily [private]}} - - - -SPI device handle. - -\Hypertarget{class_b_n_o08x_a615090aae15f1b0410a7e5ecb94957b5}\label{class_b_n_o08x_a615090aae15f1b0410a7e5ecb94957b5} -\index{BNO08x@{BNO08x}!spi\_task\_hdl@{spi\_task\_hdl}} -\index{spi\_task\_hdl@{spi\_task\_hdl}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{spi\_task\_hdl}{spi\_task\_hdl}} -{\footnotesize\ttfamily Task\+Handle\+\_\+t BNO08x\+::spi\+\_\+task\+\_\+hdl\hspace{0.3cm}{\ttfamily [private]}} - - - -\doxylink{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf}{spi\+\_\+task()} handle - -\Hypertarget{class_b_n_o08x_ac16adc5f00b0039c98a4921f13895026}\label{class_b_n_o08x_ac16adc5f00b0039c98a4921f13895026} -\index{BNO08x@{BNO08x}!spi\_transaction@{spi\_transaction}} -\index{spi\_transaction@{spi\_transaction}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{spi\_transaction}{spi\_transaction}} -{\footnotesize\ttfamily spi\+\_\+transaction\+\_\+t BNO08x\+::spi\+\_\+transaction \{\}\hspace{0.3cm}{\ttfamily [private]}} - - - -SPI transaction handle. - -\Hypertarget{class_b_n_o08x_a1b12471e92536a79d0c425d77676f2e1}\label{class_b_n_o08x_a1b12471e92536a79d0c425d77676f2e1} -\index{BNO08x@{BNO08x}!stability\_classifier@{stability\_classifier}} -\index{stability\_classifier@{stability\_classifier}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{stability\_classifier}{stability\_classifier}} -{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::stability\+\_\+classifier\hspace{0.3cm}{\ttfamily [private]}} - - - -BNO08x\+Stability status reading (See SH-\/2 Ref. Manual 6.\+5.\+31) - -\Hypertarget{class_b_n_o08x_ad80a77973371b12d722ea39063c648be}\label{class_b_n_o08x_ad80a77973371b12d722ea39063c648be} -\index{BNO08x@{BNO08x}!step\_count@{step\_count}} -\index{step\_count@{step\_count}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{step\_count}{step\_count}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::step\+\_\+count\hspace{0.3cm}{\ttfamily [private]}} - - - -Step counter reading (See SH-\/2 Ref. Manual 6.\+5.\+29) - -\Hypertarget{class_b_n_o08x_a2c98d5f2c406a3efd0b48c5666fa8c46}\label{class_b_n_o08x_a2c98d5f2c406a3efd0b48c5666fa8c46} -\index{BNO08x@{BNO08x}!TAG@{TAG}} -\index{TAG@{TAG}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TAG}{TAG}} -{\footnotesize\ttfamily const constexpr char\texorpdfstring{$\ast$}{*} BNO08x\+::\+TAG = "{}BNO08x"{}\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Class tag used for serial print statements. - -\Hypertarget{class_b_n_o08x_a1171a5738a4e6831ec7fa32a29f15554}\label{class_b_n_o08x_a1171a5738a4e6831ec7fa32a29f15554} -\index{BNO08x@{BNO08x}!tap\_detector@{tap\_detector}} -\index{tap\_detector@{tap\_detector}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{tap\_detector}{tap\_detector}} -{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::tap\+\_\+detector\hspace{0.3cm}{\ttfamily [private]}} - - - -Tap detector reading (See SH-\/2 Ref. Manual 6.\+5.\+27) - -\Hypertarget{class_b_n_o08x_a68aaaab144adbe5af00597408f044d9d}\label{class_b_n_o08x_a68aaaab144adbe5af00597408f044d9d} -\index{BNO08x@{BNO08x}!TARE\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR@{TARE\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR}} -\index{TARE\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR@{TARE\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TARE\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR}{TARE\_ARVR\_STABILIZED\_GAME\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+TARE\+\_\+\+ARVR\+\_\+\+STABILIZED\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR = 5U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Tare ARVR stabilized game rotation vector. - -\Hypertarget{class_b_n_o08x_abff9abe904bcdde951cf88c378284b45}\label{class_b_n_o08x_abff9abe904bcdde951cf88c378284b45} -\index{BNO08x@{BNO08x}!TARE\_ARVR\_STABILIZED\_ROTATION\_VECTOR@{TARE\_ARVR\_STABILIZED\_ROTATION\_VECTOR}} -\index{TARE\_ARVR\_STABILIZED\_ROTATION\_VECTOR@{TARE\_ARVR\_STABILIZED\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TARE\_ARVR\_STABILIZED\_ROTATION\_VECTOR}{TARE\_ARVR\_STABILIZED\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+TARE\+\_\+\+ARVR\+\_\+\+STABILIZED\+\_\+\+ROTATION\+\_\+\+VECTOR = 4U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Tare ARVR stabilized rotation vector. - -\Hypertarget{class_b_n_o08x_a1ef13f6f330810934416ad5fe0ee55b2}\label{class_b_n_o08x_a1ef13f6f330810934416ad5fe0ee55b2} -\index{BNO08x@{BNO08x}!TARE\_AXIS\_ALL@{TARE\_AXIS\_ALL}} -\index{TARE\_AXIS\_ALL@{TARE\_AXIS\_ALL}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TARE\_AXIS\_ALL}{TARE\_AXIS\_ALL}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+TARE\+\_\+\+AXIS\+\_\+\+ALL = 0x07U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Tare all axes (used with tare now command) - -\Hypertarget{class_b_n_o08x_aecb3e11c1ca5769fd60f42c17a105731}\label{class_b_n_o08x_aecb3e11c1ca5769fd60f42c17a105731} -\index{BNO08x@{BNO08x}!TARE\_AXIS\_Z@{TARE\_AXIS\_Z}} -\index{TARE\_AXIS\_Z@{TARE\_AXIS\_Z}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TARE\_AXIS\_Z}{TARE\_AXIS\_Z}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+TARE\+\_\+\+AXIS\+\_\+Z = 0x04U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Tar yaw axis only (used with tare now command) - -\Hypertarget{class_b_n_o08x_abaf1ec8bb197db1998a9ed3cec6180d5}\label{class_b_n_o08x_abaf1ec8bb197db1998a9ed3cec6180d5} -\index{BNO08x@{BNO08x}!TARE\_GAME\_ROTATION\_VECTOR@{TARE\_GAME\_ROTATION\_VECTOR}} -\index{TARE\_GAME\_ROTATION\_VECTOR@{TARE\_GAME\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TARE\_GAME\_ROTATION\_VECTOR}{TARE\_GAME\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+TARE\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR = 1U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Tare game rotation vector. - -\Hypertarget{class_b_n_o08x_a225397a04d849e5647992ca80d68febb}\label{class_b_n_o08x_a225397a04d849e5647992ca80d68febb} -\index{BNO08x@{BNO08x}!TARE\_GEOMAGNETIC\_ROTATION\_VECTOR@{TARE\_GEOMAGNETIC\_ROTATION\_VECTOR}} -\index{TARE\_GEOMAGNETIC\_ROTATION\_VECTOR@{TARE\_GEOMAGNETIC\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TARE\_GEOMAGNETIC\_ROTATION\_VECTOR}{TARE\_GEOMAGNETIC\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+TARE\+\_\+\+GEOMAGNETIC\+\_\+\+ROTATION\+\_\+\+VECTOR = 2U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -tare geomagnetic rotation vector - -\Hypertarget{class_b_n_o08x_a9ec354d75249f06f13599abf7bedfde0}\label{class_b_n_o08x_a9ec354d75249f06f13599abf7bedfde0} -\index{BNO08x@{BNO08x}!TARE\_GYRO\_INTEGRATED\_ROTATION\_VECTOR@{TARE\_GYRO\_INTEGRATED\_ROTATION\_VECTOR}} -\index{TARE\_GYRO\_INTEGRATED\_ROTATION\_VECTOR@{TARE\_GYRO\_INTEGRATED\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TARE\_GYRO\_INTEGRATED\_ROTATION\_VECTOR}{TARE\_GYRO\_INTEGRATED\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+TARE\+\_\+\+GYRO\+\_\+\+INTEGRATED\+\_\+\+ROTATION\+\_\+\+VECTOR = 3U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Tare gyro integrated rotation vector. - -\Hypertarget{class_b_n_o08x_a27df630f3e52b35552d2c1f2cf3496b0}\label{class_b_n_o08x_a27df630f3e52b35552d2c1f2cf3496b0} -\index{BNO08x@{BNO08x}!TARE\_NOW@{TARE\_NOW}} -\index{TARE\_NOW@{TARE\_NOW}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TARE\_NOW}{TARE\_NOW}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+TARE\+\_\+\+NOW = 0U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+4.\+4.\+1. - -\Hypertarget{class_b_n_o08x_a115aef7b38ec0dec2085f6917d832912}\label{class_b_n_o08x_a115aef7b38ec0dec2085f6917d832912} -\index{BNO08x@{BNO08x}!TARE\_PERSIST@{TARE\_PERSIST}} -\index{TARE\_PERSIST@{TARE\_PERSIST}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TARE\_PERSIST}{TARE\_PERSIST}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+TARE\+\_\+\+PERSIST = 1U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+4.\+4.\+2. - -\Hypertarget{class_b_n_o08x_a8e2cfc25d0e34ae53a762b88cc3ac3c8}\label{class_b_n_o08x_a8e2cfc25d0e34ae53a762b88cc3ac3c8} -\index{BNO08x@{BNO08x}!TARE\_ROTATION\_VECTOR@{TARE\_ROTATION\_VECTOR}} -\index{TARE\_ROTATION\_VECTOR@{TARE\_ROTATION\_VECTOR}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TARE\_ROTATION\_VECTOR}{TARE\_ROTATION\_VECTOR}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+TARE\+\_\+\+ROTATION\+\_\+\+VECTOR = 0U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}} - - - -Tare rotation vector. - -\Hypertarget{class_b_n_o08x_a59cde7dd301c94a20b84735c5d49008e}\label{class_b_n_o08x_a59cde7dd301c94a20b84735c5d49008e} -\index{BNO08x@{BNO08x}!TARE\_SET\_REORIENTATION@{TARE\_SET\_REORIENTATION}} -\index{TARE\_SET\_REORIENTATION@{TARE\_SET\_REORIENTATION}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TARE\_SET\_REORIENTATION}{TARE\_SET\_REORIENTATION}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+TARE\+\_\+\+SET\+\_\+\+REORIENTATION = 2U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -See SH2 Ref. Manual 6.\+4.\+4.\+3. - -\Hypertarget{class_b_n_o08x_a5448bffec9a90f5c388b3c22928463ae}\label{class_b_n_o08x_a5448bffec9a90f5c388b3c22928463ae} -\index{BNO08x@{BNO08x}!TASK\_CNT@{TASK\_CNT}} -\index{TASK\_CNT@{TASK\_CNT}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{TASK\_CNT}{TASK\_CNT}} -{\footnotesize\ttfamily const constexpr uint8\+\_\+t BNO08x\+::\+TASK\+\_\+\+CNT = 2U\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - - - -Total amount of tasks utilized by \doxylink{class_b_n_o08x}{BNO08x} driver library. - -\Hypertarget{class_b_n_o08x_abc972db20affbd0040b4e6c4892dd57b}\label{class_b_n_o08x_abc972db20affbd0040b4e6c4892dd57b} -\index{BNO08x@{BNO08x}!time\_stamp@{time\_stamp}} -\index{time\_stamp@{time\_stamp}!BNO08x@{BNO08x}} -\doxysubsubsection{\texorpdfstring{time\_stamp}{time\_stamp}} -{\footnotesize\ttfamily uint32\+\_\+t BNO08x\+::time\+\_\+stamp\hspace{0.3cm}{\ttfamily [private]}} - - - -Report timestamp (see datasheet 1.\+3.\+5.\+3) - - - -The documentation for this class was generated from the following files\+:\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_b_n_o08x_8hpp}{BNO08x.\+hpp}}\item -\mbox{\hyperlink{_b_n_o08x_8cpp}{BNO08x.\+cpp}}\end{DoxyCompactItemize} diff --git a/documentation/latex/class_b_n_o08x__coll__graph.md5 b/documentation/latex/class_b_n_o08x__coll__graph.md5 deleted file mode 100644 index 51ecf71..0000000 --- a/documentation/latex/class_b_n_o08x__coll__graph.md5 +++ /dev/null @@ -1 +0,0 @@ -fb0a9c1ecf2ebb54cc832b5fa274da43 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x__coll__graph.pdf b/documentation/latex/class_b_n_o08x__coll__graph.pdf deleted file mode 100644 index 6516874..0000000 Binary files a/documentation/latex/class_b_n_o08x__coll__graph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.md5 b/documentation/latex/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.md5 deleted file mode 100644 index f51f019..0000000 --- a/documentation/latex/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d270e5f2479e03b70f0b2cd31dd5b61c \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.pdf b/documentation/latex/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.pdf deleted file mode 100644 index cbd12ac..0000000 Binary files a/documentation/latex/class_b_n_o08x_a002aa97c9af8f6df2d0c83034e4f7b55_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.md5 b/documentation/latex/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.md5 deleted file mode 100644 index 7c60afa..0000000 --- a/documentation/latex/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b7df294b3e534ffbd28a66ce36074f8e \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.pdf b/documentation/latex/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.pdf deleted file mode 100644 index b2e3ff6..0000000 Binary files a/documentation/latex/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.md5 b/documentation/latex/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.md5 deleted file mode 100644 index fcb5231..0000000 --- a/documentation/latex/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -183f74debbbb41168329e6bc7025e0f9 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.pdf b/documentation/latex/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.pdf deleted file mode 100644 index d0d3d67..0000000 Binary files a/documentation/latex/class_b_n_o08x_a00ec3857cb06ae885e32059ef1cab693_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.md5 b/documentation/latex/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.md5 deleted file mode 100644 index f6889fe..0000000 --- a/documentation/latex/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6e16b58c051ea9408612261b1c1d8c8b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.pdf b/documentation/latex/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.pdf deleted file mode 100644 index f753c9e..0000000 Binary files a/documentation/latex/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.md5 b/documentation/latex/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.md5 deleted file mode 100644 index 1dcbd52..0000000 --- a/documentation/latex/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7901fa92b9512217e5823e5e4268847c \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.pdf b/documentation/latex/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.pdf deleted file mode 100644 index 8a717be..0000000 Binary files a/documentation/latex/class_b_n_o08x_a030eae12c3586acf09b48e94630b2544_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.md5 b/documentation/latex/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.md5 deleted file mode 100644 index c4fd3f5..0000000 --- a/documentation/latex/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -bd38c1a94a704ef50d7d3504775e8eeb \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.pdf b/documentation/latex/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.pdf deleted file mode 100644 index 144ea39..0000000 Binary files a/documentation/latex/class_b_n_o08x_a039e8770759e784baa438324ae17883c_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.md5 b/documentation/latex/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.md5 deleted file mode 100644 index e570fba..0000000 --- a/documentation/latex/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c1219edb4ecf96568cda1c990fc42394 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.pdf b/documentation/latex/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.pdf deleted file mode 100644 index 04fe889..0000000 Binary files a/documentation/latex/class_b_n_o08x_a039e8770759e784baa438324ae17883c_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.md5 b/documentation/latex/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.md5 deleted file mode 100644 index f470c9f..0000000 --- a/documentation/latex/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -538d82f7025d88cd34dabbff9f4bacc2 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.pdf b/documentation/latex/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.pdf deleted file mode 100644 index 621b33a..0000000 Binary files a/documentation/latex/class_b_n_o08x_a04489cf9a125495c7cf07c6ba5e9f6c0_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.md5 b/documentation/latex/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.md5 deleted file mode 100644 index 6bf7f4a..0000000 --- a/documentation/latex/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c54d3d8c45aa537bca47ca9a4e29e8bc \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.pdf b/documentation/latex/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.pdf deleted file mode 100644 index b4766df..0000000 Binary files a/documentation/latex/class_b_n_o08x_a05e4cd5861b55fc0182d7dd13bb85e49_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.md5 b/documentation/latex/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.md5 deleted file mode 100644 index 627e99c..0000000 --- a/documentation/latex/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8615014fa7da50cb05de1cdc3fb62142 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.pdf b/documentation/latex/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.pdf deleted file mode 100644 index 1da7c4a..0000000 Binary files a/documentation/latex/class_b_n_o08x_a067678914e928a6691625b17c40237a0_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.md5 b/documentation/latex/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.md5 deleted file mode 100644 index cbe21be..0000000 --- a/documentation/latex/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ef46de4d886aec0849e8d00667c9fc80 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.pdf b/documentation/latex/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.pdf deleted file mode 100644 index b768b5b..0000000 Binary files a/documentation/latex/class_b_n_o08x_a067678914e928a6691625b17c40237a0_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.md5 b/documentation/latex/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.md5 deleted file mode 100644 index 54c58e7..0000000 --- a/documentation/latex/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4e89ae34d0edef3c1a9a96972a063737 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.pdf b/documentation/latex/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.pdf deleted file mode 100644 index 200c2cc..0000000 Binary files a/documentation/latex/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.md5 b/documentation/latex/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.md5 deleted file mode 100644 index a2f8ba3..0000000 --- a/documentation/latex/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -91a1c69c5c03d0e6f14a69a55ff9dd02 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.pdf b/documentation/latex/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.pdf deleted file mode 100644 index 4aef608..0000000 Binary files a/documentation/latex/class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.md5 b/documentation/latex/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.md5 deleted file mode 100644 index a590758..0000000 --- a/documentation/latex/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -15ece511a44f9c4425f222f48c9fada9 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.pdf b/documentation/latex/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.pdf deleted file mode 100644 index 7252e43..0000000 Binary files a/documentation/latex/class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.md5 b/documentation/latex/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.md5 deleted file mode 100644 index 50d8156..0000000 --- a/documentation/latex/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -740f7234e30625f39a967abdd860c55c \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.pdf b/documentation/latex/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.pdf deleted file mode 100644 index b326c48..0000000 Binary files a/documentation/latex/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.md5 b/documentation/latex/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.md5 deleted file mode 100644 index 7f7da86..0000000 --- a/documentation/latex/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c71b124f392ef7e478c8bb08526bb67f \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.pdf b/documentation/latex/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.pdf deleted file mode 100644 index caae749..0000000 Binary files a/documentation/latex/class_b_n_o08x_a0ae135d7bf7a5f047a1d1aa5cc07e520_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.md5 b/documentation/latex/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.md5 deleted file mode 100644 index 51047bd..0000000 --- a/documentation/latex/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f8407d811b81cf9b07b4ad2fd61c58e6 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.pdf b/documentation/latex/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.pdf deleted file mode 100644 index 111a454..0000000 Binary files a/documentation/latex/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.md5 b/documentation/latex/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.md5 deleted file mode 100644 index 3b0e7ad..0000000 --- a/documentation/latex/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8d0b54ef7c09d0a974d31cb63808103c \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.pdf b/documentation/latex/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.pdf deleted file mode 100644 index c10765e..0000000 Binary files a/documentation/latex/class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.md5 b/documentation/latex/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.md5 deleted file mode 100644 index 46d28c0..0000000 --- a/documentation/latex/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -bce82c46ece03d4bc1d703a80fdf5644 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.pdf b/documentation/latex/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.pdf deleted file mode 100644 index 869531e..0000000 Binary files a/documentation/latex/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.md5 b/documentation/latex/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.md5 deleted file mode 100644 index 0822d0a..0000000 --- a/documentation/latex/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -794a01cb3ec50276d5aacdbeb30d04e1 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.pdf b/documentation/latex/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.pdf deleted file mode 100644 index e1ceeae..0000000 Binary files a/documentation/latex/class_b_n_o08x_a0ec9b1a10bbf25a057273605575f0d64_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.md5 b/documentation/latex/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.md5 deleted file mode 100644 index 5b9b46e..0000000 --- a/documentation/latex/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -16bc632e5c08a1bb1faa53991930d8f3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.pdf b/documentation/latex/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.pdf deleted file mode 100644 index a071a4f..0000000 Binary files a/documentation/latex/class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.md5 b/documentation/latex/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.md5 deleted file mode 100644 index a6fe096..0000000 --- a/documentation/latex/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -98da2a1778e70dd73d32df00748bab7e \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.pdf b/documentation/latex/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.pdf deleted file mode 100644 index e16141a..0000000 Binary files a/documentation/latex/class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.md5 b/documentation/latex/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.md5 deleted file mode 100644 index 33b66cd..0000000 --- a/documentation/latex/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -63f48050ff5fbe81651ed54e697b8d0f \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.pdf b/documentation/latex/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.pdf deleted file mode 100644 index 514b65e..0000000 Binary files a/documentation/latex/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.md5 b/documentation/latex/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.md5 deleted file mode 100644 index 8d68dac..0000000 --- a/documentation/latex/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a7e1c897d1537291b3a813c54033f3a1 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.pdf b/documentation/latex/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.pdf deleted file mode 100644 index 04ce627..0000000 Binary files a/documentation/latex/class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.md5 b/documentation/latex/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.md5 deleted file mode 100644 index c20f175..0000000 --- a/documentation/latex/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3aedd67ad1b05742bc6e117cf8fc42e7 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.pdf b/documentation/latex/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.pdf deleted file mode 100644 index 5669369..0000000 Binary files a/documentation/latex/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.md5 b/documentation/latex/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.md5 deleted file mode 100644 index 3c01a2e..0000000 --- a/documentation/latex/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5a63170cd93548d2f2712caaa01a6fd3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.pdf b/documentation/latex/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.pdf deleted file mode 100644 index 14453df..0000000 Binary files a/documentation/latex/class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.md5 b/documentation/latex/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.md5 deleted file mode 100644 index 774db5c..0000000 --- a/documentation/latex/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ecef7c4d26bf83f70f5cdce5e72ca4e6 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.pdf b/documentation/latex/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.pdf deleted file mode 100644 index bf60af0..0000000 Binary files a/documentation/latex/class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.md5 b/documentation/latex/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.md5 deleted file mode 100644 index 391f747..0000000 --- a/documentation/latex/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ea78cf900bb935591823f3db92bb02f9 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.pdf b/documentation/latex/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.pdf deleted file mode 100644 index 2463eb8..0000000 Binary files a/documentation/latex/class_b_n_o08x_a1599c0515f05a08c043f237c46d29dea_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.md5 b/documentation/latex/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.md5 deleted file mode 100644 index 4ff7136..0000000 --- a/documentation/latex/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -25107e654bd69870cd91bab608c09c70 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.pdf b/documentation/latex/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.pdf deleted file mode 100644 index b65e3cc..0000000 Binary files a/documentation/latex/class_b_n_o08x_a16f83d1e85576a51abf2c65e5de58cd2_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.md5 b/documentation/latex/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.md5 deleted file mode 100644 index 7cf3535..0000000 --- a/documentation/latex/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ae5a4381c3730bc3f682d56c9f0a729d \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.pdf b/documentation/latex/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.pdf deleted file mode 100644 index a607236..0000000 Binary files a/documentation/latex/class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.md5 b/documentation/latex/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.md5 deleted file mode 100644 index 6bf65ac..0000000 --- a/documentation/latex/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0f0d964e78f7ff9760c50b5f7f218905 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.pdf b/documentation/latex/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.pdf deleted file mode 100644 index 569d8be..0000000 Binary files a/documentation/latex/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.md5 b/documentation/latex/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.md5 deleted file mode 100644 index 8b1a122..0000000 --- a/documentation/latex/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -10dc8f2aad4fa7f402038f263991e425 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.pdf b/documentation/latex/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.pdf deleted file mode 100644 index 7d98340..0000000 Binary files a/documentation/latex/class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.md5 b/documentation/latex/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.md5 deleted file mode 100644 index 3575ead..0000000 --- a/documentation/latex/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -90e9081a4c92d68c4fc67ff973682a18 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.pdf b/documentation/latex/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.pdf deleted file mode 100644 index be2e31d..0000000 Binary files a/documentation/latex/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.md5 b/documentation/latex/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.md5 deleted file mode 100644 index be1ae1b..0000000 --- a/documentation/latex/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -523ba60e1f68dfed848cb1862e6787fe \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.pdf b/documentation/latex/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.pdf deleted file mode 100644 index bb2ff54..0000000 Binary files a/documentation/latex/class_b_n_o08x_a1c47d27917ae3b2876efa121b803f924_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.md5 b/documentation/latex/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.md5 deleted file mode 100644 index bf0bca0..0000000 --- a/documentation/latex/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9ca68cb6116c5ee6ccbe149f85142f9d \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.pdf b/documentation/latex/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.pdf deleted file mode 100644 index 887725d..0000000 Binary files a/documentation/latex/class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.md5 b/documentation/latex/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.md5 deleted file mode 100644 index 67b3fdb..0000000 --- a/documentation/latex/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -05c1080b1503594cfc48b056eabb5bd7 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.pdf b/documentation/latex/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.pdf deleted file mode 100644 index d85d4d0..0000000 Binary files a/documentation/latex/class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.md5 b/documentation/latex/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.md5 deleted file mode 100644 index ff5ae6c..0000000 --- a/documentation/latex/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d0132c912c3deee947d7802cdf0262ff \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.pdf b/documentation/latex/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.pdf deleted file mode 100644 index bf9d43a..0000000 Binary files a/documentation/latex/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.md5 b/documentation/latex/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.md5 deleted file mode 100644 index ceb543b..0000000 --- a/documentation/latex/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f7b1baa43101aee46a2f83d90d17d9a5 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.pdf b/documentation/latex/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.pdf deleted file mode 100644 index aeb34bf..0000000 Binary files a/documentation/latex/class_b_n_o08x_a1ebd456d2a67a22b5ba0911a95915921_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.md5 b/documentation/latex/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.md5 deleted file mode 100644 index 0610066..0000000 --- a/documentation/latex/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7fdb0dabdc7bf8e91a315c4353a68ddd \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.pdf b/documentation/latex/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.pdf deleted file mode 100644 index 6183fcc..0000000 Binary files a/documentation/latex/class_b_n_o08x_a1f0f4cd8dc7d38448e2198ea47d0018c_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.md5 b/documentation/latex/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.md5 deleted file mode 100644 index 0d216e0..0000000 --- a/documentation/latex/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -400ded539100c6ce9c23fee64d6b7f6b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.pdf b/documentation/latex/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.pdf deleted file mode 100644 index e4ebb99..0000000 Binary files a/documentation/latex/class_b_n_o08x_a206c0e3ddc3b745b56914976d6e69981_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.md5 b/documentation/latex/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.md5 deleted file mode 100644 index 57ba2f2..0000000 --- a/documentation/latex/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3f2f57c9fdd744e9ca30fe68f0293e2e \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.pdf b/documentation/latex/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.pdf deleted file mode 100644 index 7b5c94f..0000000 Binary files a/documentation/latex/class_b_n_o08x_a233920ce97f685fbdabecccacf471d85_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.md5 b/documentation/latex/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.md5 deleted file mode 100644 index 85b3e5a..0000000 --- a/documentation/latex/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2c7b19cdbae657ed114d21ce5dc7f452 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.pdf b/documentation/latex/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.pdf deleted file mode 100644 index 76311a7..0000000 Binary files a/documentation/latex/class_b_n_o08x_a248544b262582d10d917a687190cb454_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.md5 b/documentation/latex/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.md5 deleted file mode 100644 index 54af502..0000000 --- a/documentation/latex/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8730ea835da10dac765ba547f46578b7 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.pdf b/documentation/latex/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.pdf deleted file mode 100644 index fe4661b..0000000 Binary files a/documentation/latex/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.md5 b/documentation/latex/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.md5 deleted file mode 100644 index 9b482ca..0000000 --- a/documentation/latex/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5829649044d18373b5bfed78f5eb8557 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.pdf b/documentation/latex/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.pdf deleted file mode 100644 index 8366ccd..0000000 Binary files a/documentation/latex/class_b_n_o08x_a2795c6579cf03e22f62a5eadc88dee91_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.md5 b/documentation/latex/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.md5 deleted file mode 100644 index 659d2b5..0000000 --- a/documentation/latex/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a29d510a689f35bb409d28992909bd3b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.pdf b/documentation/latex/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.pdf deleted file mode 100644 index 4618678..0000000 Binary files a/documentation/latex/class_b_n_o08x_a27b5317d11a5b81028b87a73b7024bfa_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.md5 b/documentation/latex/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.md5 deleted file mode 100644 index 174e887..0000000 --- a/documentation/latex/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -691c3210d78459b9386f7cd50cb5b1fb \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.pdf b/documentation/latex/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.pdf deleted file mode 100644 index 3d98a31..0000000 Binary files a/documentation/latex/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.md5 b/documentation/latex/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.md5 deleted file mode 100644 index c1cd49b..0000000 --- a/documentation/latex/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5c85513ddf7d768a41c17cd4992a3364 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.pdf b/documentation/latex/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.pdf deleted file mode 100644 index c9b0fbf..0000000 Binary files a/documentation/latex/class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.md5 b/documentation/latex/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.md5 deleted file mode 100644 index c8b747f..0000000 --- a/documentation/latex/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8363d4787b170958c766d1c703c7e40f \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.pdf b/documentation/latex/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.pdf deleted file mode 100644 index c654a66..0000000 Binary files a/documentation/latex/class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.md5 b/documentation/latex/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.md5 deleted file mode 100644 index 178b165..0000000 --- a/documentation/latex/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c7d580650b9fa923d851071e6fef5420 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.pdf b/documentation/latex/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.pdf deleted file mode 100644 index b0d0fcc..0000000 Binary files a/documentation/latex/class_b_n_o08x_a2897a178bf2c53cd99df0d4570edf72e_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.md5 b/documentation/latex/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.md5 deleted file mode 100644 index 677f94f..0000000 --- a/documentation/latex/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7b02203edf40eb92dc577068b0d6cc06 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.pdf b/documentation/latex/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.pdf deleted file mode 100644 index 0e1920c..0000000 Binary files a/documentation/latex/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.md5 b/documentation/latex/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.md5 deleted file mode 100644 index 3d1189d..0000000 --- a/documentation/latex/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7b69b515885631127e67ec38b9c53ee6 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.pdf b/documentation/latex/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.pdf deleted file mode 100644 index beef5e4..0000000 Binary files a/documentation/latex/class_b_n_o08x_a28cd1c0b3477571d87133234e6358503_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.md5 b/documentation/latex/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.md5 deleted file mode 100644 index 2a3a860..0000000 --- a/documentation/latex/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -641ef4c6c91d39304d6376d7c9360e7b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.pdf b/documentation/latex/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.pdf deleted file mode 100644 index 458058b..0000000 Binary files a/documentation/latex/class_b_n_o08x_a29cfd7fc2816483ebebe9d55b677a036_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.md5 b/documentation/latex/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.md5 deleted file mode 100644 index e665eea..0000000 --- a/documentation/latex/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -27e64d61a08cbd79e6e512663c41bf93 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.pdf b/documentation/latex/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.pdf deleted file mode 100644 index 1523360..0000000 Binary files a/documentation/latex/class_b_n_o08x_a2c359a44a2c8e83ecb258a340e2d0e1a_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.md5 b/documentation/latex/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.md5 deleted file mode 100644 index e3d0768..0000000 --- a/documentation/latex/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a9601d7551ad5264115296e05c2b4a8e \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.pdf b/documentation/latex/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.pdf deleted file mode 100644 index 167df25..0000000 Binary files a/documentation/latex/class_b_n_o08x_a2d5a9fa5c960b9efa96d311d25f711de_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.md5 b/documentation/latex/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.md5 deleted file mode 100644 index 2de85a0..0000000 --- a/documentation/latex/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -728db68eeba4a3cab7a3080b8f10c6b8 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.pdf b/documentation/latex/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.pdf deleted file mode 100644 index b349368..0000000 Binary files a/documentation/latex/class_b_n_o08x_a2d98b2cba47dffee8745de1955d234a9_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.md5 b/documentation/latex/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.md5 deleted file mode 100644 index 07a3b78..0000000 --- a/documentation/latex/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1d52014e737a09b2d5f99b612f368da8 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.pdf b/documentation/latex/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.pdf deleted file mode 100644 index 8a83a91..0000000 Binary files a/documentation/latex/class_b_n_o08x_a2eb2accfbc70366e6e3eaf391622c1ff_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.md5 b/documentation/latex/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.md5 deleted file mode 100644 index 7364d47..0000000 --- a/documentation/latex/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -451ba80303e1567153f236381d46944d \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.pdf b/documentation/latex/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.pdf deleted file mode 100644 index 5f907f1..0000000 Binary files a/documentation/latex/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.md5 b/documentation/latex/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.md5 deleted file mode 100644 index ad9df91..0000000 --- a/documentation/latex/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -aece1a8aecf671c99e09d0ca5464b173 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.pdf b/documentation/latex/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.pdf deleted file mode 100644 index 254fe34..0000000 Binary files a/documentation/latex/class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.md5 b/documentation/latex/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.md5 deleted file mode 100644 index a414d92..0000000 --- a/documentation/latex/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7abb4edb9d44a6550705ed956b2da4b1 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.pdf b/documentation/latex/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.pdf deleted file mode 100644 index cf14005..0000000 Binary files a/documentation/latex/class_b_n_o08x_a358316b883928c50dd381f024e6b0645_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.md5 b/documentation/latex/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.md5 deleted file mode 100644 index 7d95878..0000000 --- a/documentation/latex/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fcbfc0d2949f7d42720afe820fe98e90 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.pdf b/documentation/latex/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.pdf deleted file mode 100644 index 533098d..0000000 Binary files a/documentation/latex/class_b_n_o08x_a3abf4a199bc7a03ac7447c2781673d88_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.md5 b/documentation/latex/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.md5 deleted file mode 100644 index 3f5865a..0000000 --- a/documentation/latex/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -cc3fdf8385d4ad7f7df18e00febec73e \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.pdf b/documentation/latex/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.pdf deleted file mode 100644 index de7ab2b..0000000 Binary files a/documentation/latex/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.md5 b/documentation/latex/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.md5 deleted file mode 100644 index f31785c..0000000 --- a/documentation/latex/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d69d774eba0a9643665559f149c26f88 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.pdf b/documentation/latex/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.pdf deleted file mode 100644 index 31598cc..0000000 Binary files a/documentation/latex/class_b_n_o08x_a3c32120bcd0987c3ca1bb72910586b59_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.md5 b/documentation/latex/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.md5 deleted file mode 100644 index 293c698..0000000 --- a/documentation/latex/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f81b1cae0a266390c1db0a9a1c6e8d04 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.pdf b/documentation/latex/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.pdf deleted file mode 100644 index 4cc4d95..0000000 Binary files a/documentation/latex/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.md5 b/documentation/latex/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.md5 deleted file mode 100644 index 52b332d..0000000 --- a/documentation/latex/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -333c766050178b21014c85a1b8841644 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.pdf b/documentation/latex/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.pdf deleted file mode 100644 index 5649534..0000000 Binary files a/documentation/latex/class_b_n_o08x_a3c9797a2a2be14ee6e8126f1295fa885_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.md5 b/documentation/latex/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.md5 deleted file mode 100644 index 6f820a0..0000000 --- a/documentation/latex/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b169571331c2593ae4793fca0e13beab \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.pdf b/documentation/latex/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.pdf deleted file mode 100644 index 3a9f280..0000000 Binary files a/documentation/latex/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.md5 b/documentation/latex/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.md5 deleted file mode 100644 index 2c3ae3c..0000000 --- a/documentation/latex/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -31921b8dcdd53c3f6af59f3fa816b363 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.pdf b/documentation/latex/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.pdf deleted file mode 100644 index 1c51ab5..0000000 Binary files a/documentation/latex/class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.md5 b/documentation/latex/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.md5 deleted file mode 100644 index f8c1eb1..0000000 --- a/documentation/latex/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -73a6527ea769c144659f112d2f942e21 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.pdf b/documentation/latex/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.pdf deleted file mode 100644 index 1b72bd3..0000000 Binary files a/documentation/latex/class_b_n_o08x_a427550a4ba25252912436b899124e157_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.md5 b/documentation/latex/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.md5 deleted file mode 100644 index 7ba12bc..0000000 --- a/documentation/latex/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -bd3e314f08dd4246bc76d51c1f6686af \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.pdf b/documentation/latex/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.pdf deleted file mode 100644 index 7c12837..0000000 Binary files a/documentation/latex/class_b_n_o08x_a427550a4ba25252912436b899124e157_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.md5 b/documentation/latex/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.md5 deleted file mode 100644 index f126df1..0000000 --- a/documentation/latex/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -60e32c1c1123648e067bc2b9e825d4b2 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.pdf b/documentation/latex/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.pdf deleted file mode 100644 index d9e5298..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.md5 b/documentation/latex/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.md5 deleted file mode 100644 index 9a8fa54..0000000 --- a/documentation/latex/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -09d30187a6b643602105a26ba955b0c3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.pdf b/documentation/latex/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.pdf deleted file mode 100644 index 12634fd..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4421c43323945946ad605f8422958dcf_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.md5 b/documentation/latex/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.md5 deleted file mode 100644 index 742755b..0000000 --- a/documentation/latex/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2ea411d324a122d526a6a94e0233b092 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.pdf b/documentation/latex/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.pdf deleted file mode 100644 index a6414e9..0000000 Binary files a/documentation/latex/class_b_n_o08x_a453ec8a70646651d4e5b10bf0b2e4d61_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.md5 b/documentation/latex/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.md5 deleted file mode 100644 index 9c9db0c..0000000 --- a/documentation/latex/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -aed5d6179347e3f8dd2b8808c8c9633b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.pdf b/documentation/latex/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.pdf deleted file mode 100644 index c24c0c5..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.md5 b/documentation/latex/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.md5 deleted file mode 100644 index 4402344..0000000 --- a/documentation/latex/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0e4a58bb22e9bb6c5b322d200364a67f \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.pdf b/documentation/latex/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.pdf deleted file mode 100644 index 3607e0b..0000000 Binary files a/documentation/latex/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.md5 b/documentation/latex/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.md5 deleted file mode 100644 index de941b8..0000000 --- a/documentation/latex/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1d78d53beea1b066d15234556c5594d6 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.pdf b/documentation/latex/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.pdf deleted file mode 100644 index f8e3162..0000000 Binary files a/documentation/latex/class_b_n_o08x_a48c1d43b66b1a0894cb1fc2179f62cdc_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.md5 b/documentation/latex/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.md5 deleted file mode 100644 index dbe701b..0000000 --- a/documentation/latex/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2b31ae297c6cb226fe0b8df716b11e35 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.pdf b/documentation/latex/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.pdf deleted file mode 100644 index ed87e76..0000000 Binary files a/documentation/latex/class_b_n_o08x_a492d5bde7377d9f6773eae1d70967f50_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.md5 b/documentation/latex/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.md5 deleted file mode 100644 index 921e9fc..0000000 --- a/documentation/latex/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -55ca054655ba5d9e4cc4f2b7b1965ef0 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.pdf b/documentation/latex/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.pdf deleted file mode 100644 index 75f148b..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4a72489c56960d83050ae9c4b9ab75ed_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.md5 b/documentation/latex/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.md5 deleted file mode 100644 index 7229314..0000000 --- a/documentation/latex/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e580ad41b167ea7e075ab118b6922b83 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.pdf b/documentation/latex/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.pdf deleted file mode 100644 index 37a6579..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.md5 b/documentation/latex/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.md5 deleted file mode 100644 index 1bfd7db..0000000 --- a/documentation/latex/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c935919d138c29a9fa821b87d1100cd3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.pdf b/documentation/latex/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.pdf deleted file mode 100644 index 510a813..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4bef64b34cbff3922848c7a93aa21e46_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.md5 b/documentation/latex/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.md5 deleted file mode 100644 index b324ec7..0000000 --- a/documentation/latex/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0a670d125eb61b2552f359b7be57962f \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.pdf b/documentation/latex/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.pdf deleted file mode 100644 index 6be5b79..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.md5 b/documentation/latex/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.md5 deleted file mode 100644 index e351199..0000000 --- a/documentation/latex/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d1a25d7a998c16cf5eb63a24a33b8534 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.pdf b/documentation/latex/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.pdf deleted file mode 100644 index 44b6758..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.md5 b/documentation/latex/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.md5 deleted file mode 100644 index 6e87169..0000000 --- a/documentation/latex/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0867ace3ab97625891f06c6270aad1fe \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.pdf b/documentation/latex/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.pdf deleted file mode 100644 index d2eb2a6..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.md5 b/documentation/latex/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.md5 deleted file mode 100644 index 50ea1ef..0000000 --- a/documentation/latex/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e72345bd8302a68baa1feb0156514ba6 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.pdf b/documentation/latex/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.pdf deleted file mode 100644 index 66795bd..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4d6832a3c0b2b4014e28145e6ffe9c2c_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.md5 b/documentation/latex/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.md5 deleted file mode 100644 index 4fbe521..0000000 --- a/documentation/latex/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4d1bf06ea0edd089d58be389b3f72ee5 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.pdf b/documentation/latex/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.pdf deleted file mode 100644 index faec7e6..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.md5 b/documentation/latex/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.md5 deleted file mode 100644 index 7c1813b..0000000 --- a/documentation/latex/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2bbce0cb8e90ff2b0d87eaa5cd5bde03 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.pdf b/documentation/latex/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.pdf deleted file mode 100644 index ac2ee34..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4f007dd431f10e741414d197bb4926c3_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.md5 b/documentation/latex/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.md5 deleted file mode 100644 index 0e08e67..0000000 --- a/documentation/latex/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8595550f7eaeeb128f863c09b34a3df3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.pdf b/documentation/latex/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.pdf deleted file mode 100644 index 64d8f4b..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4f12de628073f44b2a3fab2688cf1caf_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.md5 b/documentation/latex/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.md5 deleted file mode 100644 index 12d3ba1..0000000 --- a/documentation/latex/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -05100f4e1df7dd0127e60816ec0bd921 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.pdf b/documentation/latex/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.pdf deleted file mode 100644 index 13ecc56..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4f66045a0528a0c17c52421ea51612e7_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.md5 b/documentation/latex/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.md5 deleted file mode 100644 index 72011f9..0000000 --- a/documentation/latex/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6349ec1efa48dce1c02eefdea3e715a4 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.pdf b/documentation/latex/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.pdf deleted file mode 100644 index 835512c..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.md5 b/documentation/latex/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.md5 deleted file mode 100644 index c4a37c8..0000000 --- a/documentation/latex/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -35e329d860bde3d7815dd1b1fd4ffdb4 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.pdf b/documentation/latex/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.pdf deleted file mode 100644 index a2af016..0000000 Binary files a/documentation/latex/class_b_n_o08x_a4fdc39294922a9553d84cd96bdae4376_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.md5 b/documentation/latex/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.md5 deleted file mode 100644 index 5ce2ec2..0000000 --- a/documentation/latex/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9819ddb9761f4f23e5a170582bc41a23 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.pdf b/documentation/latex/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.pdf deleted file mode 100644 index 22cad3f..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.md5 b/documentation/latex/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.md5 deleted file mode 100644 index 510b47b..0000000 --- a/documentation/latex/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -be7355a14d4a295927c7c995f5b8218a \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.pdf b/documentation/latex/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.pdf deleted file mode 100644 index fcad9a0..0000000 Binary files a/documentation/latex/class_b_n_o08x_a51b360d795563b55559f11efb40be36a_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.md5 b/documentation/latex/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.md5 deleted file mode 100644 index 6ec7dce..0000000 --- a/documentation/latex/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e76bf030b487b605af663e29695c93d3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.pdf b/documentation/latex/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.pdf deleted file mode 100644 index aca5d5f..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.md5 b/documentation/latex/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.md5 deleted file mode 100644 index 369c89e..0000000 --- a/documentation/latex/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -32a154165e61f79ecc48d31a21cfa1f3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.pdf b/documentation/latex/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.pdf deleted file mode 100644 index 51f13cd..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.md5 b/documentation/latex/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.md5 deleted file mode 100644 index d33b841..0000000 --- a/documentation/latex/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2a42162c0b008d8385cee222bbb97d59 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.pdf b/documentation/latex/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.pdf deleted file mode 100644 index 2fec677..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5680148a41cb9cc96d1911150c46d2b8_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.md5 b/documentation/latex/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.md5 deleted file mode 100644 index 930f8bd..0000000 --- a/documentation/latex/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1ffd05dcff26d08e4c0fc327eb839ea5 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.pdf b/documentation/latex/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.pdf deleted file mode 100644 index 16943e5..0000000 Binary files a/documentation/latex/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.md5 b/documentation/latex/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.md5 deleted file mode 100644 index 06f3ac3..0000000 --- a/documentation/latex/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d100671f7c7c1ad33d6e3f38f43b6e11 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.pdf b/documentation/latex/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.pdf deleted file mode 100644 index 3fb2a34..0000000 Binary files a/documentation/latex/class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.md5 b/documentation/latex/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.md5 deleted file mode 100644 index 755dbbc..0000000 --- a/documentation/latex/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6e13792da9f329eaf4e54d1fb48e4b66 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.pdf b/documentation/latex/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.pdf deleted file mode 100644 index 89df977..0000000 Binary files a/documentation/latex/class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.md5 b/documentation/latex/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.md5 deleted file mode 100644 index c670373..0000000 --- a/documentation/latex/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d0151afb4ac617d851d1e02d3bf60111 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.pdf b/documentation/latex/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.pdf deleted file mode 100644 index cc63a11..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.md5 b/documentation/latex/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.md5 deleted file mode 100644 index 819a6c0..0000000 --- a/documentation/latex/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -90da98b84116f083e73944e8eeea7fed \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.pdf b/documentation/latex/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.pdf deleted file mode 100644 index f2d63f6..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5a0b0f5b8e962247a3b8aee8f1dc8e9f_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.md5 b/documentation/latex/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.md5 deleted file mode 100644 index 0f3605c..0000000 --- a/documentation/latex/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b0840e7cc5c9d2427511239fc61d4d7e \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.pdf b/documentation/latex/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.pdf deleted file mode 100644 index 80cef36..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.md5 b/documentation/latex/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.md5 deleted file mode 100644 index 180512f..0000000 --- a/documentation/latex/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -474f2e385ed0ff9fbfd0815a8ce05d56 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.pdf b/documentation/latex/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.pdf deleted file mode 100644 index 5eae0b9..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.md5 b/documentation/latex/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.md5 deleted file mode 100644 index da26e50..0000000 --- a/documentation/latex/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7c87f1c45f543ade82bb944ff811149e \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.pdf b/documentation/latex/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.pdf deleted file mode 100644 index e7d4559..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5adc21b484ff98c42622e2ad9871d5a0_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.md5 b/documentation/latex/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.md5 deleted file mode 100644 index ceee714..0000000 --- a/documentation/latex/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e7e045c79ae6fe1f4e54254787831b88 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.pdf b/documentation/latex/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.pdf deleted file mode 100644 index 426b89a..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.md5 b/documentation/latex/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.md5 deleted file mode 100644 index b0323f0..0000000 --- a/documentation/latex/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -bc0e8dac6cf2ef1778db63d095f06ab5 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.pdf b/documentation/latex/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.pdf deleted file mode 100644 index 9bee213..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5cc58139e4d5f0587b90e249ceb476f9_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.md5 b/documentation/latex/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.md5 deleted file mode 100644 index 162a8ad..0000000 --- a/documentation/latex/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -72f39c14bca05f3875ed184dec7f7c99 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.pdf b/documentation/latex/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.pdf deleted file mode 100644 index ff3ae0f..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5d3ed8a44a34553cf5239cdd4032e725_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.md5 b/documentation/latex/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.md5 deleted file mode 100644 index ed64d27..0000000 --- a/documentation/latex/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a9e3002d94d1a78d4c80fb1b9cb311ba \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.pdf b/documentation/latex/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.pdf deleted file mode 100644 index 0171de8..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.md5 b/documentation/latex/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.md5 deleted file mode 100644 index 1f322bc..0000000 --- a/documentation/latex/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -11958af2c75ce14d1c69ed2ecbd00f7c \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.pdf b/documentation/latex/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.pdf deleted file mode 100644 index 65ed53c..0000000 Binary files a/documentation/latex/class_b_n_o08x_a5e63a9e68dbe2968b37dcb6dae04de6f_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.md5 b/documentation/latex/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.md5 deleted file mode 100644 index 5a9e026..0000000 --- a/documentation/latex/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -03d71ec809fac22910e8769b7d5f8275 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.pdf b/documentation/latex/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.pdf deleted file mode 100644 index b8b2849..0000000 Binary files a/documentation/latex/class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.md5 b/documentation/latex/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.md5 deleted file mode 100644 index 62d2fea..0000000 --- a/documentation/latex/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -117f43ef6e5c084a8e874f2cae868928 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.pdf b/documentation/latex/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.pdf deleted file mode 100644 index 789138e..0000000 Binary files a/documentation/latex/class_b_n_o08x_a62c570ba96512f4d0d10b2594048de1f_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.md5 b/documentation/latex/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.md5 deleted file mode 100644 index d228ded..0000000 --- a/documentation/latex/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9675e2dba8817d6a09a8217d6d1af778 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.pdf b/documentation/latex/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.pdf deleted file mode 100644 index be55683..0000000 Binary files a/documentation/latex/class_b_n_o08x_a62d634fc9bced0197103f2973f27bae2_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.md5 b/documentation/latex/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.md5 deleted file mode 100644 index 4bbc4ef..0000000 --- a/documentation/latex/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -50b0d50f5bee0e44a17732e5c19451d0 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.pdf b/documentation/latex/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.pdf deleted file mode 100644 index 905b15f..0000000 Binary files a/documentation/latex/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.md5 b/documentation/latex/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.md5 deleted file mode 100644 index 70593e0..0000000 --- a/documentation/latex/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4a9f4822831dc1672ce029888cacfdc6 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.pdf b/documentation/latex/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.pdf deleted file mode 100644 index 0766899..0000000 Binary files a/documentation/latex/class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.md5 b/documentation/latex/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.md5 deleted file mode 100644 index 5681d26..0000000 --- a/documentation/latex/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3a72c3f181b871dada65ba5b83b61382 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.pdf b/documentation/latex/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.pdf deleted file mode 100644 index 19faa02..0000000 Binary files a/documentation/latex/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.md5 b/documentation/latex/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.md5 deleted file mode 100644 index 5cc57ea..0000000 --- a/documentation/latex/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3c40e9720d8297ca9d4f5b26f48adfd4 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.pdf b/documentation/latex/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.pdf deleted file mode 100644 index a17255d..0000000 Binary files a/documentation/latex/class_b_n_o08x_a6671b082d20dda8bf5c53cb47db0c338_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.md5 b/documentation/latex/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.md5 deleted file mode 100644 index 7cc6cff..0000000 --- a/documentation/latex/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2e6c0b6c47adab55c04b6d780dd54b69 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.pdf b/documentation/latex/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.pdf deleted file mode 100644 index c693b7a..0000000 Binary files a/documentation/latex/class_b_n_o08x_a687eee44d68e1bcabce04780d7eb5fb9_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.md5 b/documentation/latex/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.md5 deleted file mode 100644 index 2c26530..0000000 --- a/documentation/latex/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2f11b143ea530f593ed970e98e0a5720 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.pdf b/documentation/latex/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.pdf deleted file mode 100644 index 7067c7f..0000000 Binary files a/documentation/latex/class_b_n_o08x_a69b3255550345bcb2d302476d50e38a5_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.md5 b/documentation/latex/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.md5 deleted file mode 100644 index 389b07e..0000000 --- a/documentation/latex/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fc5c3ea53befc9f6ac944cc567864c37 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.pdf b/documentation/latex/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.pdf deleted file mode 100644 index d587be2..0000000 Binary files a/documentation/latex/class_b_n_o08x_a69f768318a621a7dc6620e5551926c3b_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.md5 b/documentation/latex/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.md5 deleted file mode 100644 index a707870..0000000 --- a/documentation/latex/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5d7009e2725ea7d743a0d4ec6c262bf1 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.pdf b/documentation/latex/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.pdf deleted file mode 100644 index ac554ca..0000000 Binary files a/documentation/latex/class_b_n_o08x_a6cd96063eeac75af5f292bdcd31972ce_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.md5 b/documentation/latex/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.md5 deleted file mode 100644 index 32782a0..0000000 --- a/documentation/latex/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -125deb8bc678430f7981bce9b313ee05 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.pdf b/documentation/latex/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.pdf deleted file mode 100644 index 7fd015d..0000000 Binary files a/documentation/latex/class_b_n_o08x_a6ddc9600c53a4248d1affcab36f6f245_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.md5 b/documentation/latex/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.md5 deleted file mode 100644 index 9ac9ad7..0000000 --- a/documentation/latex/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9ae6d4888bb5c31ef98a0d6ec40ed5f3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.pdf b/documentation/latex/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.pdf deleted file mode 100644 index 220b363..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.md5 b/documentation/latex/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.md5 deleted file mode 100644 index c0ae042..0000000 --- a/documentation/latex/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b3edf734732accf3536b55b64dedc3cf \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.pdf b/documentation/latex/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.pdf deleted file mode 100644 index 48c7356..0000000 Binary files a/documentation/latex/class_b_n_o08x_a71bbcd4b4d63d55d4f7d5f0de6154486_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.md5 b/documentation/latex/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.md5 deleted file mode 100644 index 686eaea..0000000 --- a/documentation/latex/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a645c264b1c25b5c775d2eb14b7fb1f7 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.pdf b/documentation/latex/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.pdf deleted file mode 100644 index 31afb15..0000000 Binary files a/documentation/latex/class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.md5 b/documentation/latex/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.md5 deleted file mode 100644 index e5813e3..0000000 --- a/documentation/latex/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -eec4ce960ae9cde36c52362db5860820 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.pdf b/documentation/latex/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.pdf deleted file mode 100644 index bba7584..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.md5 b/documentation/latex/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.md5 deleted file mode 100644 index 362841c..0000000 --- a/documentation/latex/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fd7e5c0697829cdbc898f1415c1e613b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.pdf b/documentation/latex/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.pdf deleted file mode 100644 index d65a3f0..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7388c67de3906ad05b233fd7eff0514d_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.md5 b/documentation/latex/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.md5 deleted file mode 100644 index 454bbe3..0000000 --- a/documentation/latex/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -90ec0e445e97fb8f79328b3cf0cf8cf8 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.pdf b/documentation/latex/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.pdf deleted file mode 100644 index 8bd156d..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7416d844f6188c8d16f181d6d4431708_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.md5 b/documentation/latex/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.md5 deleted file mode 100644 index d20e44a..0000000 --- a/documentation/latex/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -93d0850c128a1921c66cc675c1aebfbc \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.pdf b/documentation/latex/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.pdf deleted file mode 100644 index 28d2036..0000000 Binary files a/documentation/latex/class_b_n_o08x_a74725517129dd548c7a3de705d5861bd_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.md5 b/documentation/latex/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.md5 deleted file mode 100644 index 4f7bd90..0000000 --- a/documentation/latex/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -28e6465c9209f1804fce2a994dffa705 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.pdf b/documentation/latex/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.pdf deleted file mode 100644 index 6d68223..0000000 Binary files a/documentation/latex/class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.md5 b/documentation/latex/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.md5 deleted file mode 100644 index fb66cef..0000000 --- a/documentation/latex/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ac6f3f4e78f366b1c44b864cc51e8789 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.pdf b/documentation/latex/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.pdf deleted file mode 100644 index 20d8774..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.md5 b/documentation/latex/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.md5 deleted file mode 100644 index 5d38562..0000000 --- a/documentation/latex/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -98679309b9729aa529ddaa8208e6dbdd \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.pdf b/documentation/latex/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.pdf deleted file mode 100644 index 8c91ea3..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7665cce95e791c89161ec863f49c0392_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.md5 b/documentation/latex/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.md5 deleted file mode 100644 index d046daf..0000000 --- a/documentation/latex/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8c07932983dcbcb025f255c051374e65 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.pdf b/documentation/latex/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.pdf deleted file mode 100644 index 5a9cc66..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7710e8bee76742e351cecfaf441f0889_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.md5 b/documentation/latex/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.md5 deleted file mode 100644 index 77c7112..0000000 --- a/documentation/latex/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9c4ff17e6ba40cea85652ea34774b2de \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.pdf b/documentation/latex/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.pdf deleted file mode 100644 index e6afc21..0000000 Binary files a/documentation/latex/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.md5 b/documentation/latex/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.md5 deleted file mode 100644 index 597bd2b..0000000 --- a/documentation/latex/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ddaa01d0cff8c862e4cc3933baacdeba \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.pdf b/documentation/latex/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.pdf deleted file mode 100644 index c35d13d..0000000 Binary files a/documentation/latex/class_b_n_o08x_a789f9b9b8ad0a84a6ca45a85740823ca_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.md5 b/documentation/latex/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.md5 deleted file mode 100644 index a25c456..0000000 --- a/documentation/latex/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ca9b88f556b698a8593bca640ff6bffd \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.pdf b/documentation/latex/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.pdf deleted file mode 100644 index e97d3be..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.md5 b/documentation/latex/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.md5 deleted file mode 100644 index 14bf315..0000000 --- a/documentation/latex/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ee7f1f33f919e5dbbc81ab7755cbb3b9 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.pdf b/documentation/latex/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.pdf deleted file mode 100644 index 580edae..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7be6047fef851a064c7cbc9eba092f6d_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.md5 b/documentation/latex/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.md5 deleted file mode 100644 index 21d915c..0000000 --- a/documentation/latex/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -90066997e2a116078431d47bba1cf628 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.pdf b/documentation/latex/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.pdf deleted file mode 100644 index 3652a53..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7c7a74367db26ea8bfbdea633ee1d654_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.md5 b/documentation/latex/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.md5 deleted file mode 100644 index 8f8fbee..0000000 --- a/documentation/latex/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a2018f1946908453f4c55961ee3d8801 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.pdf b/documentation/latex/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.pdf deleted file mode 100644 index 3c13ae1..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7cdeb849e728487de961cdfd4030c773_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.md5 b/documentation/latex/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.md5 deleted file mode 100644 index 155967c..0000000 --- a/documentation/latex/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2a5421da0eb87f254e38a90365b3b896 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.pdf b/documentation/latex/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.pdf deleted file mode 100644 index 7d71992..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.md5 b/documentation/latex/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.md5 deleted file mode 100644 index 153a011..0000000 --- a/documentation/latex/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a2cf7e8bd3f8683e631359c98f4514eb \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.pdf b/documentation/latex/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.pdf deleted file mode 100644 index 384f578..0000000 Binary files a/documentation/latex/class_b_n_o08x_a7fe5de95b1f51da44247a87317fd0c75_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.md5 b/documentation/latex/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.md5 deleted file mode 100644 index 73e59e6..0000000 --- a/documentation/latex/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -cfd15030dfa039586a06db63b1574c74 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.pdf b/documentation/latex/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.pdf deleted file mode 100644 index e7c12d0..0000000 Binary files a/documentation/latex/class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.md5 b/documentation/latex/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.md5 deleted file mode 100644 index 9c51e8f..0000000 --- a/documentation/latex/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4ecd50ea17019f1b03afce5966c444ee \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.pdf b/documentation/latex/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.pdf deleted file mode 100644 index 6562286..0000000 Binary files a/documentation/latex/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.md5 b/documentation/latex/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.md5 deleted file mode 100644 index 97065eb..0000000 --- a/documentation/latex/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8d44f99fcc7b735fadf97b33b22d0d9b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.pdf b/documentation/latex/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.pdf deleted file mode 100644 index 7d324ef..0000000 Binary files a/documentation/latex/class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.md5 b/documentation/latex/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.md5 deleted file mode 100644 index 074922c..0000000 --- a/documentation/latex/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4bf6ac81b9364a952a5d3c9d0867f22e \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.pdf b/documentation/latex/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.pdf deleted file mode 100644 index 0947cc2..0000000 Binary files a/documentation/latex/class_b_n_o08x_a83fed63c67957ec4338afd43087d6e22_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.md5 b/documentation/latex/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.md5 deleted file mode 100644 index f73b5a7..0000000 --- a/documentation/latex/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1232452b146c6a5e0dbddf845ff76257 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.pdf b/documentation/latex/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.pdf deleted file mode 100644 index af1ad44..0000000 Binary files a/documentation/latex/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.md5 b/documentation/latex/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.md5 deleted file mode 100644 index a725643..0000000 --- a/documentation/latex/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4636e184198bc7675115525efcffde06 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.pdf b/documentation/latex/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.pdf deleted file mode 100644 index aca742f..0000000 Binary files a/documentation/latex/class_b_n_o08x_a86ff710f2b359e905c7154bfb7d5b104_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.md5 b/documentation/latex/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.md5 deleted file mode 100644 index 0689a77..0000000 --- a/documentation/latex/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -61bc4e5e087d9c784aa8f1de4845170c \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.pdf b/documentation/latex/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.pdf deleted file mode 100644 index 84a5691..0000000 Binary files a/documentation/latex/class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.md5 b/documentation/latex/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.md5 deleted file mode 100644 index 1e533d4..0000000 --- a/documentation/latex/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -23ccade64b2e51df86c12d13dc1c1678 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.pdf b/documentation/latex/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.pdf deleted file mode 100644 index 7186bcd..0000000 Binary files a/documentation/latex/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.md5 b/documentation/latex/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.md5 deleted file mode 100644 index f0813e2..0000000 --- a/documentation/latex/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0599804fcef63b981e93cb00737708ed \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.pdf b/documentation/latex/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.pdf deleted file mode 100644 index a2e6d17..0000000 Binary files a/documentation/latex/class_b_n_o08x_a89618eba08186ee8e679e7313907ddef_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.md5 b/documentation/latex/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.md5 deleted file mode 100644 index f2b5e1d..0000000 --- a/documentation/latex/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -05126c0256e4d8ffda34d85afc120a49 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.pdf b/documentation/latex/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.pdf deleted file mode 100644 index d94363b..0000000 Binary files a/documentation/latex/class_b_n_o08x_a8a36db7f1c932f33e05e494632059801_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.md5 b/documentation/latex/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.md5 deleted file mode 100644 index 41e3e7b..0000000 --- a/documentation/latex/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a3496c222c9396918b3c5416e47c13b6 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.pdf b/documentation/latex/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.pdf deleted file mode 100644 index 4034640..0000000 Binary files a/documentation/latex/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.md5 b/documentation/latex/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.md5 deleted file mode 100644 index 474b191..0000000 --- a/documentation/latex/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -345a9de9aca7952d5afc7015da0fe8e0 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.pdf b/documentation/latex/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.pdf deleted file mode 100644 index 78ccb14..0000000 Binary files a/documentation/latex/class_b_n_o08x_a8a5f3b985989e846e831f70f7733d0bc_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.md5 b/documentation/latex/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.md5 deleted file mode 100644 index 730663e..0000000 --- a/documentation/latex/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9d6ffa794e95d37fa429b044c2998199 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.pdf b/documentation/latex/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.pdf deleted file mode 100644 index 744a96e..0000000 Binary files a/documentation/latex/class_b_n_o08x_a8be135ed41646199540583b29806d4e5_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.md5 b/documentation/latex/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.md5 deleted file mode 100644 index 56ad6b6..0000000 --- a/documentation/latex/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3868d9455a1dacb5c483a25bb1969b03 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.pdf b/documentation/latex/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.pdf deleted file mode 100644 index 511a8f3..0000000 Binary files a/documentation/latex/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.md5 b/documentation/latex/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.md5 deleted file mode 100644 index a20e046..0000000 --- a/documentation/latex/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e39685835a1ee00ba9913dea40d36bc3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.pdf b/documentation/latex/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.pdf deleted file mode 100644 index aa14e8c..0000000 Binary files a/documentation/latex/class_b_n_o08x_a8d9db3e1b6208c2661e1c543deefa53d_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.md5 b/documentation/latex/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.md5 deleted file mode 100644 index 4e7c448..0000000 --- a/documentation/latex/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -aab6fded1bb38684117b1cd61c1bfb1b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.pdf b/documentation/latex/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.pdf deleted file mode 100644 index b02664f..0000000 Binary files a/documentation/latex/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.md5 b/documentation/latex/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.md5 deleted file mode 100644 index 54b2f3f..0000000 --- a/documentation/latex/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d4b9e239b043510ea6055ab94fd55794 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.pdf b/documentation/latex/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.pdf deleted file mode 100644 index 07bf049..0000000 Binary files a/documentation/latex/class_b_n_o08x_a8d9f28d8857279a3c4b1f62f6dabb638_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.md5 b/documentation/latex/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.md5 deleted file mode 100644 index 5792e04..0000000 --- a/documentation/latex/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d253d336ff9971a0e9282dc501dda2c4 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.pdf b/documentation/latex/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.pdf deleted file mode 100644 index d440196..0000000 Binary files a/documentation/latex/class_b_n_o08x_a8de12c9c47549502147bd85dbb7e364e_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.md5 b/documentation/latex/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.md5 deleted file mode 100644 index e923b6b..0000000 --- a/documentation/latex/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9db8bc9a5e8865d673883314fa940274 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.pdf b/documentation/latex/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.pdf deleted file mode 100644 index 2ed155d..0000000 Binary files a/documentation/latex/class_b_n_o08x_a8f34d5475474f00ae6a92f73c1fe14e4_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.md5 b/documentation/latex/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.md5 deleted file mode 100644 index 03a4b68..0000000 --- a/documentation/latex/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1c81be56c6b0dbb8402855575fe249f0 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.pdf b/documentation/latex/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.pdf deleted file mode 100644 index c885bf5..0000000 Binary files a/documentation/latex/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.md5 b/documentation/latex/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.md5 deleted file mode 100644 index 2713197..0000000 --- a/documentation/latex/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -09c8eafd18a5e7b7f42d6847f0fc1ffe \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.pdf b/documentation/latex/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.pdf deleted file mode 100644 index 2205c67..0000000 Binary files a/documentation/latex/class_b_n_o08x_a8f4a10a8427a266fa28fc1c85c8e850f_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.md5 b/documentation/latex/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.md5 deleted file mode 100644 index 20fc869..0000000 --- a/documentation/latex/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -02724dddee5183f634bb16aad7188fb1 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.pdf b/documentation/latex/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.pdf deleted file mode 100644 index 4a61850..0000000 Binary files a/documentation/latex/class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.md5 b/documentation/latex/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.md5 deleted file mode 100644 index bf3541b..0000000 --- a/documentation/latex/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -bde6972a95c5ac5914de40e3d7f6dbe9 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.pdf b/documentation/latex/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.pdf deleted file mode 100644 index 243d237..0000000 Binary files a/documentation/latex/class_b_n_o08x_a962b695ef4733d558c6f9684da0931ab_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.md5 b/documentation/latex/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.md5 deleted file mode 100644 index b9ad28c..0000000 --- a/documentation/latex/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f21ad58f5f8855a904c21fc9ef086cf7 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.pdf b/documentation/latex/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.pdf deleted file mode 100644 index d6a6a0e..0000000 Binary files a/documentation/latex/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.md5 b/documentation/latex/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.md5 deleted file mode 100644 index f7c15ac..0000000 --- a/documentation/latex/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -296c1431e2986ff138823538142e52a6 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.pdf b/documentation/latex/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.pdf deleted file mode 100644 index 7b59bfb..0000000 Binary files a/documentation/latex/class_b_n_o08x_a96d47dd0f9aedfbe3f731f8ae76b2e85_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.md5 b/documentation/latex/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.md5 deleted file mode 100644 index 40b43e3..0000000 --- a/documentation/latex/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2169324e0eb9ef0a516be65b511cb103 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.pdf b/documentation/latex/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.pdf deleted file mode 100644 index 3a59630..0000000 Binary files a/documentation/latex/class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.md5 b/documentation/latex/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.md5 deleted file mode 100644 index 6f15c93..0000000 --- a/documentation/latex/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c893beeae54e982fd59e194e8120dbe9 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.pdf b/documentation/latex/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.pdf deleted file mode 100644 index f060a60..0000000 Binary files a/documentation/latex/class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.md5 b/documentation/latex/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.md5 deleted file mode 100644 index 5b08258..0000000 --- a/documentation/latex/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2ad29d7afe04967f68dfe32d639a1fba \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.pdf b/documentation/latex/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.pdf deleted file mode 100644 index 9eefc81..0000000 Binary files a/documentation/latex/class_b_n_o08x_a9d96108b0f5b1e1e1ac431bc993ca758_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.md5 b/documentation/latex/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.md5 deleted file mode 100644 index 157d4d0..0000000 --- a/documentation/latex/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c285fd500df33aed55b6ad224f4d6143 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.pdf b/documentation/latex/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.pdf deleted file mode 100644 index 46729e9..0000000 Binary files a/documentation/latex/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.md5 b/documentation/latex/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.md5 deleted file mode 100644 index ccd8cf7..0000000 --- a/documentation/latex/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3450c11c335592e8ff9a853f5390955d \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.pdf b/documentation/latex/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.pdf deleted file mode 100644 index 920c6c1..0000000 Binary files a/documentation/latex/class_b_n_o08x_a9e72a094c4469c9eb9fb766744560c53_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.md5 b/documentation/latex/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.md5 deleted file mode 100644 index c953891..0000000 --- a/documentation/latex/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3ed99abf14c810563ce4a80447ffc2ae \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.pdf b/documentation/latex/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.pdf deleted file mode 100644 index 9932561..0000000 Binary files a/documentation/latex/class_b_n_o08x_a9ee7e73f695af8965a9ede50136d5a8c_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.md5 b/documentation/latex/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.md5 deleted file mode 100644 index e7ed0a0..0000000 --- a/documentation/latex/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a2777e4c6e9d1782aebd42df65dd58e8 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.pdf b/documentation/latex/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.pdf deleted file mode 100644 index 4ae78ea..0000000 Binary files a/documentation/latex/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.md5 b/documentation/latex/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.md5 deleted file mode 100644 index 820549e..0000000 --- a/documentation/latex/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2e0654b0c4f7d73ff3e0a0e7dc527f97 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.pdf b/documentation/latex/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.pdf deleted file mode 100644 index e1d7a52..0000000 Binary files a/documentation/latex/class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.md5 b/documentation/latex/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.md5 deleted file mode 100644 index 9e07b9b..0000000 --- a/documentation/latex/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -47224a4d2f2e6ffbd01a253c83d4059b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.pdf b/documentation/latex/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.pdf deleted file mode 100644 index c61f919..0000000 Binary files a/documentation/latex/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.md5 b/documentation/latex/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.md5 deleted file mode 100644 index 93322ff..0000000 --- a/documentation/latex/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b854dffbce0bf35e23f0883e31aec687 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.pdf b/documentation/latex/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.pdf deleted file mode 100644 index d975889..0000000 Binary files a/documentation/latex/class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.md5 b/documentation/latex/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.md5 deleted file mode 100644 index e42f314..0000000 --- a/documentation/latex/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -23056154a2a00e23e81d2d1e38697b08 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.pdf b/documentation/latex/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.pdf deleted file mode 100644 index b00b72e..0000000 Binary files a/documentation/latex/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.md5 b/documentation/latex/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.md5 deleted file mode 100644 index b41dade..0000000 --- a/documentation/latex/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e55caed8a82da680b516057796490b37 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.pdf b/documentation/latex/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.pdf deleted file mode 100644 index a31f858..0000000 Binary files a/documentation/latex/class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.md5 b/documentation/latex/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.md5 deleted file mode 100644 index 0a9e9ac..0000000 --- a/documentation/latex/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -440b6682a0343004b4f3275ec2e7cc40 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.pdf b/documentation/latex/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.pdf deleted file mode 100644 index 9c79105..0000000 Binary files a/documentation/latex/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.md5 b/documentation/latex/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.md5 deleted file mode 100644 index f2ef8a9..0000000 --- a/documentation/latex/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -bc4c840b007602689cd1be9295fdd811 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.pdf b/documentation/latex/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.pdf deleted file mode 100644 index a47da55..0000000 Binary files a/documentation/latex/class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.md5 b/documentation/latex/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.md5 deleted file mode 100644 index d3e07c4..0000000 --- a/documentation/latex/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -03b552f33daab541a2220f9e40c7979e \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.pdf b/documentation/latex/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.pdf deleted file mode 100644 index 1261b7b..0000000 Binary files a/documentation/latex/class_b_n_o08x_aa309152750686fbf8ebf7d6de1f1254b_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.md5 b/documentation/latex/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.md5 deleted file mode 100644 index 5318f5a..0000000 --- a/documentation/latex/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b06203cbaa00272235eca10756163b67 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.pdf b/documentation/latex/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.pdf deleted file mode 100644 index 520b345..0000000 Binary files a/documentation/latex/class_b_n_o08x_aa390bf840246e3233e07f6a424efcb6f_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.md5 b/documentation/latex/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.md5 deleted file mode 100644 index a1809e3..0000000 --- a/documentation/latex/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -cd122d35972a11e58a9881a185da45b2 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.pdf b/documentation/latex/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.pdf deleted file mode 100644 index b139990..0000000 Binary files a/documentation/latex/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.md5 b/documentation/latex/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.md5 deleted file mode 100644 index ef56262..0000000 --- a/documentation/latex/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -48e9267d55b19a52e1c739bef4486c2a \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.pdf b/documentation/latex/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.pdf deleted file mode 100644 index 9172855..0000000 Binary files a/documentation/latex/class_b_n_o08x_aa59e3d8953c96dc1cc5958a1ac628df4_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.md5 b/documentation/latex/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.md5 deleted file mode 100644 index fc4c013..0000000 --- a/documentation/latex/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -bfe4757a00409b9458ed314bc57bdeaf \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.pdf b/documentation/latex/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.pdf deleted file mode 100644 index 892f064..0000000 Binary files a/documentation/latex/class_b_n_o08x_aa5b483cb0036e9dd43bf797259634add_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.md5 b/documentation/latex/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.md5 deleted file mode 100644 index 7d4f481..0000000 --- a/documentation/latex/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -bca0ec6e94c8297753f429e3287d3427 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.pdf b/documentation/latex/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.pdf deleted file mode 100644 index cbd6a82..0000000 Binary files a/documentation/latex/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.md5 b/documentation/latex/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.md5 deleted file mode 100644 index 31b9ddf..0000000 --- a/documentation/latex/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -db964e3ec34cf1bd88d2dde95afd3986 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.pdf b/documentation/latex/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.pdf deleted file mode 100644 index eb44fd1..0000000 Binary files a/documentation/latex/class_b_n_o08x_aa9291dec6c05a3786fe58221e6856e8f_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.md5 b/documentation/latex/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.md5 deleted file mode 100644 index 6bf7b93..0000000 --- a/documentation/latex/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -38ab95b73a83b03f0bd22ff978b265ca \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.pdf b/documentation/latex/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.pdf deleted file mode 100644 index b731801..0000000 Binary files a/documentation/latex/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.md5 b/documentation/latex/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.md5 deleted file mode 100644 index 7610f6b..0000000 --- a/documentation/latex/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6098cfde91bc4e58d0f440f4aaa1a5e1 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.pdf b/documentation/latex/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.pdf deleted file mode 100644 index 8e537ef..0000000 Binary files a/documentation/latex/class_b_n_o08x_aac0a00bed7825d8a2c357a48c3626931_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.md5 b/documentation/latex/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.md5 deleted file mode 100644 index f5e7fb1..0000000 --- a/documentation/latex/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -109b55388b51ffeb286a10d606dd04b1 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.pdf b/documentation/latex/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.pdf deleted file mode 100644 index 9108e39..0000000 Binary files a/documentation/latex/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.md5 b/documentation/latex/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.md5 deleted file mode 100644 index 826b672..0000000 --- a/documentation/latex/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -80cad08734ee3f7c2b2fa3d3ea10061b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.pdf b/documentation/latex/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.pdf deleted file mode 100644 index 2865117..0000000 Binary files a/documentation/latex/class_b_n_o08x_aaf28212a5f1960c62a73282976142cfc_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.md5 b/documentation/latex/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.md5 deleted file mode 100644 index 4ca67a3..0000000 --- a/documentation/latex/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fe3413c05fc8c54861e4651422c794b5 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.pdf b/documentation/latex/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.pdf deleted file mode 100644 index 931c013..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab02386f13caa446bab5921c1a71f92ab_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.md5 b/documentation/latex/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.md5 deleted file mode 100644 index 8eacf98..0000000 --- a/documentation/latex/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2b50ef3362d37bc03c592b9004498483 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.pdf b/documentation/latex/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.pdf deleted file mode 100644 index 674e9ed..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.md5 b/documentation/latex/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.md5 deleted file mode 100644 index ea0bb9f..0000000 --- a/documentation/latex/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -dbad4dc95f4c5ed00c911e87d0a052c2 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.pdf b/documentation/latex/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.pdf deleted file mode 100644 index cb05718..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab0a60844b36fb140cad588a65b3a9655_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.md5 b/documentation/latex/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.md5 deleted file mode 100644 index 67d326b..0000000 --- a/documentation/latex/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -cb549506cf2b72eb24953da74827dfd3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.pdf b/documentation/latex/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.pdf deleted file mode 100644 index b96e4a1..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab132a061bd437fd109225446aa1f6010_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.md5 b/documentation/latex/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.md5 deleted file mode 100644 index d3790b8..0000000 --- a/documentation/latex/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b3e55416e313416c700e1ee43f5b8518 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.pdf b/documentation/latex/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.pdf deleted file mode 100644 index c6dfe10..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.md5 b/documentation/latex/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.md5 deleted file mode 100644 index 4136509..0000000 --- a/documentation/latex/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ec9882082c6c3146d1c10a9a3b341712 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.pdf b/documentation/latex/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.pdf deleted file mode 100644 index a40e760..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab187fe50fcfbb04bec9e80eb0fccf61c_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.md5 b/documentation/latex/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.md5 deleted file mode 100644 index c603537..0000000 --- a/documentation/latex/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -384464d9c04dbe92abde5098b894b491 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.pdf b/documentation/latex/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.pdf deleted file mode 100644 index 81681e0..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.md5 b/documentation/latex/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.md5 deleted file mode 100644 index e995658..0000000 --- a/documentation/latex/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ade7ce07eeab4aabce3544d1ce90fd53 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.pdf b/documentation/latex/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.pdf deleted file mode 100644 index fb6ce8f..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab307ed3352e04c9e998ab4dd066f8932_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.md5 b/documentation/latex/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.md5 deleted file mode 100644 index c5311e6..0000000 --- a/documentation/latex/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8baebc4729d7226bc49adfbb9e04a0d8 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.pdf b/documentation/latex/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.pdf deleted file mode 100644 index 3a0293a..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.md5 b/documentation/latex/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.md5 deleted file mode 100644 index 8dfdf70..0000000 --- a/documentation/latex/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f52bc1a3a3ede578879bb9754998f83d \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.pdf b/documentation/latex/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.pdf deleted file mode 100644 index cf5c36b..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab4373e9b87837ea9fcbc0b536338c7b8_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.md5 b/documentation/latex/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.md5 deleted file mode 100644 index f2db960..0000000 --- a/documentation/latex/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d74266cd42e0bc5151a6bf914837ec39 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.pdf b/documentation/latex/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.pdf deleted file mode 100644 index 317b80a..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.md5 b/documentation/latex/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.md5 deleted file mode 100644 index be12012..0000000 --- a/documentation/latex/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d89e91692dfb95972957faa7b0062558 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.pdf b/documentation/latex/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.pdf deleted file mode 100644 index 3c4903d..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab4c1d5cde156af09b7e88913f3af62c7_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.md5 b/documentation/latex/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.md5 deleted file mode 100644 index 6d75cd9..0000000 --- a/documentation/latex/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -07051878ecbc770df129c448fb06d9e6 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.pdf b/documentation/latex/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.pdf deleted file mode 100644 index 5f53a9a..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.md5 b/documentation/latex/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.md5 deleted file mode 100644 index 6386c33..0000000 --- a/documentation/latex/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b91a8a27c0eef80a78e9b34038e97102 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.pdf b/documentation/latex/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.pdf deleted file mode 100644 index 5cb4724..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.md5 b/documentation/latex/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.md5 deleted file mode 100644 index c17c803..0000000 --- a/documentation/latex/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -999409d2d64d5ae3fe34a3c245ac2b89 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.pdf b/documentation/latex/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.pdf deleted file mode 100644 index 6b6f7b1..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab4c8e37c730ddb168f78c29bd7ae6566_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.md5 b/documentation/latex/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.md5 deleted file mode 100644 index aa5401e..0000000 --- a/documentation/latex/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c9d294079da0ac4ede71f987d71e7ea4 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.pdf b/documentation/latex/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.pdf deleted file mode 100644 index 3f1b1bf..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.md5 b/documentation/latex/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.md5 deleted file mode 100644 index 8f89a90..0000000 --- a/documentation/latex/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -461c54513838b186b2b0399746427a30 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.pdf b/documentation/latex/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.pdf deleted file mode 100644 index 59a4629..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.md5 b/documentation/latex/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.md5 deleted file mode 100644 index 2ca664d..0000000 --- a/documentation/latex/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -957ff7b5951c8549c4a65a443835df38 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.pdf b/documentation/latex/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.pdf deleted file mode 100644 index 1da452e..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.md5 b/documentation/latex/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.md5 deleted file mode 100644 index b837110..0000000 --- a/documentation/latex/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -02db257db48570897dfe1a2149b79f9a \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.pdf b/documentation/latex/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.pdf deleted file mode 100644 index 57563d6..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.md5 b/documentation/latex/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.md5 deleted file mode 100644 index 2ff5248..0000000 --- a/documentation/latex/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2afe716a76a92e561d18501ece5480f5 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.pdf b/documentation/latex/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.pdf deleted file mode 100644 index ecd8a62..0000000 Binary files a/documentation/latex/class_b_n_o08x_ab6dc34d058002e21978f8a7e4cf24592_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.md5 b/documentation/latex/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.md5 deleted file mode 100644 index 0ac087e..0000000 --- a/documentation/latex/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b2633f9df2bcdaaf19276b4c6e250972 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.pdf b/documentation/latex/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.pdf deleted file mode 100644 index 797b691..0000000 Binary files a/documentation/latex/class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.md5 b/documentation/latex/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.md5 deleted file mode 100644 index facc6f8..0000000 --- a/documentation/latex/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b27af7cc12419305808d45f5ce5b985c \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.pdf b/documentation/latex/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.pdf deleted file mode 100644 index e6c1e45..0000000 Binary files a/documentation/latex/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.md5 b/documentation/latex/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.md5 deleted file mode 100644 index b8f61ce..0000000 --- a/documentation/latex/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -29840b69c0e934919ed57bceb51782b5 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.pdf b/documentation/latex/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.pdf deleted file mode 100644 index 6a59694..0000000 Binary files a/documentation/latex/class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.md5 b/documentation/latex/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.md5 deleted file mode 100644 index b08e7d5..0000000 --- a/documentation/latex/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -c609f6c9b80d96f486b7c02d8c05c77d \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.pdf b/documentation/latex/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.pdf deleted file mode 100644 index 2b8a218..0000000 Binary files a/documentation/latex/class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.md5 b/documentation/latex/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.md5 deleted file mode 100644 index b6fb0ba..0000000 --- a/documentation/latex/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -011c1425ea63924300c23c8d3ac7bb6c \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.pdf b/documentation/latex/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.pdf deleted file mode 100644 index 65ca817..0000000 Binary files a/documentation/latex/class_b_n_o08x_ac2118c4da6631d3b9806353ca2cbba27_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.md5 b/documentation/latex/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.md5 deleted file mode 100644 index 5d6491c..0000000 --- a/documentation/latex/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e94a140989a61df9312754c920b6fc46 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.pdf b/documentation/latex/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.pdf deleted file mode 100644 index f00f7c4..0000000 Binary files a/documentation/latex/class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.md5 b/documentation/latex/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.md5 deleted file mode 100644 index 603e106..0000000 --- a/documentation/latex/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f952a2b616b482c515642c09a6f2edfe \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.pdf b/documentation/latex/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.pdf deleted file mode 100644 index 2182b33..0000000 Binary files a/documentation/latex/class_b_n_o08x_ac75b7fb1a1b407d0888ea07d708831b1_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.md5 b/documentation/latex/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.md5 deleted file mode 100644 index 18b8d73..0000000 --- a/documentation/latex/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ee54d08c394f18d39f6e164a04e5791a \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.pdf b/documentation/latex/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.pdf deleted file mode 100644 index 6c9ecd2..0000000 Binary files a/documentation/latex/class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.md5 b/documentation/latex/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.md5 deleted file mode 100644 index 99d2f24..0000000 --- a/documentation/latex/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b533167545a2b5647af253cd2ad0d24f \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.pdf b/documentation/latex/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.pdf deleted file mode 100644 index 6cfc5a8..0000000 Binary files a/documentation/latex/class_b_n_o08x_acb246769719351e02bf2aff06d039475_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.md5 b/documentation/latex/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.md5 deleted file mode 100644 index 233c214..0000000 --- a/documentation/latex/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4c487b1b9bf9e913cd21918b1cb357a8 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.pdf b/documentation/latex/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.pdf deleted file mode 100644 index cecfe02..0000000 Binary files a/documentation/latex/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.md5 b/documentation/latex/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.md5 deleted file mode 100644 index a8f63e7..0000000 --- a/documentation/latex/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b88581f851c975ef6c3f70c4f4ca3955 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.pdf b/documentation/latex/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.pdf deleted file mode 100644 index 92bacd7..0000000 Binary files a/documentation/latex/class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.md5 b/documentation/latex/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.md5 deleted file mode 100644 index debe9c9..0000000 --- a/documentation/latex/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -ccb25fe3de76fabc7927d32b5a5d8bf0 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.pdf b/documentation/latex/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.pdf deleted file mode 100644 index f7059e5..0000000 Binary files a/documentation/latex/class_b_n_o08x_ad0b9e8f8d051798bb1da9b19598dbd64_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.md5 b/documentation/latex/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.md5 deleted file mode 100644 index 9eb95be..0000000 --- a/documentation/latex/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0b7cccfbedcef9c7e501c6e15a814fd4 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.pdf b/documentation/latex/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.pdf deleted file mode 100644 index 4a13de4..0000000 Binary files a/documentation/latex/class_b_n_o08x_ad0f0fec4e53029b4ba907414a36ac5ea_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.md5 b/documentation/latex/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.md5 deleted file mode 100644 index 6e72403..0000000 --- a/documentation/latex/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f904cb4bc17522f84382c1c6a042e691 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.pdf b/documentation/latex/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.pdf deleted file mode 100644 index 39db3fb..0000000 Binary files a/documentation/latex/class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.md5 b/documentation/latex/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.md5 deleted file mode 100644 index 23938be..0000000 --- a/documentation/latex/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -149da31311968758d99658cb43f7987c \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.pdf b/documentation/latex/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.pdf deleted file mode 100644 index 3e3aef8..0000000 Binary files a/documentation/latex/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.md5 b/documentation/latex/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.md5 deleted file mode 100644 index 5b0c1f2..0000000 --- a/documentation/latex/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8df6235260bffa86a3bcfc9edbc6ce48 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.pdf b/documentation/latex/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.pdf deleted file mode 100644 index 45b7cac..0000000 Binary files a/documentation/latex/class_b_n_o08x_ad5c991150895b80bee68c933059a4058_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.md5 b/documentation/latex/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.md5 deleted file mode 100644 index 097f744..0000000 --- a/documentation/latex/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5676fd679e87992ea1e8a30f7c74f7b1 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.pdf b/documentation/latex/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.pdf deleted file mode 100644 index 3547d73..0000000 Binary files a/documentation/latex/class_b_n_o08x_ad7de3999d4df19038e27c01f9b02010e_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.md5 b/documentation/latex/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.md5 deleted file mode 100644 index e04eb56..0000000 --- a/documentation/latex/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -705d99c2c8cd7ef0a78e98f93be5365b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.pdf b/documentation/latex/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.pdf deleted file mode 100644 index 48766ce..0000000 Binary files a/documentation/latex/class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.md5 b/documentation/latex/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.md5 deleted file mode 100644 index ebc6a8a..0000000 --- a/documentation/latex/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b826989a8fdf73fc9047243bee5884c3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.pdf b/documentation/latex/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.pdf deleted file mode 100644 index d23757e..0000000 Binary files a/documentation/latex/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.md5 b/documentation/latex/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.md5 deleted file mode 100644 index bba6e7d..0000000 --- a/documentation/latex/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -578a674d29e99e35da5ea45afb4801f6 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.pdf b/documentation/latex/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.pdf deleted file mode 100644 index a2d9242..0000000 Binary files a/documentation/latex/class_b_n_o08x_adf789e709ac1667656db757c8d559af9_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.md5 b/documentation/latex/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.md5 deleted file mode 100644 index 1b6ad59..0000000 --- a/documentation/latex/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e652ffcbe78f0fd7596ef8d5deb14d57 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.pdf b/documentation/latex/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.pdf deleted file mode 100644 index 676c1c9..0000000 Binary files a/documentation/latex/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.md5 b/documentation/latex/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.md5 deleted file mode 100644 index b88878d..0000000 --- a/documentation/latex/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9edb58084af524a57aea91a0ae3ae5c5 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.pdf b/documentation/latex/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.pdf deleted file mode 100644 index 78b4868..0000000 Binary files a/documentation/latex/class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.md5 b/documentation/latex/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.md5 deleted file mode 100644 index 49e3443..0000000 --- a/documentation/latex/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7237fe00bf54b3c155f495fe44315350 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.pdf b/documentation/latex/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.pdf deleted file mode 100644 index fcfb17d..0000000 Binary files a/documentation/latex/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.md5 b/documentation/latex/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.md5 deleted file mode 100644 index 337003c..0000000 --- a/documentation/latex/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -495bd20d98c5472dcfa6f2d698bd9e21 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.pdf b/documentation/latex/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.pdf deleted file mode 100644 index 6f97bdb..0000000 Binary files a/documentation/latex/class_b_n_o08x_ae1435b83ca83bc51b75f3303afe87f7b_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.md5 b/documentation/latex/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.md5 deleted file mode 100644 index f3ecb9e..0000000 --- a/documentation/latex/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -429a5dc96ae3dd2278816a3bace42435 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.pdf b/documentation/latex/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.pdf deleted file mode 100644 index 18d06bd..0000000 Binary files a/documentation/latex/class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.md5 b/documentation/latex/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.md5 deleted file mode 100644 index 8c2c4a4..0000000 --- a/documentation/latex/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a3e025ce8ebd1b96795128406479af6c \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.pdf b/documentation/latex/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.pdf deleted file mode 100644 index ac1185d..0000000 Binary files a/documentation/latex/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.md5 b/documentation/latex/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.md5 deleted file mode 100644 index f53cbad..0000000 --- a/documentation/latex/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -eac6919c047aef102b481a6c4ff8795b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.pdf b/documentation/latex/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.pdf deleted file mode 100644 index 3c8b876..0000000 Binary files a/documentation/latex/class_b_n_o08x_ae766248440e76fb26bbadc6ee0b54ddb_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.md5 b/documentation/latex/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.md5 deleted file mode 100644 index 10fea3a..0000000 --- a/documentation/latex/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0c0b7fd01456eeacac73d985e5381590 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.pdf b/documentation/latex/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.pdf deleted file mode 100644 index be536be..0000000 Binary files a/documentation/latex/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.md5 b/documentation/latex/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.md5 deleted file mode 100644 index 74b9967..0000000 --- a/documentation/latex/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -18f81d74dd74b692cb511f149c99fc5e \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.pdf b/documentation/latex/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.pdf deleted file mode 100644 index a5b6c25..0000000 Binary files a/documentation/latex/class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.md5 b/documentation/latex/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.md5 deleted file mode 100644 index 4359a5e..0000000 --- a/documentation/latex/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9aea13a5028d8f4123276053376ed52d \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.pdf b/documentation/latex/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.pdf deleted file mode 100644 index 8477bd6..0000000 Binary files a/documentation/latex/class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.md5 b/documentation/latex/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.md5 deleted file mode 100644 index 0afda66..0000000 --- a/documentation/latex/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -679fbdfaee17602fc6f33d072399a2d2 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.pdf b/documentation/latex/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.pdf deleted file mode 100644 index 09d47ab..0000000 Binary files a/documentation/latex/class_b_n_o08x_af50010400cbd1445e9ddfa259384b412_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.md5 b/documentation/latex/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.md5 deleted file mode 100644 index 09dc76e..0000000 --- a/documentation/latex/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -072aeec087f6b46af3783486b6b429de \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.pdf b/documentation/latex/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.pdf deleted file mode 100644 index 11e794c..0000000 Binary files a/documentation/latex/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.md5 b/documentation/latex/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.md5 deleted file mode 100644 index feeaa0b..0000000 --- a/documentation/latex/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3fcac07f092e8fcf1dc045ac12024126 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.pdf b/documentation/latex/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.pdf deleted file mode 100644 index c296ab2..0000000 Binary files a/documentation/latex/class_b_n_o08x_af5d6dae7c0f8d36b6ac91adff614ab3a_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.md5 b/documentation/latex/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.md5 deleted file mode 100644 index 28bb289..0000000 --- a/documentation/latex/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e1f0b8db217b3c27f501b7870f58003b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.pdf b/documentation/latex/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.pdf deleted file mode 100644 index 2b58720..0000000 Binary files a/documentation/latex/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.md5 b/documentation/latex/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.md5 deleted file mode 100644 index 30602b8..0000000 --- a/documentation/latex/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7b1e294c2e6b82bf1f5989a5dbb5dee9 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.pdf b/documentation/latex/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.pdf deleted file mode 100644 index 3b5327b..0000000 Binary files a/documentation/latex/class_b_n_o08x_af7f960dbd26c6f1834661ef5f5bbd4d3_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.md5 b/documentation/latex/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.md5 deleted file mode 100644 index 294ba77..0000000 --- a/documentation/latex/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -06afc036ab61c400489276d84f3ebec3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.pdf b/documentation/latex/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.pdf deleted file mode 100644 index c1a378d..0000000 Binary files a/documentation/latex/class_b_n_o08x_af80f7795656e695e036d3b1557aed94c_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.md5 b/documentation/latex/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.md5 deleted file mode 100644 index c1b6c02..0000000 --- a/documentation/latex/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fa823417b577123da18aac170be188c0 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.pdf b/documentation/latex/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.pdf deleted file mode 100644 index 0821655..0000000 Binary files a/documentation/latex/class_b_n_o08x_af971d82426740e62c1f05adcd2c9ce7c_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.md5 b/documentation/latex/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.md5 deleted file mode 100644 index de81488..0000000 --- a/documentation/latex/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b8d43d19f458f42f29e29f8903947f38 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.pdf b/documentation/latex/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.pdf deleted file mode 100644 index c0b5eda..0000000 Binary files a/documentation/latex/class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.md5 b/documentation/latex/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.md5 deleted file mode 100644 index 559ea1a..0000000 --- a/documentation/latex/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6c787a5956ecdc8f82c153f159d4e5f6 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.pdf b/documentation/latex/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.pdf deleted file mode 100644 index cfc03a1..0000000 Binary files a/documentation/latex/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.md5 b/documentation/latex/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.md5 deleted file mode 100644 index 0e40b23..0000000 --- a/documentation/latex/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9d939dff204389d0eb12bd77699cadb2 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.pdf b/documentation/latex/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.pdf deleted file mode 100644 index f9624c6..0000000 Binary files a/documentation/latex/class_b_n_o08x_afbd2b02d5abe7084ce9de49ee2c9142f_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.md5 b/documentation/latex/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.md5 deleted file mode 100644 index b9d8047..0000000 --- a/documentation/latex/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -63cc67e22f6c95c6ad7875a84efb5165 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.pdf b/documentation/latex/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.pdf deleted file mode 100644 index 74e6489..0000000 Binary files a/documentation/latex/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.md5 b/documentation/latex/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.md5 deleted file mode 100644 index 3571322..0000000 --- a/documentation/latex/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7a68a799fd22a4d119da4ce930e1ddcc \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.pdf b/documentation/latex/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.pdf deleted file mode 100644 index 2142050..0000000 Binary files a/documentation/latex/class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.md5 b/documentation/latex/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.md5 deleted file mode 100644 index 858851e..0000000 --- a/documentation/latex/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e6d3c64400e7ccfe794ff0b4b127ea01 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.pdf b/documentation/latex/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.pdf deleted file mode 100644 index 88e7e8c..0000000 Binary files a/documentation/latex/class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.md5 b/documentation/latex/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.md5 deleted file mode 100644 index 9a0335a..0000000 --- a/documentation/latex/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0e70086099d081cf12dbc5c1d3c98b5b \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.pdf b/documentation/latex/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.pdf deleted file mode 100644 index 2826345..0000000 Binary files a/documentation/latex/class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.md5 b/documentation/latex/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.md5 deleted file mode 100644 index 4cdd1e5..0000000 --- a/documentation/latex/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -09af1541256156fd308589f48f63057c \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.pdf b/documentation/latex/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.pdf deleted file mode 100644 index d5426e0..0000000 Binary files a/documentation/latex/class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.md5 b/documentation/latex/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.md5 deleted file mode 100644 index f24b343..0000000 --- a/documentation/latex/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7750f228aa080778702e286159215698 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.pdf b/documentation/latex/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.pdf deleted file mode 100644 index 6cbca34..0000000 Binary files a/documentation/latex/class_b_n_o08x_afe588fbd0055193d3bc08984d7732354_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.md5 b/documentation/latex/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.md5 deleted file mode 100644 index 384d851..0000000 --- a/documentation/latex/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5bceee3192368759a63da682ad0a9679 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.pdf b/documentation/latex/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.pdf deleted file mode 100644 index 4a1fe2d..0000000 Binary files a/documentation/latex/class_b_n_o08x_aff9a7e0190b228f5032474a3f4feb9a1_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.md5 b/documentation/latex/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.md5 deleted file mode 100644 index 07921c2..0000000 --- a/documentation/latex/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -cf00de9cf08c1ab4df050b66d77691e1 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.pdf b/documentation/latex/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.pdf deleted file mode 100644 index 26f2b47..0000000 Binary files a/documentation/latex/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.md5 b/documentation/latex/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.md5 deleted file mode 100644 index 41d00fd..0000000 --- a/documentation/latex/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -98b40de2abd126937c05a147263baa73 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.pdf b/documentation/latex/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.pdf deleted file mode 100644 index 2b94882..0000000 Binary files a/documentation/latex/class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper.tex b/documentation/latex/class_b_n_o08x_test_helper.tex deleted file mode 100644 index 0b04846..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper.tex +++ /dev/null @@ -1,900 +0,0 @@ -\doxysection{BNO08x\+Test\+Helper Class Reference} -\hypertarget{class_b_n_o08x_test_helper}{}\label{class_b_n_o08x_test_helper}\index{BNO08xTestHelper@{BNO08xTestHelper}} - - -\doxylink{class_b_n_o08x}{BNO08x} unit test helper class. - - - - -{\ttfamily \#include $<$BNO08x\+Test\+Helper.\+hpp$>$} - - - -Collaboration diagram for BNO08x\+Test\+Helper\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_helper__coll__graph} -\end{center} -\end{figure} -\doxysubsubsection*{Classes} -\begin{DoxyCompactItemize} -\item -struct \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} -\begin{DoxyCompactList}\small\item\em IMU configuration settings passed into constructor. \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Public Types} -\begin{DoxyCompactItemize} -\item -typedef struct BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t \mbox{\hyperlink{class_b_n_o08x_test_helper_a0b3d9379e670b0c532ba76801cfb7580}{imu\+\_\+report\+\_\+data\+\_\+t}} -\begin{DoxyCompactList}\small\item\em IMU configuration settings passed into constructor. \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Static Public Member Functions} -\begin{DoxyCompactItemize} -\item -static void \mbox{\hyperlink{class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885}{print\+\_\+test\+\_\+start\+\_\+banner}} (const char \texorpdfstring{$\ast$}{*}TEST\+\_\+\+TAG) -\begin{DoxyCompactList}\small\item\em Prints test begin banner. \end{DoxyCompactList}\item -static void \mbox{\hyperlink{class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919}{print\+\_\+test\+\_\+end\+\_\+banner}} (const char \texorpdfstring{$\ast$}{*}TEST\+\_\+\+TAG) -\begin{DoxyCompactList}\small\item\em Prints end begin banner. \end{DoxyCompactList}\item -static void \mbox{\hyperlink{class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002}{print\+\_\+test\+\_\+msg}} (const char \texorpdfstring{$\ast$}{*}TEST\+\_\+\+TAG, const char \texorpdfstring{$\ast$}{*}msg) -\begin{DoxyCompactList}\small\item\em Prints a message during a test. \end{DoxyCompactList}\item -static void \mbox{\hyperlink{class_b_n_o08x_test_helper_a9e2f9bf13f28f1a6ba87e86bc5947cf1}{set\+\_\+test\+\_\+imu\+\_\+cfg}} (\mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}} cfg) -\begin{DoxyCompactList}\small\item\em Set test imu configuration used with \doxylink{class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518}{create\+\_\+test\+\_\+imu()} \end{DoxyCompactList}\item -static void \mbox{\hyperlink{class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518}{create\+\_\+test\+\_\+imu}} () -\begin{DoxyCompactList}\small\item\em Calls \doxylink{class_b_n_o08x}{BNO08x} constructor and creates new test IMU on heap. \end{DoxyCompactList}\item -static void \mbox{\hyperlink{class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40}{destroy\+\_\+test\+\_\+imu}} () -\begin{DoxyCompactList}\small\item\em Deletes test IMU calling deconstructor and releases heap allocated memory. \end{DoxyCompactList}\item -static \mbox{\hyperlink{class_b_n_o08x}{BNO08x}} \texorpdfstring{$\ast$}{*} \mbox{\hyperlink{class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b}{get\+\_\+test\+\_\+imu}} () -\begin{DoxyCompactList}\small\item\em Deletes test IMU calling deconstructor and releases heap allocated memory. \end{DoxyCompactList}\item -static esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d}{call\+\_\+init\+\_\+config\+\_\+args}} () -\begin{DoxyCompactList}\small\item\em Used to call private \doxylink{class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d}{BNO08x\+::init\+\_\+config\+\_\+args()} member for tests. \end{DoxyCompactList}\item -static esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161}{call\+\_\+init\+\_\+gpio}} () -\begin{DoxyCompactList}\small\item\em Used to call private \doxylink{class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10}{BNO08x\+::init\+\_\+gpio()} member for tests. \end{DoxyCompactList}\item -static esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15}{call\+\_\+init\+\_\+hint\+\_\+isr}} () -\begin{DoxyCompactList}\small\item\em Used to call private \doxylink{class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61}{BNO08x\+::init\+\_\+hint\+\_\+isr()} member for tests. \end{DoxyCompactList}\item -static esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5}{call\+\_\+init\+\_\+spi}} () -\begin{DoxyCompactList}\small\item\em Used to call private \doxylink{class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81}{BNO08x\+::init\+\_\+spi()} member for tests. \end{DoxyCompactList}\item -static esp\+\_\+err\+\_\+t \mbox{\hyperlink{class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a}{call\+\_\+launch\+\_\+tasks}} () -\begin{DoxyCompactList}\small\item\em Used to call private \doxylink{class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be}{BNO08x\+::launch\+\_\+tasks()} member for tests. \end{DoxyCompactList}\item -static bool \mbox{\hyperlink{class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd}{rotation\+\_\+vector\+\_\+data\+\_\+is\+\_\+new}} (\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}default\+\_\+report\+\_\+data) -\begin{DoxyCompactList}\small\item\em Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. \end{DoxyCompactList}\item -static bool \mbox{\hyperlink{class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6}{gyro\+\_\+integrated\+\_\+rotation\+\_\+vector\+\_\+data\+\_\+is\+\_\+new}} (\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}default\+\_\+report\+\_\+data) -\begin{DoxyCompactList}\small\item\em Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. \end{DoxyCompactList}\item -static bool \mbox{\hyperlink{class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2}{uncalibrated\+\_\+gyro\+\_\+data\+\_\+is\+\_\+new}} (\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}default\+\_\+report\+\_\+data) -\begin{DoxyCompactList}\small\item\em Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. \end{DoxyCompactList}\item -static bool \mbox{\hyperlink{class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9}{calibrated\+\_\+gyro\+\_\+data\+\_\+is\+\_\+new}} (\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}default\+\_\+report\+\_\+data) -\begin{DoxyCompactList}\small\item\em Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. \end{DoxyCompactList}\item -static bool \mbox{\hyperlink{class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea}{accelerometer\+\_\+data\+\_\+is\+\_\+new}} (\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}default\+\_\+report\+\_\+data) -\begin{DoxyCompactList}\small\item\em Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. \end{DoxyCompactList}\item -static bool \mbox{\hyperlink{class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590}{linear\+\_\+accelerometer\+\_\+data\+\_\+is\+\_\+new}} (\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}default\+\_\+report\+\_\+data) -\begin{DoxyCompactList}\small\item\em Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. \end{DoxyCompactList}\item -static bool \mbox{\hyperlink{class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a}{gravity\+\_\+data\+\_\+is\+\_\+new}} (\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}default\+\_\+report\+\_\+data) -\begin{DoxyCompactList}\small\item\em Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. \end{DoxyCompactList}\item -static bool \mbox{\hyperlink{class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5}{magnetometer\+\_\+data\+\_\+is\+\_\+new}} (\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}default\+\_\+report\+\_\+data) -\begin{DoxyCompactList}\small\item\em Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. \end{DoxyCompactList}\item -static bool \mbox{\hyperlink{class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782}{step\+\_\+counter\+\_\+data\+\_\+is\+\_\+new}} (\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}default\+\_\+report\+\_\+data) -\begin{DoxyCompactList}\small\item\em Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. \end{DoxyCompactList}\item -static bool \mbox{\hyperlink{class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3}{stability\+\_\+classifier\+\_\+data\+\_\+is\+\_\+new}} (\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}default\+\_\+report\+\_\+data) -\begin{DoxyCompactList}\small\item\em Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. \end{DoxyCompactList}\item -static bool \mbox{\hyperlink{class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9}{activity\+\_\+classifier\+\_\+data\+\_\+is\+\_\+new}} (\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}, \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}default\+\_\+report\+\_\+data) -\begin{DoxyCompactList}\small\item\em Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. \end{DoxyCompactList}\item -static void \mbox{\hyperlink{class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2}{update\+\_\+report\+\_\+data}} (\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}\mbox{\hyperlink{_callback_tests_8cpp_a22334b11e0558ec663d040de9b7db8c9}{report\+\_\+data}}) -\begin{DoxyCompactList}\small\item\em Updates report data with calls relevant test\+\_\+imu methods. \end{DoxyCompactList}\item -static void \mbox{\hyperlink{class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528}{reset\+\_\+all\+\_\+imu\+\_\+data\+\_\+to\+\_\+test\+\_\+defaults}} () -\begin{DoxyCompactList}\small\item\em Resets internal test imu data with test defaults. \end{DoxyCompactList}\item -static const char \texorpdfstring{$\ast$}{*} \mbox{\hyperlink{class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3}{BNO08x\+Accuracy\+\_\+to\+\_\+str}} (\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} accuracy) -\begin{DoxyCompactList}\small\item\em Converts BNO08x\+Accuracy enum class object to string. \end{DoxyCompactList}\item -static const char \texorpdfstring{$\ast$}{*} \mbox{\hyperlink{class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059}{BNO08x\+Stability\+\_\+to\+\_\+str}} (\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}{BNO08x\+Stability}} stability) -\begin{DoxyCompactList}\small\item\em Converts BNO08x\+Stability enum class object to string. \end{DoxyCompactList}\item -static const char \texorpdfstring{$\ast$}{*} \mbox{\hyperlink{class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750}{BNO08x\+Activity\+\_\+to\+\_\+str}} (\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}{BNO08x\+Activity}} activity) -\begin{DoxyCompactList}\small\item\em Converts BNO08x\+Activity enum class object to string. \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Static Private Attributes} -\begin{DoxyCompactItemize} -\item -static \mbox{\hyperlink{class_b_n_o08x}{BNO08x}} \texorpdfstring{$\ast$}{*} \mbox{\hyperlink{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}{test\+\_\+imu}} = nullptr -\item -static \mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}} \mbox{\hyperlink{class_b_n_o08x_test_helper_a008b268f705b9d2925230cb8193c9f28}{imu\+\_\+cfg}} -\item -static const constexpr char \texorpdfstring{$\ast$}{*} \mbox{\hyperlink{class_b_n_o08x_test_helper_aa09d388a5da3a925ac25125b9c5c3a90}{TAG}} = "{}BNO08x\+Test\+Helper"{} -\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -\doxylink{class_b_n_o08x}{BNO08x} unit test helper class. - -\doxysubsection{Member Typedef Documentation} -\Hypertarget{class_b_n_o08x_test_helper_a0b3d9379e670b0c532ba76801cfb7580}\label{class_b_n_o08x_test_helper_a0b3d9379e670b0c532ba76801cfb7580} -\index{BNO08xTestHelper@{BNO08xTestHelper}!imu\_report\_data\_t@{imu\_report\_data\_t}} -\index{imu\_report\_data\_t@{imu\_report\_data\_t}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{imu\_report\_data\_t}{imu\_report\_data\_t}} -{\footnotesize\ttfamily typedef struct BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t} - - - -IMU configuration settings passed into constructor. - - - -\doxysubsection{Member Function Documentation} -\Hypertarget{class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea}\label{class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea} -\index{BNO08xTestHelper@{BNO08xTestHelper}!accelerometer\_data\_is\_new@{accelerometer\_data\_is\_new}} -\index{accelerometer\_data\_is\_new@{accelerometer\_data\_is\_new}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{accelerometer\_data\_is\_new()}{accelerometer\_data\_is\_new()}} -{\footnotesize\ttfamily static bool BNO08x\+Test\+Helper\+::accelerometer\+\_\+data\+\_\+is\+\_\+new (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{report\+\_\+data, }\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{default\+\_\+report\+\_\+data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & Current report data. \\ -\hline -{\em default\+\_\+report\+\_\+data} & Default report data to compare (should always contain default values)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if new data was received for respective report. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9}\label{class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9} -\index{BNO08xTestHelper@{BNO08xTestHelper}!activity\_classifier\_data\_is\_new@{activity\_classifier\_data\_is\_new}} -\index{activity\_classifier\_data\_is\_new@{activity\_classifier\_data\_is\_new}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{activity\_classifier\_data\_is\_new()}{activity\_classifier\_data\_is\_new()}} -{\footnotesize\ttfamily static bool BNO08x\+Test\+Helper\+::activity\+\_\+classifier\+\_\+data\+\_\+is\+\_\+new (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{report\+\_\+data, }\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{default\+\_\+report\+\_\+data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & Current report data. \\ -\hline -{\em default\+\_\+report\+\_\+data} & Default report data to compare (should always contain default values)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if new data was received for respective report. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=324pt]{class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3}\label{class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3} -\index{BNO08xTestHelper@{BNO08xTestHelper}!BNO08xAccuracy\_to\_str@{BNO08xAccuracy\_to\_str}} -\index{BNO08xAccuracy\_to\_str@{BNO08xAccuracy\_to\_str}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{BNO08xAccuracy\_to\_str()}{BNO08xAccuracy\_to\_str()}} -{\footnotesize\ttfamily static const char \texorpdfstring{$\ast$}{*} BNO08x\+Test\+Helper\+::\+BNO08x\+Accuracy\+\_\+to\+\_\+str (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}}}]{accuracy }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Converts BNO08x\+Accuracy enum class object to string. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & BNO08x\+Accuracy object to convert to string.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The resulting string conversion. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750}\label{class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750} -\index{BNO08xTestHelper@{BNO08xTestHelper}!BNO08xActivity\_to\_str@{BNO08xActivity\_to\_str}} -\index{BNO08xActivity\_to\_str@{BNO08xActivity\_to\_str}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{BNO08xActivity\_to\_str()}{BNO08xActivity\_to\_str()}} -{\footnotesize\ttfamily static const char \texorpdfstring{$\ast$}{*} BNO08x\+Test\+Helper\+::\+BNO08x\+Activity\+\_\+to\+\_\+str (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}{BNO08x\+Activity}}}]{activity }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Converts BNO08x\+Activity enum class object to string. - - -\begin{DoxyParams}{Parameters} -{\em activity} & BNO08x\+Activity object to convert to string.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The resulting string conversion. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=330pt]{class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059}\label{class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059} -\index{BNO08xTestHelper@{BNO08xTestHelper}!BNO08xStability\_to\_str@{BNO08xStability\_to\_str}} -\index{BNO08xStability\_to\_str@{BNO08xStability\_to\_str}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{BNO08xStability\_to\_str()}{BNO08xStability\_to\_str()}} -{\footnotesize\ttfamily static const char \texorpdfstring{$\ast$}{*} BNO08x\+Test\+Helper\+::\+BNO08x\+Stability\+\_\+to\+\_\+str (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}{BNO08x\+Stability}}}]{stability }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Converts BNO08x\+Stability enum class object to string. - - -\begin{DoxyParams}{Parameters} -{\em stability} & BNO08x\+Stability object to convert to string.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -The resulting string conversion. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=330pt]{class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9}\label{class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9} -\index{BNO08xTestHelper@{BNO08xTestHelper}!calibrated\_gyro\_data\_is\_new@{calibrated\_gyro\_data\_is\_new}} -\index{calibrated\_gyro\_data\_is\_new@{calibrated\_gyro\_data\_is\_new}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{calibrated\_gyro\_data\_is\_new()}{calibrated\_gyro\_data\_is\_new()}} -{\footnotesize\ttfamily static bool BNO08x\+Test\+Helper\+::calibrated\+\_\+gyro\+\_\+data\+\_\+is\+\_\+new (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{report\+\_\+data, }\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{default\+\_\+report\+\_\+data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & Current report data. \\ -\hline -{\em default\+\_\+report\+\_\+data} & Default report data to compare (should always contain default values)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if new data was received for respective report. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=336pt]{class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d}\label{class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d} -\index{BNO08xTestHelper@{BNO08xTestHelper}!call\_init\_config\_args@{call\_init\_config\_args}} -\index{call\_init\_config\_args@{call\_init\_config\_args}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{call\_init\_config\_args()}{call\_init\_config\_args()}} -{\footnotesize\ttfamily static esp\+\_\+err\+\_\+t BNO08x\+Test\+Helper\+::call\+\_\+init\+\_\+config\+\_\+args (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Used to call private \doxylink{class_b_n_o08x_a589eb9780f5bf613bbd447ef5b9ade3d}{BNO08x\+::init\+\_\+config\+\_\+args()} member for tests. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if init succeeded. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=309pt]{class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161}\label{class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161} -\index{BNO08xTestHelper@{BNO08xTestHelper}!call\_init\_gpio@{call\_init\_gpio}} -\index{call\_init\_gpio@{call\_init\_gpio}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{call\_init\_gpio()}{call\_init\_gpio()}} -{\footnotesize\ttfamily static esp\+\_\+err\+\_\+t BNO08x\+Test\+Helper\+::call\+\_\+init\+\_\+gpio (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Used to call private \doxylink{class_b_n_o08x_ae0dab25557befcf62bf384fdc241ef10}{BNO08x\+::init\+\_\+gpio()} member for tests. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if init succeeded. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=309pt]{class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15}\label{class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15} -\index{BNO08xTestHelper@{BNO08xTestHelper}!call\_init\_hint\_isr@{call\_init\_hint\_isr}} -\index{call\_init\_hint\_isr@{call\_init\_hint\_isr}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{call\_init\_hint\_isr()}{call\_init\_hint\_isr()}} -{\footnotesize\ttfamily static esp\+\_\+err\+\_\+t BNO08x\+Test\+Helper\+::call\+\_\+init\+\_\+hint\+\_\+isr (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Used to call private \doxylink{class_b_n_o08x_aa27026da2c52b4aca49b78863f10ec61}{BNO08x\+::init\+\_\+hint\+\_\+isr()} member for tests. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if init succeeded. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=309pt]{class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5}\label{class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5} -\index{BNO08xTestHelper@{BNO08xTestHelper}!call\_init\_spi@{call\_init\_spi}} -\index{call\_init\_spi@{call\_init\_spi}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{call\_init\_spi()}{call\_init\_spi()}} -{\footnotesize\ttfamily static esp\+\_\+err\+\_\+t BNO08x\+Test\+Helper\+::call\+\_\+init\+\_\+spi (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Used to call private \doxylink{class_b_n_o08x_a58f43c8bb1e7fe8560ce442d46240e81}{BNO08x\+::init\+\_\+spi()} member for tests. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if init succeeded. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=326pt]{class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=309pt]{class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a}\label{class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a} -\index{BNO08xTestHelper@{BNO08xTestHelper}!call\_launch\_tasks@{call\_launch\_tasks}} -\index{call\_launch\_tasks@{call\_launch\_tasks}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{call\_launch\_tasks()}{call\_launch\_tasks()}} -{\footnotesize\ttfamily static esp\+\_\+err\+\_\+t BNO08x\+Test\+Helper\+::call\+\_\+launch\+\_\+tasks (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Used to call private \doxylink{class_b_n_o08x_a06f99a6b2182b49a0e61e2107f2be6be}{BNO08x\+::launch\+\_\+tasks()} member for tests. - -\begin{DoxyReturn}{Returns} -ESP\+\_\+\+OK if init succeeded. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=309pt]{class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518}\label{class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518} -\index{BNO08xTestHelper@{BNO08xTestHelper}!create\_test\_imu@{create\_test\_imu}} -\index{create\_test\_imu@{create\_test\_imu}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{create\_test\_imu()}{create\_test\_imu()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Helper\+::create\+\_\+test\+\_\+imu (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Calls \doxylink{class_b_n_o08x}{BNO08x} constructor and creates new test IMU on heap. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=321pt]{class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40}\label{class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40} -\index{BNO08xTestHelper@{BNO08xTestHelper}!destroy\_test\_imu@{destroy\_test\_imu}} -\index{destroy\_test\_imu@{destroy\_test\_imu}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{destroy\_test\_imu()}{destroy\_test\_imu()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Helper\+::destroy\+\_\+test\+\_\+imu (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Deletes test IMU calling deconstructor and releases heap allocated memory. - -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b}\label{class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b} -\index{BNO08xTestHelper@{BNO08xTestHelper}!get\_test\_imu@{get\_test\_imu}} -\index{get\_test\_imu@{get\_test\_imu}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{get\_test\_imu()}{get\_test\_imu()}} -{\footnotesize\ttfamily static \mbox{\hyperlink{class_b_n_o08x}{BNO08x}} \texorpdfstring{$\ast$}{*} BNO08x\+Test\+Helper\+::get\+\_\+test\+\_\+imu (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Deletes test IMU calling deconstructor and releases heap allocated memory. - -\begin{DoxyReturn}{Returns} -Pointer to \doxylink{class_b_n_o08x}{BNO08x} IMU object to test. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a}\label{class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a} -\index{BNO08xTestHelper@{BNO08xTestHelper}!gravity\_data\_is\_new@{gravity\_data\_is\_new}} -\index{gravity\_data\_is\_new@{gravity\_data\_is\_new}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{gravity\_data\_is\_new()}{gravity\_data\_is\_new()}} -{\footnotesize\ttfamily static bool BNO08x\+Test\+Helper\+::gravity\+\_\+data\+\_\+is\+\_\+new (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{report\+\_\+data, }\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{default\+\_\+report\+\_\+data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & Current report data. \\ -\hline -{\em default\+\_\+report\+\_\+data} & Default report data to compare (should always contain default values)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if new data was received for respective report. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=321pt]{class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6}\label{class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6} -\index{BNO08xTestHelper@{BNO08xTestHelper}!gyro\_integrated\_rotation\_vector\_data\_is\_new@{gyro\_integrated\_rotation\_vector\_data\_is\_new}} -\index{gyro\_integrated\_rotation\_vector\_data\_is\_new@{gyro\_integrated\_rotation\_vector\_data\_is\_new}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{gyro\_integrated\_rotation\_vector\_data\_is\_new()}{gyro\_integrated\_rotation\_vector\_data\_is\_new()}} -{\footnotesize\ttfamily static bool BNO08x\+Test\+Helper\+::gyro\+\_\+integrated\+\_\+rotation\+\_\+vector\+\_\+data\+\_\+is\+\_\+new (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{report\+\_\+data, }\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{default\+\_\+report\+\_\+data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & Current report data. \\ -\hline -{\em default\+\_\+report\+\_\+data} & Default report data to compare (should always contain default values)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if new data was received for respective report. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=321pt]{class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590}\label{class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590} -\index{BNO08xTestHelper@{BNO08xTestHelper}!linear\_accelerometer\_data\_is\_new@{linear\_accelerometer\_data\_is\_new}} -\index{linear\_accelerometer\_data\_is\_new@{linear\_accelerometer\_data\_is\_new}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{linear\_accelerometer\_data\_is\_new()}{linear\_accelerometer\_data\_is\_new()}} -{\footnotesize\ttfamily static bool BNO08x\+Test\+Helper\+::linear\+\_\+accelerometer\+\_\+data\+\_\+is\+\_\+new (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{report\+\_\+data, }\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{default\+\_\+report\+\_\+data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & Current report data. \\ -\hline -{\em default\+\_\+report\+\_\+data} & Default report data to compare (should always contain default values)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if new data was received for respective report. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=330pt]{class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5}\label{class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5} -\index{BNO08xTestHelper@{BNO08xTestHelper}!magnetometer\_data\_is\_new@{magnetometer\_data\_is\_new}} -\index{magnetometer\_data\_is\_new@{magnetometer\_data\_is\_new}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{magnetometer\_data\_is\_new()}{magnetometer\_data\_is\_new()}} -{\footnotesize\ttfamily static bool BNO08x\+Test\+Helper\+::magnetometer\+\_\+data\+\_\+is\+\_\+new (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{report\+\_\+data, }\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{default\+\_\+report\+\_\+data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & Current report data. \\ -\hline -{\em default\+\_\+report\+\_\+data} & Default report data to compare (should always contain default values)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if new data was received for respective report. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919}\label{class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919} -\index{BNO08xTestHelper@{BNO08xTestHelper}!print\_test\_end\_banner@{print\_test\_end\_banner}} -\index{print\_test\_end\_banner@{print\_test\_end\_banner}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{print\_test\_end\_banner()}{print\_test\_end\_banner()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Helper\+::print\+\_\+test\+\_\+end\+\_\+banner (\begin{DoxyParamCaption}\item[{const char \texorpdfstring{$\ast$}{*}}]{TEST\+\_\+\+TAG }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Prints end begin banner. - - -\begin{DoxyParams}{Parameters} -{\em TEST\+\_\+\+TAG} & String containing test name.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002}\label{class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002} -\index{BNO08xTestHelper@{BNO08xTestHelper}!print\_test\_msg@{print\_test\_msg}} -\index{print\_test\_msg@{print\_test\_msg}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{print\_test\_msg()}{print\_test\_msg()}} -{\footnotesize\ttfamily BNO08x\+Test\+Helper\+::print\+\_\+test\+\_\+msg (\begin{DoxyParamCaption}\item[{const char \texorpdfstring{$\ast$}{*}}]{TEST\+\_\+\+TAG, }\item[{const char \texorpdfstring{$\ast$}{*}}]{msg }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Prints a message during a test. - - -\begin{DoxyParams}{Parameters} -{\em TEST\+\_\+\+TAG} & String containing test name. \\ -\hline -{\em msg} & String containing message to print.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885}\label{class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885} -\index{BNO08xTestHelper@{BNO08xTestHelper}!print\_test\_start\_banner@{print\_test\_start\_banner}} -\index{print\_test\_start\_banner@{print\_test\_start\_banner}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{print\_test\_start\_banner()}{print\_test\_start\_banner()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Helper\+::print\+\_\+test\+\_\+start\+\_\+banner (\begin{DoxyParamCaption}\item[{const char \texorpdfstring{$\ast$}{*}}]{TEST\+\_\+\+TAG }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Prints test begin banner. - - -\begin{DoxyParams}{Parameters} -{\em TEST\+\_\+\+TAG} & String containing test name.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528}\label{class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528} -\index{BNO08xTestHelper@{BNO08xTestHelper}!reset\_all\_imu\_data\_to\_test\_defaults@{reset\_all\_imu\_data\_to\_test\_defaults}} -\index{reset\_all\_imu\_data\_to\_test\_defaults@{reset\_all\_imu\_data\_to\_test\_defaults}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{reset\_all\_imu\_data\_to\_test\_defaults()}{reset\_all\_imu\_data\_to\_test\_defaults()}} -{\footnotesize\ttfamily BNO08x\+Test\+Helper\+::reset\+\_\+all\+\_\+imu\+\_\+data\+\_\+to\+\_\+test\+\_\+defaults (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Resets internal test imu data with test defaults. - -\begin{DoxyReturn}{Returns} -void, nothing to return. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd}\label{class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd} -\index{BNO08xTestHelper@{BNO08xTestHelper}!rotation\_vector\_data\_is\_new@{rotation\_vector\_data\_is\_new}} -\index{rotation\_vector\_data\_is\_new@{rotation\_vector\_data\_is\_new}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{rotation\_vector\_data\_is\_new()}{rotation\_vector\_data\_is\_new()}} -{\footnotesize\ttfamily static bool BNO08x\+Test\+Helper\+::rotation\+\_\+vector\+\_\+data\+\_\+is\+\_\+new (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{report\+\_\+data, }\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{default\+\_\+report\+\_\+data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & Current report data. \\ -\hline -{\em default\+\_\+report\+\_\+data} & Default report data to compare (should always contain default values)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if new data was received for respective report. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=326pt]{class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_a9e2f9bf13f28f1a6ba87e86bc5947cf1}\label{class_b_n_o08x_test_helper_a9e2f9bf13f28f1a6ba87e86bc5947cf1} -\index{BNO08xTestHelper@{BNO08xTestHelper}!set\_test\_imu\_cfg@{set\_test\_imu\_cfg}} -\index{set\_test\_imu\_cfg@{set\_test\_imu\_cfg}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{set\_test\_imu\_cfg()}{set\_test\_imu\_cfg()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Helper\+::set\+\_\+test\+\_\+imu\+\_\+cfg (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}}}]{cfg }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Set test imu configuration used with \doxylink{class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518}{create\+\_\+test\+\_\+imu()} - - -\begin{DoxyParams}{Parameters} -{\em cfg} & String containing test name.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, nothing to return -\end{DoxyReturn} -\Hypertarget{class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3}\label{class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3} -\index{BNO08xTestHelper@{BNO08xTestHelper}!stability\_classifier\_data\_is\_new@{stability\_classifier\_data\_is\_new}} -\index{stability\_classifier\_data\_is\_new@{stability\_classifier\_data\_is\_new}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{stability\_classifier\_data\_is\_new()}{stability\_classifier\_data\_is\_new()}} -{\footnotesize\ttfamily static bool BNO08x\+Test\+Helper\+::stability\+\_\+classifier\+\_\+data\+\_\+is\+\_\+new (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{report\+\_\+data, }\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{default\+\_\+report\+\_\+data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & Current report data. \\ -\hline -{\em default\+\_\+report\+\_\+data} & Default report data to compare (should always contain default values)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if new data was received for respective report. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=327pt]{class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782}\label{class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782} -\index{BNO08xTestHelper@{BNO08xTestHelper}!step\_counter\_data\_is\_new@{step\_counter\_data\_is\_new}} -\index{step\_counter\_data\_is\_new@{step\_counter\_data\_is\_new}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{step\_counter\_data\_is\_new()}{step\_counter\_data\_is\_new()}} -{\footnotesize\ttfamily static bool BNO08x\+Test\+Helper\+::step\+\_\+counter\+\_\+data\+\_\+is\+\_\+new (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{report\+\_\+data, }\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{default\+\_\+report\+\_\+data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & Current report data. \\ -\hline -{\em default\+\_\+report\+\_\+data} & Default report data to compare (should always contain default values)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if new data was received for respective report. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=312pt]{class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2}\label{class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2} -\index{BNO08xTestHelper@{BNO08xTestHelper}!uncalibrated\_gyro\_data\_is\_new@{uncalibrated\_gyro\_data\_is\_new}} -\index{uncalibrated\_gyro\_data\_is\_new@{uncalibrated\_gyro\_data\_is\_new}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{uncalibrated\_gyro\_data\_is\_new()}{uncalibrated\_gyro\_data\_is\_new()}} -{\footnotesize\ttfamily static bool BNO08x\+Test\+Helper\+::uncalibrated\+\_\+gyro\+\_\+data\+\_\+is\+\_\+new (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{report\+\_\+data, }\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{default\+\_\+report\+\_\+data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Checks if report\+\_\+data matches the default states stored within prev\+\_\+report\+\_\+data data for respective report. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & Current report data. \\ -\hline -{\em default\+\_\+report\+\_\+data} & Default report data to compare (should always contain default values)\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -True if new data was received for respective report. -\end{DoxyReturn} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=346pt]{class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2}\label{class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2} -\index{BNO08xTestHelper@{BNO08xTestHelper}!update\_report\_data@{update\_report\_data}} -\index{update\_report\_data@{update\_report\_data}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{update\_report\_data()}{update\_report\_data()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Helper\+::update\+\_\+report\+\_\+data (\begin{DoxyParamCaption}\item[{\mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t}} \texorpdfstring{$\ast$}{*}}]{report\+\_\+data }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - - - -Updates report data with calls relevant test\+\_\+imu methods. - - -\begin{DoxyParams}{Parameters} -{\em report\+\_\+data} & Pointer to \doxylink{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{imu\+\_\+report\+\_\+data\+\_\+t} struct to save report data.\\ -\hline -\end{DoxyParams} -\begin{DoxyReturn}{Returns} -void, noting to return. -\end{DoxyReturn} -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[height=550pt]{class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph} -\end{center} -\end{figure} - - -\doxysubsection{Member Data Documentation} -\Hypertarget{class_b_n_o08x_test_helper_a008b268f705b9d2925230cb8193c9f28}\label{class_b_n_o08x_test_helper_a008b268f705b9d2925230cb8193c9f28} -\index{BNO08xTestHelper@{BNO08xTestHelper}!imu\_cfg@{imu\_cfg}} -\index{imu\_cfg@{imu\_cfg}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{imu\_cfg}{imu\_cfg}} -{\footnotesize\ttfamily \mbox{\hyperlink{structbno08x__config__t}{bno08x\+\_\+config\+\_\+t}} BNO08x\+Test\+Helper\+::imu\+\_\+cfg\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}, {\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_test_helper_aa09d388a5da3a925ac25125b9c5c3a90}\label{class_b_n_o08x_test_helper_aa09d388a5da3a925ac25125b9c5c3a90} -\index{BNO08xTestHelper@{BNO08xTestHelper}!TAG@{TAG}} -\index{TAG@{TAG}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{TAG}{TAG}} -{\footnotesize\ttfamily const constexpr char\texorpdfstring{$\ast$}{*} BNO08x\+Test\+Helper\+::\+TAG = "{}BNO08x\+Test\+Helper"{}\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [constexpr]}, {\ttfamily [private]}} - -\Hypertarget{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243}\label{class_b_n_o08x_test_helper_a2da34e5d5e353cd37fa458fcfe7cf243} -\index{BNO08xTestHelper@{BNO08xTestHelper}!test\_imu@{test\_imu}} -\index{test\_imu@{test\_imu}!BNO08xTestHelper@{BNO08xTestHelper}} -\doxysubsubsection{\texorpdfstring{test\_imu}{test\_imu}} -{\footnotesize\ttfamily \mbox{\hyperlink{class_b_n_o08x}{BNO08x}}\texorpdfstring{$\ast$}{*} BNO08x\+Test\+Helper\+::test\+\_\+imu = nullptr\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}, {\ttfamily [private]}} - - - -The documentation for this class was generated from the following files\+:\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_b_n_o08x_test_helper_8hpp}{BNO08x\+Test\+Helper.\+hpp}}\item -\mbox{\hyperlink{_callback_tests_8cpp}{Callback\+Tests.\+cpp}}\end{DoxyCompactItemize} diff --git a/documentation/latex/class_b_n_o08x_test_helper__coll__graph.md5 b/documentation/latex/class_b_n_o08x_test_helper__coll__graph.md5 deleted file mode 100644 index 613f2fb..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper__coll__graph.md5 +++ /dev/null @@ -1 +0,0 @@ -c444efa6aec5d97d11734b05b735edd6 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper__coll__graph.pdf b/documentation/latex/class_b_n_o08x_test_helper__coll__graph.pdf deleted file mode 100644 index ba0074f..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper__coll__graph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.md5 deleted file mode 100644 index e78fbaf..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -6e33090c2f47ac3aaab28205e1c80d22 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.pdf deleted file mode 100644 index b205f05..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a066f8389fd1c682ec9565ebc3060d885_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.md5 deleted file mode 100644 index d90b7fe..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -774bc86981b6a854930a88027a1ddebf \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.pdf deleted file mode 100644 index 39bde5c..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a084e65ff5c0e2f429b39ebb53b0e03c9_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.md5 deleted file mode 100644 index c6c4786..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -3d3d41c3989eec84fc2d4e55f7a2de09 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.pdf deleted file mode 100644 index 28e9afb..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a157342da2def8b659d27ae4d24063cb5_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.md5 deleted file mode 100644 index 28768c0..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a9c8f76a881de81210b8829028b2fc24 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.pdf deleted file mode 100644 index c36231e..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a16423fc3250e88eb5392800022f82919_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.md5 deleted file mode 100644 index a62d295..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8966e251679bb08e749301afd2778a90 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.pdf deleted file mode 100644 index 817e74a..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a3c2514f3bad3f091de4646c5798f487a_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.md5 deleted file mode 100644 index e96ca5d..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -226fe57a4ed76671dde2d7392d5647f8 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.pdf deleted file mode 100644 index 8c6c1b2..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a41a432a3fe288e45b6ab139a00bd7d6b_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.md5 deleted file mode 100644 index 67efc36..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b86fbcefb4ef3aab843ae4f3af457d12 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.pdf deleted file mode 100644 index 7a1064d..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.md5 deleted file mode 100644 index 13afaa0..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2382f39139d1838e5a1758e45bab5a8f \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.pdf deleted file mode 100644 index d06e115..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a504749533ccd91890d73440809d38161_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.md5 deleted file mode 100644 index 940a43c..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b3c069f64b8564ceee20df448c2c1594 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.pdf deleted file mode 100644 index db76df5..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.md5 deleted file mode 100644 index 2396f1e..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -d4d981acb0210a83cf1b78e7bc862865 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.pdf deleted file mode 100644 index 3a69b97..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a6bd040c7d670a9713f2ab8a8a3913518_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.md5 deleted file mode 100644 index b722688..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -34cf6439ec04bcd5e4d7db48524cc6f3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.pdf deleted file mode 100644 index 5e2870a..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.md5 deleted file mode 100644 index 70bc950..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -78b09f921e09771c1b2c6b31b58450ed \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.pdf deleted file mode 100644 index a86c4ed..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a71d9fd7d459a98a7e9089a8587a21f8d_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.md5 deleted file mode 100644 index baa9e94..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -fdd80cda1eadf931042fd15a412d9a45 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.pdf deleted file mode 100644 index 4ff5f98..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.md5 deleted file mode 100644 index 8ff21cd..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -58983fd82a6d182ef014b48cd6feffaa \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.pdf deleted file mode 100644 index 9f98f93..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a7d2d784da1e850dab41154b35d7cdab5_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.md5 deleted file mode 100644 index cba32e3..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -819ee216af20f5de906d82ee16bc0391 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.pdf deleted file mode 100644 index 53da168..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a7fbfc48c0fff306ab81e2320bc171002_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.md5 deleted file mode 100644 index f199291..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -1d1e57029e5ff47cb2769698f11414e2 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.pdf deleted file mode 100644 index f394381..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.md5 deleted file mode 100644 index 7247fe1..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7a1817b7cc689ca8658d545397f3e3b7 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.pdf deleted file mode 100644 index 637e83e..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a836c928981ac85d34668c9b97af17a15_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.md5 deleted file mode 100644 index d83d8fb..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -abed61e8c024659fae42bd43362d5268 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.pdf deleted file mode 100644 index ed48ff2..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a857b66c12c231af0d546c026ec017ab3_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.md5 deleted file mode 100644 index a56eaf5..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f18864171ea787e6d23686ff3ce3eb12 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.pdf deleted file mode 100644 index 4110f19..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_a95ed21657224358877a66d010eeefad3_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.md5 deleted file mode 100644 index 2dae37a..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a990c67305e9c19c4d43da6f5c7e4010 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.pdf deleted file mode 100644 index 7bd96f0..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_aa7eb152d4192c3949bb3443ef6221782_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.md5 deleted file mode 100644 index d3ba1cc..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -aad575f68f793ac8d65c1273ee539960 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.pdf deleted file mode 100644 index 40347a4..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_ac5b0ac4c70bbfcba9f2e8f353b35f9f6_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.md5 deleted file mode 100644 index f5a04b1..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -2246faac856dd80abdf1cf8f0c47f0e0 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.pdf deleted file mode 100644 index 9e7c21d..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.md5 deleted file mode 100644 index 7f36e42..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -15410f7812d9ad79c001aaf709cf9eab \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.pdf deleted file mode 100644 index 80337d7..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_ac81c63583b19e5c7b3233324aaea98e2_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.md5 deleted file mode 100644 index 2d5b51e..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -9daec3bf9594d6de4535c8b77f75d013 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.pdf deleted file mode 100644 index d7c69ba..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_ac95ba2892d54e6219123ad3ca0104750_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.md5 deleted file mode 100644 index 97a299c..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -0524a3280e434669f255c0a85374ec1d \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.pdf deleted file mode 100644 index 199fb2f..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_ad398739ce46400c1ac35e1cf7603d590_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.md5 deleted file mode 100644 index dca3ccc..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -e5a1bd125fafc130ab57978c43fd29f0 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.pdf deleted file mode 100644 index 17aec40..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_adb5952b2b96b553024b6a841e30adad2_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.md5 deleted file mode 100644 index 7293163..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7c9fa535906f75ec1ed674a280187d08 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.pdf deleted file mode 100644 index e4e743d..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_ade6be1fd8ef3a99e0edae4cbf25eb528_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.md5 deleted file mode 100644 index a245e07..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -19a787b99f8c090d3421c1a25a4d15a4 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.pdf deleted file mode 100644 index 3741ea1..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_ade97098806c8779b26f9c166c4b03eea_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.md5 deleted file mode 100644 index f7c1bb4..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -5acf95edb3f84fde35df12b673d1ab0c \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.pdf deleted file mode 100644 index 7bb3116..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.md5 deleted file mode 100644 index cc8a6f4..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -a3c4ed36e1aaab5e376ac2a088f67540 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.pdf deleted file mode 100644 index f62415f..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_adf2488d1f7e3dec21a0d0c99417c181a_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.md5 deleted file mode 100644 index 576292a..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f235aaf3a21ff47ff126bfe1c393d6df \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.pdf deleted file mode 100644 index 0ca2d33..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_ae2d6df7dcfdbd106c2247803461bbc40_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.md5 deleted file mode 100644 index 9c87e5a..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -7ce219d2b5ae57cf08a807a38d85cebb \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.pdf deleted file mode 100644 index f7b068b..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_ae922f36719ab085550ef270d5a149059_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.md5 deleted file mode 100644 index 5234a6f..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -902096018f5c67707eb54931354c73f1 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.pdf deleted file mode 100644 index 02019b8..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_aeb8cd985faf8e403f62b60fced9cb2fd_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.md5 deleted file mode 100644 index 4a04287..0000000 --- a/documentation/latex/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -832bb52796622a8100ebdf9317f219ab \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.pdf deleted file mode 100644 index 3d94353..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_helper_afc6cc734ad843aca30a7cb76ad6dedb9_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_suite.tex b/documentation/latex/class_b_n_o08x_test_suite.tex deleted file mode 100644 index 310c709..0000000 --- a/documentation/latex/class_b_n_o08x_test_suite.tex +++ /dev/null @@ -1,172 +0,0 @@ -\doxysection{BNO08x\+Test\+Suite Class Reference} -\hypertarget{class_b_n_o08x_test_suite}{}\label{class_b_n_o08x_test_suite}\index{BNO08xTestSuite@{BNO08xTestSuite}} - - -\doxylink{class_b_n_o08x}{BNO08x} unit test launch point class. - - - - -{\ttfamily \#include $<$BNO08x\+Test\+Suite.\+hpp$>$} - -\doxysubsubsection*{Static Public Member Functions} -\begin{DoxyCompactItemize} -\item -static void \mbox{\hyperlink{class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd}{run\+\_\+all\+\_\+tests}} () -\item -static void \mbox{\hyperlink{class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16}{run\+\_\+init\+\_\+deinit\+\_\+tests}} (bool call\+\_\+unity\+\_\+end\+\_\+begin=true) -\item -static void \mbox{\hyperlink{class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb}{run\+\_\+single\+\_\+report\+\_\+tests}} (bool call\+\_\+unity\+\_\+end\+\_\+begin=true) -\item -static void \mbox{\hyperlink{class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5}{run\+\_\+multi\+\_\+report\+\_\+tests}} (bool call\+\_\+unity\+\_\+end\+\_\+begin=true) -\item -static void \mbox{\hyperlink{class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8}{run\+\_\+callback\+\_\+tests}} (bool call\+\_\+unity\+\_\+end\+\_\+begin=true) -\end{DoxyCompactItemize} -\doxysubsubsection*{Static Private Member Functions} -\begin{DoxyCompactItemize} -\item -static void \mbox{\hyperlink{class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085}{print\+\_\+begin\+\_\+tests\+\_\+banner}} (const char \texorpdfstring{$\ast$}{*}test\+\_\+set\+\_\+name) -\item -static void \mbox{\hyperlink{class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb}{print\+\_\+end\+\_\+tests\+\_\+banner}} (const char \texorpdfstring{$\ast$}{*}test\+\_\+set\+\_\+name) -\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -\doxylink{class_b_n_o08x}{BNO08x} unit test launch point class. - -\doxysubsection{Member Function Documentation} -\Hypertarget{class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085}\label{class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085} -\index{BNO08xTestSuite@{BNO08xTestSuite}!print\_begin\_tests\_banner@{print\_begin\_tests\_banner}} -\index{print\_begin\_tests\_banner@{print\_begin\_tests\_banner}!BNO08xTestSuite@{BNO08xTestSuite}} -\doxysubsubsection{\texorpdfstring{print\_begin\_tests\_banner()}{print\_begin\_tests\_banner()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Suite\+::print\+\_\+begin\+\_\+tests\+\_\+banner (\begin{DoxyParamCaption}\item[{const char \texorpdfstring{$\ast$}{*}}]{test\+\_\+set\+\_\+name }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}, {\ttfamily [private]}} - -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb}\label{class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb} -\index{BNO08xTestSuite@{BNO08xTestSuite}!print\_end\_tests\_banner@{print\_end\_tests\_banner}} -\index{print\_end\_tests\_banner@{print\_end\_tests\_banner}!BNO08xTestSuite@{BNO08xTestSuite}} -\doxysubsubsection{\texorpdfstring{print\_end\_tests\_banner()}{print\_end\_tests\_banner()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Suite\+::print\+\_\+end\+\_\+tests\+\_\+banner (\begin{DoxyParamCaption}\item[{const char \texorpdfstring{$\ast$}{*}}]{test\+\_\+set\+\_\+name }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}, {\ttfamily [private]}} - -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd}\label{class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd} -\index{BNO08xTestSuite@{BNO08xTestSuite}!run\_all\_tests@{run\_all\_tests}} -\index{run\_all\_tests@{run\_all\_tests}!BNO08xTestSuite@{BNO08xTestSuite}} -\doxysubsubsection{\texorpdfstring{run\_all\_tests()}{run\_all\_tests()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Suite\+::run\+\_\+all\+\_\+tests (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=350pt]{class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8}\label{class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8} -\index{BNO08xTestSuite@{BNO08xTestSuite}!run\_callback\_tests@{run\_callback\_tests}} -\index{run\_callback\_tests@{run\_callback\_tests}!BNO08xTestSuite@{BNO08xTestSuite}} -\doxysubsubsection{\texorpdfstring{run\_callback\_tests()}{run\_callback\_tests()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Suite\+::run\+\_\+callback\+\_\+tests (\begin{DoxyParamCaption}\item[{bool}]{call\+\_\+unity\+\_\+end\+\_\+begin = {\ttfamily true} }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=348pt]{class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=343pt]{class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16}\label{class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16} -\index{BNO08xTestSuite@{BNO08xTestSuite}!run\_init\_deinit\_tests@{run\_init\_deinit\_tests}} -\index{run\_init\_deinit\_tests@{run\_init\_deinit\_tests}!BNO08xTestSuite@{BNO08xTestSuite}} -\doxysubsubsection{\texorpdfstring{run\_init\_deinit\_tests()}{run\_init\_deinit\_tests()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Suite\+::run\+\_\+init\+\_\+deinit\+\_\+tests (\begin{DoxyParamCaption}\item[{bool}]{call\+\_\+unity\+\_\+end\+\_\+begin = {\ttfamily true} }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=348pt]{class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=343pt]{class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5}\label{class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5} -\index{BNO08xTestSuite@{BNO08xTestSuite}!run\_multi\_report\_tests@{run\_multi\_report\_tests}} -\index{run\_multi\_report\_tests@{run\_multi\_report\_tests}!BNO08xTestSuite@{BNO08xTestSuite}} -\doxysubsubsection{\texorpdfstring{run\_multi\_report\_tests()}{run\_multi\_report\_tests()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Suite\+::run\+\_\+multi\+\_\+report\+\_\+tests (\begin{DoxyParamCaption}\item[{bool}]{call\+\_\+unity\+\_\+end\+\_\+begin = {\ttfamily true} }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=348pt]{class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=343pt]{class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph} -\end{center} -\end{figure} -\Hypertarget{class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb}\label{class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb} -\index{BNO08xTestSuite@{BNO08xTestSuite}!run\_single\_report\_tests@{run\_single\_report\_tests}} -\index{run\_single\_report\_tests@{run\_single\_report\_tests}!BNO08xTestSuite@{BNO08xTestSuite}} -\doxysubsubsection{\texorpdfstring{run\_single\_report\_tests()}{run\_single\_report\_tests()}} -{\footnotesize\ttfamily static void BNO08x\+Test\+Suite\+::run\+\_\+single\+\_\+report\+\_\+tests (\begin{DoxyParamCaption}\item[{bool}]{call\+\_\+unity\+\_\+end\+\_\+begin = {\ttfamily true} }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}, {\ttfamily [static]}} - -Here is the call graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=348pt]{class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph} -\end{center} -\end{figure} -Here is the caller graph for this function\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=343pt]{class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph} -\end{center} -\end{figure} - - -The documentation for this class was generated from the following file\+:\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_b_n_o08x_test_suite_8hpp}{BNO08x\+Test\+Suite.\+hpp}}\end{DoxyCompactItemize} diff --git a/documentation/latex/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.md5 deleted file mode 100644 index 90ed484..0000000 --- a/documentation/latex/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -334bf98e834753886d541e24049de7fd \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.pdf deleted file mode 100644 index 003684b..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_suite_a2fea3ea192a63c9573c774e772f5c085_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.md5 b/documentation/latex/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.md5 deleted file mode 100644 index 00a62ea..0000000 --- a/documentation/latex/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -4abb8811296bc328b8ed9a44c0e38163 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.pdf b/documentation/latex/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.pdf deleted file mode 100644 index 940da9f..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.md5 deleted file mode 100644 index d7b3fa5..0000000 --- a/documentation/latex/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b86691b30403f40e7b0b498ab4f89582 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.pdf deleted file mode 100644 index 1bf9e63..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_suite_a37899d7bf67fce5c3dd77dd5647f8ecb_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.md5 b/documentation/latex/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.md5 deleted file mode 100644 index 492d7b3..0000000 --- a/documentation/latex/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -f5215c21e9ea287ea4be6e252cb76450 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.pdf b/documentation/latex/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.pdf deleted file mode 100644 index df38633..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.md5 deleted file mode 100644 index 0f852bc..0000000 --- a/documentation/latex/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -15f5ae7d00ab917e4fdb9752e4eb8508 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.pdf deleted file mode 100644 index 8f085bd..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_suite_a53de9b0fe1b28c18e3a1ca4c68a06f16_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.md5 deleted file mode 100644 index 8dbcfd7..0000000 --- a/documentation/latex/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -b52cad4f5cf6ab507b4a4eb8ca6a93e3 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.pdf deleted file mode 100644 index 582495d..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_suite_a5a9b6538773911afed92b16c435ebceb_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.md5 b/documentation/latex/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.md5 deleted file mode 100644 index 6794b4d..0000000 --- a/documentation/latex/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -704fcdbac312fe6d6a0d2b2e4d3a2789 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.pdf b/documentation/latex/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.pdf deleted file mode 100644 index 053e0eb..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.md5 deleted file mode 100644 index 4bbac41..0000000 --- a/documentation/latex/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -081ae480916d317e56754fc239b66460 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.pdf deleted file mode 100644 index 3fbedee..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_suite_a8e294955bf512e2e88c086f04f6030a8_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.md5 b/documentation/latex/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.md5 deleted file mode 100644 index 73c56a1..0000000 --- a/documentation/latex/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -8924e8b03b8d505d19d0514736e58daf \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.pdf b/documentation/latex/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.pdf deleted file mode 100644 index f3fa1cb..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.md5 b/documentation/latex/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.md5 deleted file mode 100644 index 8a0587e..0000000 --- a/documentation/latex/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -819638db82dc4a3bce19d66676cce005 \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.pdf b/documentation/latex/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.pdf deleted file mode 100644 index f99687a..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_suite_a916cff374791381de61f1035f9935ac5_icgraph.pdf and /dev/null differ diff --git a/documentation/latex/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.md5 b/documentation/latex/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.md5 deleted file mode 100644 index a0a8dcc..0000000 --- a/documentation/latex/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.md5 +++ /dev/null @@ -1 +0,0 @@ -42b2215b3618d09fa366a8601225271f \ No newline at end of file diff --git a/documentation/latex/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.pdf b/documentation/latex/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.pdf deleted file mode 100644 index 0df37fb..0000000 Binary files a/documentation/latex/class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd_cgraph.pdf and /dev/null differ diff --git a/documentation/latex/dir_105fd1ee051c171768c94e464b88861d.tex b/documentation/latex/dir_105fd1ee051c171768c94e464b88861d.tex deleted file mode 100644 index 987c927..0000000 --- a/documentation/latex/dir_105fd1ee051c171768c94e464b88861d.tex +++ /dev/null @@ -1,15 +0,0 @@ -\doxysection{source Directory Reference} -\hypertarget{dir_105fd1ee051c171768c94e464b88861d}{}\label{dir_105fd1ee051c171768c94e464b88861d}\index{source Directory Reference@{source Directory Reference}} -Directory dependency graph for source\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=180pt]{dir_105fd1ee051c171768c94e464b88861d_dep} -\end{center} -\end{figure} -\doxysubsubsection*{Files} -\begin{DoxyCompactItemize} -\item -file \mbox{\hyperlink{_b_n_o08x_8cpp}{BNO08x.\+cpp}} -\end{DoxyCompactItemize} diff --git a/documentation/latex/dir_105fd1ee051c171768c94e464b88861d_dep.md5 b/documentation/latex/dir_105fd1ee051c171768c94e464b88861d_dep.md5 deleted file mode 100644 index 07db8c0..0000000 --- a/documentation/latex/dir_105fd1ee051c171768c94e464b88861d_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -76c1b7531cb9f13814675d55ea700c92 \ No newline at end of file diff --git a/documentation/latex/dir_105fd1ee051c171768c94e464b88861d_dep.pdf b/documentation/latex/dir_105fd1ee051c171768c94e464b88861d_dep.pdf deleted file mode 100644 index 5835833..0000000 Binary files a/documentation/latex/dir_105fd1ee051c171768c94e464b88861d_dep.pdf and /dev/null differ diff --git a/documentation/latex/dir_14dea6b744ab39100edf1f9916c217e0.tex b/documentation/latex/dir_14dea6b744ab39100edf1f9916c217e0.tex deleted file mode 100644 index 5b5e197..0000000 --- a/documentation/latex/dir_14dea6b744ab39100edf1f9916c217e0.tex +++ /dev/null @@ -1,21 +0,0 @@ -\doxysection{test Directory Reference} -\hypertarget{dir_14dea6b744ab39100edf1f9916c217e0}{}\label{dir_14dea6b744ab39100edf1f9916c217e0}\index{test Directory Reference@{test Directory Reference}} -Directory dependency graph for test\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=180pt]{dir_14dea6b744ab39100edf1f9916c217e0_dep} -\end{center} -\end{figure} -\doxysubsubsection*{Files} -\begin{DoxyCompactItemize} -\item -file \mbox{\hyperlink{_callback_tests_8cpp}{Callback\+Tests.\+cpp}} -\item -file \mbox{\hyperlink{_init_deinit_tests_8cpp}{Init\+Deinit\+Tests.\+cpp}} -\item -file \mbox{\hyperlink{_multi_report_tests_8cpp}{Multi\+Report\+Tests.\+cpp}} -\item -file \mbox{\hyperlink{_single_report_tests_8cpp}{Single\+Report\+Tests.\+cpp}} -\end{DoxyCompactItemize} diff --git a/documentation/latex/dir_14dea6b744ab39100edf1f9916c217e0_dep.md5 b/documentation/latex/dir_14dea6b744ab39100edf1f9916c217e0_dep.md5 deleted file mode 100644 index e80583d..0000000 --- a/documentation/latex/dir_14dea6b744ab39100edf1f9916c217e0_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -65d7476f5306b5b8a6e00408a7eb7734 \ No newline at end of file diff --git a/documentation/latex/dir_14dea6b744ab39100edf1f9916c217e0_dep.pdf b/documentation/latex/dir_14dea6b744ab39100edf1f9916c217e0_dep.pdf deleted file mode 100644 index 3d9ea2a..0000000 Binary files a/documentation/latex/dir_14dea6b744ab39100edf1f9916c217e0_dep.pdf and /dev/null differ diff --git a/documentation/latex/dir_85e9385bd83516731053aadc7da3c8af.tex b/documentation/latex/dir_85e9385bd83516731053aadc7da3c8af.tex deleted file mode 100644 index c26b853..0000000 --- a/documentation/latex/dir_85e9385bd83516731053aadc7da3c8af.tex +++ /dev/null @@ -1,15 +0,0 @@ -\doxysection{imu\+\_\+update Directory Reference} -\hypertarget{dir_85e9385bd83516731053aadc7da3c8af}{}\label{dir_85e9385bd83516731053aadc7da3c8af}\index{imu\_update Directory Reference@{imu\_update Directory Reference}} -Directory dependency graph for imu\+\_\+update\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=278pt]{dir_85e9385bd83516731053aadc7da3c8af_dep} -\end{center} -\end{figure} -\doxysubsubsection*{Directories} -\begin{DoxyCompactItemize} -\item -directory \mbox{\hyperlink{dir_c60d9bf80716f90f729fd65c40ec81f7}{bno08x\+\_\+update}} -\end{DoxyCompactItemize} diff --git a/documentation/latex/dir_85e9385bd83516731053aadc7da3c8af_dep.md5 b/documentation/latex/dir_85e9385bd83516731053aadc7da3c8af_dep.md5 deleted file mode 100644 index a856f53..0000000 --- a/documentation/latex/dir_85e9385bd83516731053aadc7da3c8af_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -685023a910c171116b6443e88b6f7bf1 \ No newline at end of file diff --git a/documentation/latex/dir_85e9385bd83516731053aadc7da3c8af_dep.pdf b/documentation/latex/dir_85e9385bd83516731053aadc7da3c8af_dep.pdf deleted file mode 100644 index 9168c6e..0000000 Binary files a/documentation/latex/dir_85e9385bd83516731053aadc7da3c8af_dep.pdf and /dev/null differ diff --git a/documentation/latex/dir_9667f1a5b10a5222433e41df91e1bf5d.tex b/documentation/latex/dir_9667f1a5b10a5222433e41df91e1bf5d.tex deleted file mode 100644 index 2fe7cd9..0000000 --- a/documentation/latex/dir_9667f1a5b10a5222433e41df91e1bf5d.tex +++ /dev/null @@ -1,23 +0,0 @@ -\doxysection{include Directory Reference} -\hypertarget{dir_9667f1a5b10a5222433e41df91e1bf5d}{}\label{dir_9667f1a5b10a5222433e41df91e1bf5d}\index{include Directory Reference@{include Directory Reference}} -Directory dependency graph for include\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=180pt]{dir_9667f1a5b10a5222433e41df91e1bf5d_dep} -\end{center} -\end{figure} -\doxysubsubsection*{Files} -\begin{DoxyCompactItemize} -\item -file \mbox{\hyperlink{_b_n_o08x_8hpp}{BNO08x.\+hpp}} -\item -file \mbox{\hyperlink{_b_n_o08x__global__types_8hpp}{BNO08x\+\_\+global\+\_\+types.\+hpp}} -\item -file \mbox{\hyperlink{_b_n_o08x__macros_8hpp}{BNO08x\+\_\+macros.\+hpp}} -\item -file \mbox{\hyperlink{_b_n_o08x_test_helper_8hpp}{BNO08x\+Test\+Helper.\+hpp}} -\item -file \mbox{\hyperlink{_b_n_o08x_test_suite_8hpp}{BNO08x\+Test\+Suite.\+hpp}} -\end{DoxyCompactItemize} diff --git a/documentation/latex/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.md5 b/documentation/latex/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.md5 deleted file mode 100644 index 29ab75b..0000000 --- a/documentation/latex/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -1a959f5226a0619482e82cf08fc76c15 \ No newline at end of file diff --git a/documentation/latex/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.pdf b/documentation/latex/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.pdf deleted file mode 100644 index 23961fa..0000000 Binary files a/documentation/latex/dir_9667f1a5b10a5222433e41df91e1bf5d_dep.pdf and /dev/null differ diff --git a/documentation/latex/dir_a6718ce9703adf4789a693642ffedf7f.tex b/documentation/latex/dir_a6718ce9703adf4789a693642ffedf7f.tex deleted file mode 100644 index 575d7a8..0000000 --- a/documentation/latex/dir_a6718ce9703adf4789a693642ffedf7f.tex +++ /dev/null @@ -1,19 +0,0 @@ -\doxysection{esp32\+\_\+\+BNO08x Directory Reference} -\hypertarget{dir_a6718ce9703adf4789a693642ffedf7f}{}\label{dir_a6718ce9703adf4789a693642ffedf7f}\index{esp32\_BNO08x Directory Reference@{esp32\_BNO08x Directory Reference}} -Directory dependency graph for esp32\+\_\+\+BNO08x\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=326pt]{dir_a6718ce9703adf4789a693642ffedf7f_dep} -\end{center} -\end{figure} -\doxysubsubsection*{Directories} -\begin{DoxyCompactItemize} -\item -directory \mbox{\hyperlink{dir_9667f1a5b10a5222433e41df91e1bf5d}{include}} -\item -directory \mbox{\hyperlink{dir_105fd1ee051c171768c94e464b88861d}{source}} -\item -directory \mbox{\hyperlink{dir_14dea6b744ab39100edf1f9916c217e0}{test}} -\end{DoxyCompactItemize} diff --git a/documentation/latex/dir_a6718ce9703adf4789a693642ffedf7f_dep.md5 b/documentation/latex/dir_a6718ce9703adf4789a693642ffedf7f_dep.md5 deleted file mode 100644 index 59beb8c..0000000 --- a/documentation/latex/dir_a6718ce9703adf4789a693642ffedf7f_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -37d251802c676e8c5c4e479554df4db8 \ No newline at end of file diff --git a/documentation/latex/dir_a6718ce9703adf4789a693642ffedf7f_dep.pdf b/documentation/latex/dir_a6718ce9703adf4789a693642ffedf7f_dep.pdf deleted file mode 100644 index 48c2eb6..0000000 Binary files a/documentation/latex/dir_a6718ce9703adf4789a693642ffedf7f_dep.pdf and /dev/null differ diff --git a/documentation/latex/dir_c60d9bf80716f90f729fd65c40ec81f7.tex b/documentation/latex/dir_c60d9bf80716f90f729fd65c40ec81f7.tex deleted file mode 100644 index 93f5ff7..0000000 --- a/documentation/latex/dir_c60d9bf80716f90f729fd65c40ec81f7.tex +++ /dev/null @@ -1,15 +0,0 @@ -\doxysection{bno08x\+\_\+update Directory Reference} -\hypertarget{dir_c60d9bf80716f90f729fd65c40ec81f7}{}\label{dir_c60d9bf80716f90f729fd65c40ec81f7}\index{bno08x\_update Directory Reference@{bno08x\_update Directory Reference}} -Directory dependency graph for bno08x\+\_\+update\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=298pt]{dir_c60d9bf80716f90f729fd65c40ec81f7_dep} -\end{center} -\end{figure} -\doxysubsubsection*{Directories} -\begin{DoxyCompactItemize} -\item -directory \mbox{\hyperlink{dir_fd670e5d11b8bb731501003ff6578ae1}{components}} -\end{DoxyCompactItemize} diff --git a/documentation/latex/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.md5 b/documentation/latex/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.md5 deleted file mode 100644 index c80cb87..0000000 --- a/documentation/latex/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -63aaadf87a7d982f18fd764f52e28a27 \ No newline at end of file diff --git a/documentation/latex/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.pdf b/documentation/latex/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.pdf deleted file mode 100644 index 927b677..0000000 Binary files a/documentation/latex/dir_c60d9bf80716f90f729fd65c40ec81f7_dep.pdf and /dev/null differ diff --git a/documentation/latex/dir_fd670e5d11b8bb731501003ff6578ae1.tex b/documentation/latex/dir_fd670e5d11b8bb731501003ff6578ae1.tex deleted file mode 100644 index e34116a..0000000 --- a/documentation/latex/dir_fd670e5d11b8bb731501003ff6578ae1.tex +++ /dev/null @@ -1,15 +0,0 @@ -\doxysection{components Directory Reference} -\hypertarget{dir_fd670e5d11b8bb731501003ff6578ae1}{}\label{dir_fd670e5d11b8bb731501003ff6578ae1}\index{components Directory Reference@{components Directory Reference}} -Directory dependency graph for components\+: -\nopagebreak -\begin{figure}[H] -\begin{center} -\leavevmode -\includegraphics[width=300pt]{dir_fd670e5d11b8bb731501003ff6578ae1_dep} -\end{center} -\end{figure} -\doxysubsubsection*{Directories} -\begin{DoxyCompactItemize} -\item -directory \mbox{\hyperlink{dir_a6718ce9703adf4789a693642ffedf7f}{esp32\+\_\+\+BNO08x}} -\end{DoxyCompactItemize} diff --git a/documentation/latex/dir_fd670e5d11b8bb731501003ff6578ae1_dep.md5 b/documentation/latex/dir_fd670e5d11b8bb731501003ff6578ae1_dep.md5 deleted file mode 100644 index 20d5888..0000000 --- a/documentation/latex/dir_fd670e5d11b8bb731501003ff6578ae1_dep.md5 +++ /dev/null @@ -1 +0,0 @@ -e26c358ec72ae9812a1309c2994c8f8a \ No newline at end of file diff --git a/documentation/latex/dir_fd670e5d11b8bb731501003ff6578ae1_dep.pdf b/documentation/latex/dir_fd670e5d11b8bb731501003ff6578ae1_dep.pdf deleted file mode 100644 index 5a4bf0d..0000000 Binary files a/documentation/latex/dir_fd670e5d11b8bb731501003ff6578ae1_dep.pdf and /dev/null differ diff --git a/documentation/latex/doxygen.sty b/documentation/latex/doxygen.sty deleted file mode 100644 index 4bfc17f..0000000 --- a/documentation/latex/doxygen.sty +++ /dev/null @@ -1,694 +0,0 @@ -\NeedsTeXFormat{LaTeX2e} -\ProvidesPackage{doxygen} - -% Packages used by this style file -\RequirePackage{alltt} -%%\RequirePackage{array} %% moved to refman.tex due to workaround for LaTex 2019 version and unmaintained tabu package -\RequirePackage{calc} -\RequirePackage{float} -%%\RequirePackage{ifthen} %% moved to refman.tex due to workaround for LaTex 2019 version and unmaintained tabu package -\RequirePackage{verbatim} -\RequirePackage[table]{xcolor} -\RequirePackage{longtable_doxygen} -\RequirePackage{tabu_doxygen} -\RequirePackage{fancyvrb} -\RequirePackage{tabularx} -\RequirePackage{multicol} -\RequirePackage{multirow} -\RequirePackage{hanging} -\RequirePackage{ifpdf} -\RequirePackage{adjustbox} -\RequirePackage{amssymb} -\RequirePackage{stackengine} -\RequirePackage{enumitem} -\RequirePackage{alphalph} -\RequirePackage[normalem]{ulem} % for strikeout, but don't modify emphasis - -%---------- Internal commands used in this style file ---------------- - -\newcommand{\ensurespace}[1]{% - \begingroup% - \setlength{\dimen@}{#1}% - \vskip\z@\@plus\dimen@% - \penalty -100\vskip\z@\@plus -\dimen@% - \vskip\dimen@% - \penalty 9999% - \vskip -\dimen@% - \vskip\z@skip% hide the previous |\vskip| from |\addvspace| - \endgroup% -} - -\newcommand{\DoxyHorRuler}[1]{% - \setlength{\parskip}{0ex plus 0ex minus 0ex}% - \ifthenelse{#1=0}% - {% - \hrule% - }% - {% - \hrulefilll% - }% -} -\newcommand{\DoxyLabelFont}{} -\newcommand{\entrylabel}[1]{% - {% - \parbox[b]{\labelwidth-4pt}{% - \makebox[0pt][l]{\DoxyLabelFont#1}% - \vspace{1.5\baselineskip}% - }% - }% -} - -\newenvironment{DoxyDesc}[1]{% - \ensurespace{4\baselineskip}% - \begin{list}{}{% - \settowidth{\labelwidth}{20pt}% - %\setlength{\parsep}{0pt}% - \setlength{\itemsep}{0pt}% - \setlength{\leftmargin}{\labelwidth+\labelsep}% - \renewcommand{\makelabel}{\entrylabel}% - }% - \item[#1]% -}{% - \end{list}% -} - -\newsavebox{\xrefbox} -\newlength{\xreflength} -\newcommand{\xreflabel}[1]{% - \sbox{\xrefbox}{#1}% - \setlength{\xreflength}{\wd\xrefbox}% - \ifthenelse{\xreflength>\labelwidth}{% - \begin{minipage}{\textwidth}% - \setlength{\parindent}{0pt}% - \hangindent=15pt\bfseries #1\vspace{1.2\itemsep}% - \end{minipage}% - }{% - \parbox[b]{\labelwidth}{\makebox[0pt][l]{\textbf{#1}}}% - }% -} - -%---------- Commands used by doxygen LaTeX output generator ---------- - -% Used by
     ... 
    -\newenvironment{DoxyPre}{% - \small% - \begin{alltt}% -}{% - \end{alltt}% - \normalsize% -} -% Necessary for redefining not defined characters, i.e. "Replacement Character" in tex output. -\newlength{\CodeWidthChar} -\newlength{\CodeHeightChar} -\settowidth{\CodeWidthChar}{?} -\settoheight{\CodeHeightChar}{?} -% Necessary for hanging indent -\newlength{\DoxyCodeWidth} - -\newcommand\DoxyCodeLine[1]{ - \ifthenelse{\equal{\detokenize{#1}}{}} - { - \vspace*{\baselineskip} - } - { - \hangpara{\DoxyCodeWidth}{1}{#1}\par - } -} - -\newcommand\NiceSpace{% - \discretionary{}{\kern\fontdimen2\font}{\kern\fontdimen2\font}% -} - -% Used by @code ... @endcode -\newenvironment{DoxyCode}[1]{% - \par% - \scriptsize% - \normalfont\ttfamily% - \rightskip0pt plus 1fil% - \settowidth{\DoxyCodeWidth}{000000}% - \settowidth{\CodeWidthChar}{?}% - \settoheight{\CodeHeightChar}{?}% - \setlength{\parskip}{0ex plus 0ex minus 0ex}% - \ifthenelse{\equal{#1}{0}} - { - {\lccode`~32 \lowercase{\global\let~}\NiceSpace}\obeyspaces% - } - { - {\lccode`~32 \lowercase{\global\let~}}\obeyspaces% - } - -}{% - \normalfont% - \normalsize% - \settowidth{\CodeWidthChar}{?}% - \settoheight{\CodeHeightChar}{?}% -} - -% Redefining not defined characters, i.e. "Replacement Character" in tex output. -\def\ucr{\adjustbox{width=\CodeWidthChar,height=\CodeHeightChar}{\stackinset{c}{}{c}{-.2pt}{% - \textcolor{white}{\sffamily\bfseries\small ?}}{% - \rotatebox{45}{$\blacksquare$}}}} - -% Used by @example, @include, @includelineno and @dontinclude -\newenvironment{DoxyCodeInclude}[1]{% - \DoxyCode{#1}% -}{% - \endDoxyCode% -} - -% Used by @verbatim ... @endverbatim -\newenvironment{DoxyVerb}{% - \par% - \footnotesize% - \verbatim% -}{% - \endverbatim% - \normalsize% -} - -% Used by @verbinclude -\newenvironment{DoxyVerbInclude}{% - \DoxyVerb% -}{% - \endDoxyVerb% -} - -% Used by numbered lists (using '-#' or
      ...
    ) -\setlistdepth{12} -\newlist{DoxyEnumerate}{enumerate}{12} -\setlist[DoxyEnumerate,1]{label=\arabic*.} -\setlist[DoxyEnumerate,2]{label=(\enumalphalphcnt*)} -\setlist[DoxyEnumerate,3]{label=\roman*.} -\setlist[DoxyEnumerate,4]{label=\enumAlphAlphcnt*.} -\setlist[DoxyEnumerate,5]{label=\arabic*.} -\setlist[DoxyEnumerate,6]{label=(\enumalphalphcnt*)} -\setlist[DoxyEnumerate,7]{label=\roman*.} -\setlist[DoxyEnumerate,8]{label=\enumAlphAlphcnt*.} -\setlist[DoxyEnumerate,9]{label=\arabic*.} -\setlist[DoxyEnumerate,10]{label=(\enumalphalphcnt*)} -\setlist[DoxyEnumerate,11]{label=\roman*.} -\setlist[DoxyEnumerate,12]{label=\enumAlphAlphcnt*.} - -% Used by bullet lists (using '-', @li, @arg, or
      ...
    ) -\setlistdepth{12} -\newlist{DoxyItemize}{itemize}{12} -\setlist[DoxyItemize]{label=\textperiodcentered} - -\setlist[DoxyItemize,1]{label=\textbullet} -\setlist[DoxyItemize,2]{label=\normalfont\bfseries \textendash} -\setlist[DoxyItemize,3]{label=\textasteriskcentered} -\setlist[DoxyItemize,4]{label=\textperiodcentered} - -% Used by description lists (using
    ...
    ) -\newenvironment{DoxyDescription}{% - \description% -}{% - \enddescription% -} - -% Used by @image, @dotfile, @dot ... @enddot, and @msc ... @endmsc -% (only if caption is specified) -\newenvironment{DoxyImage}{% - \begin{figure}[H]% - \centering% -}{% - \end{figure}% -} - -% Used by @image, @dotfile, @dot ... @enddot, and @msc ... @endmsc -% (only if no caption is specified) -\newenvironment{DoxyImageNoCaption}{% - \begin{center}% -}{% - \end{center}% -} - -% Used by @image -% (only if inline is specified) -\newenvironment{DoxyInlineImage}{% -}{% -} - -% Used by @attention -\newenvironment{DoxyAttention}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @author and @authors -\newenvironment{DoxyAuthor}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @date -\newenvironment{DoxyDate}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @invariant -\newenvironment{DoxyInvariant}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @note -\newenvironment{DoxyNote}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @post -\newenvironment{DoxyPostcond}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @pre -\newenvironment{DoxyPrecond}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @copyright -\newenvironment{DoxyCopyright}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @remark -\newenvironment{DoxyRemark}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @return and @returns -\newenvironment{DoxyReturn}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @since -\newenvironment{DoxySince}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @see -\newenvironment{DoxySeeAlso}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @version -\newenvironment{DoxyVersion}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @warning -\newenvironment{DoxyWarning}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by @par and @paragraph -\newenvironment{DoxyParagraph}[1]{% - \begin{DoxyDesc}{#1}% -}{% - \end{DoxyDesc}% -} - -% Used by parameter lists -\newenvironment{DoxyParams}[2][]{% - \tabulinesep=1mm% - \par% - \ifthenelse{\equal{#1}{}}% - {\begin{longtabu*}spread 0pt [l]{|X[-1,l]|X[-1,l]|}}% name + description - {\ifthenelse{\equal{#1}{1}}% - {\begin{longtabu*}spread 0pt [l]{|X[-1,l]|X[-1,l]|X[-1,l]|}}% in/out + name + desc - {\begin{longtabu*}spread 0pt [l]{|X[-1,l]|X[-1,l]|X[-1,l]|X[-1,l]|}}% in/out + type + name + desc - } - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #2}\\[1ex]% - \hline% - \endfirsthead% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #2}\\[1ex]% - \hline% - \endhead% -}{% - \end{longtabu*}% - \vspace{6pt}% -} - -% Used for fields of simple structs -\newenvironment{DoxyFields}[1]{% - \tabulinesep=1mm% - \par% - \begin{longtabu*}spread 0pt [l]{|X[-1,r]|X[-1,l]|X[-1,l]|}% - \multicolumn{3}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endfirsthead% - \multicolumn{3}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endhead% -}{% - \end{longtabu*}% - \vspace{6pt}% -} - -% Used for fields simple class style enums -\newenvironment{DoxyEnumFields}[1]{% - \tabulinesep=1mm% - \par% - \begin{longtabu*}spread 0pt [l]{|X[-1,r]|X[-1,l]|}% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endfirsthead% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endhead% -}{% - \end{longtabu*}% - \vspace{6pt}% -} - -% Used for parameters within a detailed function description -\newenvironment{DoxyParamCaption}{% - \renewcommand{\item}[2][]{\\ \hspace*{2.0cm} ##1 {\em ##2}}% -}{% -} - -% Used by return value lists -\newenvironment{DoxyRetVals}[1]{% - \tabulinesep=1mm% - \par% - \begin{longtabu*}spread 0pt [l]{|X[-1,r]|X[-1,l]|}% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endfirsthead% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endhead% -}{% - \end{longtabu*}% - \vspace{6pt}% -} - -% Used by exception lists -\newenvironment{DoxyExceptions}[1]{% - \tabulinesep=1mm% - \par% - \begin{longtabu*}spread 0pt [l]{|X[-1,r]|X[-1,l]|}% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endfirsthead% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endhead% -}{% - \end{longtabu*}% - \vspace{6pt}% -} - -% Used by template parameter lists -\newenvironment{DoxyTemplParams}[1]{% - \tabulinesep=1mm% - \par% - \begin{longtabu*}spread 0pt [l]{|X[-1,r]|X[-1,l]|}% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endfirsthead% - \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% - \hline% - \endhead% -}{% - \end{longtabu*}% - \vspace{6pt}% -} - -% Used for member lists -\newenvironment{DoxyCompactItemize}{% - \begin{itemize}% - \setlength{\itemsep}{-3pt}% - \setlength{\parsep}{0pt}% - \setlength{\topsep}{0pt}% - \setlength{\partopsep}{0pt}% -}{% - \end{itemize}% -} - -% Used for member descriptions -\newenvironment{DoxyCompactList}{% - \begin{list}{}{% - \setlength{\leftmargin}{0.5cm}% - \setlength{\itemsep}{0pt}% - \setlength{\parsep}{0pt}% - \setlength{\topsep}{0pt}% - \renewcommand{\makelabel}{\hfill}% - }% -}{% - \end{list}% -} - -% Used for reference lists (@bug, @deprecated, @todo, etc.) -\newenvironment{DoxyRefList}{% - \begin{list}{}{% - \setlength{\labelwidth}{10pt}% - \setlength{\leftmargin}{\labelwidth}% - \addtolength{\leftmargin}{\labelsep}% - \renewcommand{\makelabel}{\xreflabel}% - }% -}{% - \end{list}% -} - -% Used by @bug, @deprecated, @todo, etc. -\newenvironment{DoxyRefDesc}[1]{% - \begin{list}{}{% - \renewcommand\makelabel[1]{\textbf{##1}}% - \settowidth\labelwidth{\makelabel{#1}}% - \setlength\leftmargin{\labelwidth+\labelsep}% - }% -}{% - \end{list}% -} - -% Used by parameter lists and simple sections -\newenvironment{Desc} -{\begin{list}{}{% - \settowidth{\labelwidth}{20pt}% - \setlength{\parsep}{0pt}% - \setlength{\itemsep}{0pt}% - \setlength{\leftmargin}{\labelwidth+\labelsep}% - \renewcommand{\makelabel}{\entrylabel}% - } -}{% - \end{list}% -} - -% Used by tables -\newcommand{\PBS}[1]{\let\temp=\\#1\let\\=\temp}% -\newenvironment{TabularC}[1]% -{\tabulinesep=1mm -\begin{longtabu*}spread 0pt [c]{*#1{|X[-1]}|}}% -{\end{longtabu*}\par}% - -\newenvironment{TabularNC}[1]% -{\begin{tabu}spread 0pt [l]{*#1{|X[-1]}|}}% -{\end{tabu}\par}% - -% Used for member group headers -\newenvironment{Indent}{% - \begin{list}{}{% - \setlength{\leftmargin}{0.5cm}% - }% - \item[]\ignorespaces% -}{% - \unskip% - \end{list}% -} - -% Used when hyperlinks are turned on -\newcommand{\doxylink}[2]{% - \mbox{\hyperlink{#1}{#2}}% -} - -% Used when hyperlinks are turned on -% Third argument is the SectionType, see the doxygen internal -% documentation for the values (relevant: Page ... Subsubsection). -\newcommand{\doxysectlink}[3]{% - \mbox{\hyperlink{#1}{#2}}% -} -% Used when hyperlinks are turned off -\newcommand{\doxyref}[3]{% - \textbf{#1} (\textnormal{#2}\,\pageref{#3})% -} - -% Used when hyperlinks are turned off -% Fourth argument is the SectionType, see the doxygen internal -% documentation for the values (relevant: Page ... Subsubsection). -\newcommand{\doxysectref}[4]{% - \textbf{#1} (\textnormal{#2}\,\pageref{#3})% -} - -% Used to link to a table when hyperlinks are turned on -\newcommand{\doxytablelink}[2]{% - \ref{#1}% -} - -% Used to link to a table when hyperlinks are turned off -\newcommand{\doxytableref}[3]{% - \ref{#3}% -} - -% Used by @addindex -\newcommand{\lcurly}{\{} -\newcommand{\rcurly}{\}} - -% Colors used for syntax highlighting -\definecolor{comment}{rgb}{0.5,0.0,0.0} -\definecolor{keyword}{rgb}{0.0,0.5,0.0} -\definecolor{keywordtype}{rgb}{0.38,0.25,0.125} -\definecolor{keywordflow}{rgb}{0.88,0.5,0.0} -\definecolor{preprocessor}{rgb}{0.5,0.38,0.125} -\definecolor{stringliteral}{rgb}{0.0,0.125,0.25} -\definecolor{charliteral}{rgb}{0.0,0.5,0.5} -\definecolor{xmlcdata}{rgb}{0.0,0.0,0.0} -\definecolor{vhdldigit}{rgb}{1.0,0.0,1.0} -\definecolor{vhdlkeyword}{rgb}{0.43,0.0,0.43} -\definecolor{vhdllogic}{rgb}{1.0,0.0,0.0} -\definecolor{vhdlchar}{rgb}{0.0,0.0,0.0} - -% Color used for table heading -\newcommand{\tableheadbgcolor}{lightgray}% - -% Version of hypertarget with correct landing location -\newcommand{\Hypertarget}[1]{\Hy@raisedlink{\hypertarget{#1}{}}} - -% possibility to have sections etc. be within the margins -% unfortunately had to copy part of book.cls and add \raggedright -\makeatletter -\newcounter{subsubsubsection}[subsubsection] -\newcounter{subsubsubsubsection}[subsubsubsection] -\newcounter{subsubsubsubsubsection}[subsubsubsubsection] -\newcounter{subsubsubsubsubsubsection}[subsubsubsubsubsection] -\renewcommand{\thesubsubsubsection}{\thesubsubsection.\arabic{subsubsubsection}} -\renewcommand{\thesubsubsubsubsection}{\thesubsubsubsection.\arabic{subsubsubsubsection}} -\renewcommand{\thesubsubsubsubsubsection}{\thesubsubsubsubsection.\arabic{subsubsubsubsubsection}} -\renewcommand{\thesubsubsubsubsubsubsection}{\thesubsubsubsubsubsection.\arabic{subsubsubsubsubsubsection}} -\newcommand{\subsubsubsectionmark}[1]{} -\newcommand{\subsubsubsubsectionmark}[1]{} -\newcommand{\subsubsubsubsubsectionmark}[1]{} -\newcommand{\subsubsubsubsubsubsectionmark}[1]{} -\def\toclevel@subsubsubsection{4} -\def\toclevel@subsubsubsubsection{5} -\def\toclevel@subsubsubsubsubsection{6} -\def\toclevel@subsubsubsubsubsubsection{7} -\def\toclevel@paragraph{8} -\def\toclevel@subparagraph{9} - -\newcommand\doxysection{\@startsection {section}{1}{\z@}% - {-3.5ex \@plus -1ex \@minus -.2ex}% - {2.3ex \@plus.2ex}% - {\raggedright\normalfont\Large\bfseries}} -\newcommand\doxysubsection{\@startsection{subsection}{2}{\z@}% - {-3.25ex\@plus -1ex \@minus -.2ex}% - {1.5ex \@plus .2ex}% - {\raggedright\normalfont\large\bfseries}} -\newcommand\doxysubsubsection{\@startsection{subsubsection}{3}{\z@}% - {-3.25ex\@plus -1ex \@minus -.2ex}% - {1.5ex \@plus .2ex}% - {\raggedright\normalfont\normalsize\bfseries}} -\newcommand\doxysubsubsubsection{\@startsection{subsubsubsection}{4}{\z@}% - {-3.25ex\@plus -1ex \@minus -.2ex}% - {1.5ex \@plus .2ex}% - {\raggedright\normalfont\normalsize\bfseries}} -\newcommand\doxysubsubsubsubsection{\@startsection{subsubsubsubsection}{5}{\z@}% - {-3.25ex\@plus -1ex \@minus -.2ex}% - {1.5ex \@plus .2ex}% - {\raggedright\normalfont\normalsize\bfseries}} -\newcommand\doxysubsubsubsubsubsection{\@startsection{subsubsubsubsubsection}{6}{\z@}% - {-3.25ex\@plus -1ex \@minus -.2ex}% - {1.5ex \@plus .2ex}% - {\raggedright\normalfont\normalsize\bfseries}} -\newcommand\doxysubsubsubsubsubsubsection{\@startsection{subsubsubsubsubsubsection}{7}{\z@}% - {-3.25ex\@plus -1ex \@minus -.2ex}% - {1.5ex \@plus .2ex}% - {\raggedright\normalfont\normalsize\bfseries}} -\newcommand\doxyparagraph{\@startsection{paragraph}{8}{\z@}% - {-3.25ex\@plus -1ex \@minus -.2ex}% - {1.5ex \@plus .2ex}% - {\raggedright\normalfont\normalsize\bfseries}} -\newcommand\doxysubparagraph{\@startsection{subparagraph}{9}{\parindent}% - {-3.25ex\@plus -1ex \@minus -.2ex}% - {1.5ex \@plus .2ex}% - {\raggedright\normalfont\normalsize\bfseries}} - -\newcommand\l@subsubsubsection{\@dottedtocline{4}{6.1em}{7.8em}} -\newcommand\l@subsubsubsubsection{\@dottedtocline{5}{6.1em}{9.4em}} -\newcommand\l@subsubsubsubsubsection{\@dottedtocline{6}{6.1em}{11em}} -\newcommand\l@subsubsubsubsubsubsection{\@dottedtocline{7}{6.1em}{12.6em}} -\renewcommand\l@paragraph{\@dottedtocline{8}{6.1em}{14.2em}} -\renewcommand\l@subparagraph{\@dottedtocline{9}{6.1em}{15.8em}} -\makeatother -% the sectsty doesn't look to be maintained but gives, in our case, some warning like: -% LaTeX Warning: Command \underline has changed. -% Check if current package is valid. -% unfortunately had to copy the relevant part -\newcommand*{\doxypartfont} [1] - {\gdef\SS@partnumberfont{\SS@sectid{0}\SS@nopart\SS@makeulinepartchap#1} - \gdef\SS@parttitlefont{\SS@sectid{0}\SS@titlepart\SS@makeulinepartchap#1}} -\newcommand*{\doxychapterfont} [1] - {\gdef\SS@chapnumfont{\SS@sectid{1}\SS@nopart\SS@makeulinepartchap#1} - \gdef\SS@chaptitlefont{\SS@sectid{1}\SS@titlepart\SS@makeulinepartchap#1}} -\newcommand*{\doxysectionfont} [1] - {\gdef\SS@sectfont{\SS@sectid{2}\SS@rr\SS@makeulinesect#1}} -\newcommand*{\doxysubsectionfont} [1] - {\gdef\SS@subsectfont{\SS@sectid{3}\SS@rr\SS@makeulinesect#1}} -\newcommand*{\doxysubsubsectionfont} [1] - {\gdef\SS@subsubsectfont{\SS@sectid{4}\SS@rr\SS@makeulinesect#1}} -\newcommand*{\doxyparagraphfont} [1] - {\gdef\SS@parafont{\SS@sectid{5}\SS@rr\SS@makeulinesect#1}} -\newcommand*{\doxysubparagraphfont} [1] - {\gdef\SS@subparafont{\SS@sectid{6}\SS@rr\SS@makeulinesect#1}} -\newcommand*{\doxyminisecfont} [1] - {\gdef\SS@minisecfont{\SS@sectid{7}\SS@rr\SS@makeulinepartchap#1}} -\newcommand*{\doxyallsectionsfont} [1] {\doxypartfont{#1}% - \doxychapterfont{#1}% - \doxysectionfont{#1}% - \doxysubsectionfont{#1}% - \doxysubsubsectionfont{#1}% - \doxyparagraphfont{#1}% - \doxysubparagraphfont{#1}% - \doxyminisecfont{#1}}% -% Define caption that is also suitable in a table -\makeatletter -\def\doxyfigcaption{% -\H@refstepcounter{figure}% -\@dblarg{\@caption{figure}}} -\makeatother - -% Define alpha enumarative names for counters > 26 -\makeatletter -\def\enumalphalphcnt#1{\expandafter\@enumalphalphcnt\csname c@#1\endcsname} -\def\@enumalphalphcnt#1{\alphalph{#1}} -\def\enumAlphAlphcnt#1{\expandafter\@enumAlphAlphcnt\csname c@#1\endcsname} -\def\@enumAlphAlphcnt#1{\AlphAlph{#1}} -\makeatother -\AddEnumerateCounter{\enumalphalphcnt}{\@enumalphalphcnt}{aa} -\AddEnumerateCounter{\enumAlphAlphcnt}{\@enumAlphAlphcnt}{AA} diff --git a/documentation/latex/etoc_doxygen.sty b/documentation/latex/etoc_doxygen.sty deleted file mode 100644 index 5f7e127..0000000 --- a/documentation/latex/etoc_doxygen.sty +++ /dev/null @@ -1,2178 +0,0 @@ -%% -%% This is file etoc_doxygen.sty -%% -%% Apart from this header notice and the renaming from etoc to -%% etoc_doxygen (also in \ProvidesPackage) it is an identical -%% copy of -%% -%% etoc.sty -%% -%% at version 1.2b of 2023/07/01. -%% -%% This file has been provided to Doxygen team courtesy of the -%% author for benefit of users having a LaTeX installation not -%% yet providing version 1.2a or later of etoc, whose -%% deeplevels feature is required. -%% -%% The original source etoc.dtx (only of the latest version at -%% any given time) is available at -%% -%% https://ctan.org/pkg/etoc -%% -%% and contains the terms for copying and modification as well -%% as author contact information. -%% -%% In brief any modified versions of this file must be renamed -%% with new filenames distinct from etoc.sty. -%% -%% Package: etoc -%% Version: 1.2b -%% License: LPPL 1.3c -%% Copyright (C) 2012-2023 Jean-Francois B. -\NeedsTeXFormat{LaTeX2e}[2003/12/01] -\ProvidesPackage{etoc_doxygen}[2023/07/01 v1.2b Completely customisable TOCs (JFB)] -\newif\ifEtoc@oldLaTeX -\@ifl@t@r\fmtversion{2020/10/01} - {} - {\Etoc@oldLaTeXtrue - \PackageInfo{etoc}{Old LaTeX (\fmtversion) detected!\MessageBreak - Since 1.1a (2023/01/14), etoc prefers LaTeX at least\MessageBreak - as recent as 2020-10-01, for reasons of the .toc file,\MessageBreak - and used to require it (from 1.1a to 1.2).\MessageBreak - This etoc (1.2b) does not *require* it, but has not been\MessageBreak - tested thoroughly on old LaTeX (especially if document\MessageBreak - does not use hyperref) and retrofitting was done only\MessageBreak - on basis of author partial remembrances of old context.\MessageBreak - Reported}} -\RequirePackage{kvoptions} -\SetupKeyvalOptions{prefix=Etoc@} -\newif\ifEtoc@lof -\DeclareVoidOption{lof}{\Etoc@loftrue - \PackageInfo{etoc}{Experimental support for \string\locallistoffigures.\MessageBreak - Barely tested, use at own risk}% -} -\newif\ifEtoc@lot -\DeclareVoidOption{lot}{\Etoc@lottrue - \PackageInfo{etoc}{Experimental support for \string\locallistoftables.\MessageBreak - Barely tested, use at own risk}% -} -\@ifclassloaded{memoir}{ -\PackageInfo{etoc} - {As this is with memoir class, all `...totoc' options\MessageBreak - are set true by default. Reported} -\DeclareBoolOption[true]{maintoctotoc} -\DeclareBoolOption[true]{localtoctotoc} -\DeclareBoolOption[true]{localloftotoc} -\DeclareBoolOption[true]{locallottotoc} -}{ -\DeclareBoolOption[false]{maintoctotoc} -\DeclareBoolOption[false]{localtoctotoc} -\DeclareBoolOption[false]{localloftotoc} -\DeclareBoolOption[false]{locallottotoc} -} -\DeclareBoolOption[true]{ouroboros} -\DeclareBoolOption[false]{deeplevels} -\DeclareDefaultOption{\PackageWarning{etoc}{Option `\CurrentOption' is unknown.}} -\ProcessKeyvalOptions* -\DisableKeyvalOption[action=error,package=etoc]{etoc}{lof} -\DisableKeyvalOption[action=error,package=etoc]{etoc}{lot} -\DisableKeyvalOption[action=error,package=etoc]{etoc}{deeplevels} -\def\etocsetup#1{\setkeys{etoc}{#1}} -\def\etocifmaintoctotoc{\ifEtoc@maintoctotoc - \expandafter\@firstoftwo - \else - \expandafter\@secondoftwo - \fi} -\def\etociflocaltoctotoc{\ifEtoc@localtoctotoc - \expandafter\@firstoftwo - \else - \expandafter\@secondoftwo - \fi} -\def\etociflocalloftotoc{\ifEtoc@localloftotoc - \expandafter\@firstoftwo - \else - \expandafter\@secondoftwo - \fi} -\def\etociflocallottotoc{\ifEtoc@locallottotoc - \expandafter\@firstoftwo - \else - \expandafter\@secondoftwo - \fi} -\RequirePackage{multicol} -\def\etoc@{\etoc@} -\long\def\Etoc@gobtoetoc@ #1\etoc@{} -\newtoks\Etoc@toctoks -\def\Etoc@par{\par} -\def\etocinline{\def\Etoc@par{}} -\let\etocnopar\etocinline -\def\etocdisplay{\def\Etoc@par{\par}} -\let\Etoc@global\@empty -\def\etocglobaldefs{\let\Etoc@global\global\let\tof@global\global} -\def\etoclocaldefs {\let\Etoc@global\@empty\let\tof@global\@empty} -\newif\ifEtoc@numbered -\newif\ifEtoc@hyperref -\newif\ifEtoc@parskip -\newif\ifEtoc@tocwithid -\newif\ifEtoc@standardlines -\newif\ifEtoc@etocstyle -\newif\ifEtoc@classstyle -\newif\ifEtoc@keeporiginaltoc -\newif\ifEtoc@skipprefix -\newif\ifEtoc@isfirst -\newif\ifEtoc@localtoc -\newif\ifEtoc@skipthisone -\newif\ifEtoc@stoptoc -\newif\ifEtoc@notactive -\newif\ifEtoc@mustclosegroup -\newif\ifEtoc@isemptytoc -\newif\ifEtoc@checksemptiness -\def\etocchecksemptiness {\Etoc@checksemptinesstrue } -\def\etocdoesnotcheckemptiness {\Etoc@checksemptinessfalse } -\newif\ifEtoc@notocifnotoc -\def\etocnotocifnotoc {\Etoc@checksemptinesstrue\Etoc@notocifnotoctrue } -\newcounter{etoc@tocid} -\def\Etoc@tocext{toc} -\def\Etoc@lofext{lof} -\def\Etoc@lotext{lot} -\let\Etoc@currext\Etoc@tocext -\def\etocifislocal{\ifEtoc@localtoc\expandafter\@firstoftwo\else - \expandafter\@secondoftwo\fi - } -\def\etocifislocaltoc{\etocifislocal{\ifx\Etoc@currext\Etoc@tocext - \expandafter\@firstoftwo\else - \expandafter\@secondoftwo\fi}% - {\@secondoftwo}% - } -\def\etocifislocallof{\etocifislocal{\ifx\Etoc@currext\Etoc@lofext - \expandafter\@firstoftwo\else - \expandafter\@secondoftwo\fi}% - {\@secondoftwo}% - } -\def\etocifislocallot{\etocifislocal{\ifx\Etoc@currext\Etoc@lotext - \expandafter\@firstoftwo\else - \expandafter\@secondoftwo\fi}% - {\@secondoftwo}% - } -\expandafter\def\csname Etoc@-3@@\endcsname {-\thr@@} -\expandafter\def\csname Etoc@-2@@\endcsname {-\tw@} -\expandafter\let\csname Etoc@-1@@\endcsname \m@ne -\expandafter\let\csname Etoc@0@@\endcsname \z@ -\expandafter\let\csname Etoc@1@@\endcsname \@ne -\expandafter\let\csname Etoc@2@@\endcsname \tw@ -\expandafter\let\csname Etoc@3@@\endcsname \thr@@ -\expandafter\chardef\csname Etoc@4@@\endcsname 4 -\expandafter\chardef\csname Etoc@5@@\endcsname 5 -\expandafter\chardef\csname Etoc@6@@\endcsname 6 -\ifEtoc@deeplevels - \expandafter\chardef\csname Etoc@7@@\endcsname 7 - \expandafter\chardef\csname Etoc@8@@\endcsname 8 - \expandafter\chardef\csname Etoc@9@@\endcsname 9 - \expandafter\chardef\csname Etoc@10@@\endcsname 10 - \expandafter\chardef\csname Etoc@11@@\endcsname 11 - \expandafter\chardef\csname Etoc@12@@\endcsname 12 -\fi -\expandafter\let\expandafter\Etoc@maxlevel - \csname Etoc@\ifEtoc@deeplevels12\else6\fi @@\endcsname -\edef\etocthemaxlevel{\number\Etoc@maxlevel} -\@ifclassloaded{memoir}{\def\Etoc@minf{-\thr@@}}{\def\Etoc@minf{-\tw@}} -\let\Etoc@none@@ \Etoc@minf -\expandafter\let\expandafter\Etoc@all@@ - \csname Etoc@\ifEtoc@deeplevels11\else5\fi @@\endcsname -\let\Etoc@dolevels\@empty -\def\Etoc@newlevel #1{\expandafter\def\expandafter\Etoc@dolevels\expandafter - {\Etoc@dolevels\Etoc@do{#1}}} -\ifdefined\expanded - \def\etocsetlevel#1#2{\expanded{\noexpand\etoc@setlevel{#1}{#2}}}% -\else - \def\etocsetlevel#1#2{{\edef\Etoc@tmp{\noexpand\etoc@setlevel{#1}{#2}}\expandafter}\Etoc@tmp}% -\fi -\def\etoc@setlevel#1#2{% - \edef\Etoc@tmp{\the\numexpr#2}% - \if1\ifnum\Etoc@tmp>\Etoc@maxlevel0\fi\unless\ifnum\Etoc@minf<\Etoc@tmp;\fi1% - \ifEtoc@deeplevels - \in@{.#1,}{.none,.all,.figure,.table,.-3,.-2,.-1,.0,.1,.2,.3,.4,.5,.6,% - .7,.8,.9,.10,.11,.12,}% - \else - \in@{.#1,}{.none,.all,.figure,.table,.-3,.-2,.-1,.0,.1,.2,.3,.4,.5,.6,}% - \fi - \ifin@\else\if\@car#1\@nil @\in@true\fi\fi - \ifin@ - \PackageWarning{etoc} - {Sorry, but `#1' is forbidden as level name.\MessageBreak - \if\@car#1\@nil @% - (because of the @ as first character)\MessageBreak\fi - Reported}% - \else - \etocifunknownlevelTF{#1}{\Etoc@newlevel{#1}}{}% - \expandafter\let\csname Etoc@#1@@\expandafter\endcsname - \csname Etoc@\Etoc@tmp @@\endcsname - \expandafter\edef\csname Etoc@@#1@@\endcsname - {\expandafter\noexpand\csname Etoc@#1@@\endcsname}% - \expandafter\edef\csname toclevel@@#1\endcsname - {\expandafter\noexpand\csname toclevel@#1\endcsname}% - \fi - \else - \PackageWarning{etoc} - {Argument `\detokenize{#2}' of \string\etocsetlevel\space should - represent one of\MessageBreak - \ifnum\Etoc@minf=-\thr@@-2, \fi-1, 0, 1, 2, \ifEtoc@deeplevels ...\else3, 4\fi, - \the\numexpr\Etoc@maxlevel-1, or \number\Etoc@maxlevel\space - but evaluates to \Etoc@tmp.\MessageBreak - The level of `#1' will be set to \number\Etoc@maxlevel.\MessageBreak - Tables of contents will ignore `#1' as long\MessageBreak - as its level is \number\Etoc@maxlevel\space (=\string\etocthemaxlevel).% - \MessageBreak - Reported}% - \etocifunknownlevelTF{#1}{\Etoc@newlevel{#1}}{}% - \expandafter\let\csname Etoc@#1@@\endcsname\Etoc@maxlevel - \fi -} -\def\etoclevel#1{\csname Etoc@#1@@\endcsname} -\def\etocthelevel#1{\number\csname Etoc@#1@@\endcsname} -\def\etocifunknownlevelTF#1{\@ifundefined{Etoc@#1@@}} -\@ifclassloaded{memoir}{\etocsetlevel{book}{-2}}{} -\etocsetlevel{part}{-1} -\etocsetlevel{chapter}{0} -\etocsetlevel{section}{1} -\etocsetlevel{subsection}{2} -\etocsetlevel{subsubsection}{3} -\etocsetlevel{paragraph}{4} -\etocsetlevel{subparagraph}{5} -\ifdefined\c@chapter - \etocsetlevel{appendix}{0} -\else - \etocsetlevel{appendix}{1} -\fi -\def\Etoc@do#1{\@namedef{l@@#1}{\csname l@#1\endcsname}} -\Etoc@dolevels -\let\Etoc@figure@@\Etoc@maxlevel -\let\Etoc@table@@ \Etoc@maxlevel -\let\Etoc@gobblethreeorfour\@gobblefour -\ifdefined\@gobblethree - \let\Etoc@gobblethree\@gobblethree -\else - \long\def\Etoc@gobblethree#1#2#3{}% -\fi -\AtBeginDocument{% -\@ifpackageloaded{parskip}{\Etoc@parskiptrue}{}% -\@ifpackageloaded{hyperref} - {\Etoc@hyperreftrue} - {\ifEtoc@oldLaTeX - \let\Etoc@gobblethreeorfour\Etoc@gobblethree - \let\Etoc@etoccontentsline@fourargs\Etoc@etoccontentsline@ - \long\def\Etoc@etoccontentsline@#1#2#3{% - \Etoc@etoccontentsline@fourargs{#1}{#2}{#3}{}% - }% - \fi - }% -} -\def\etocskipfirstprefix {\global\Etoc@skipprefixtrue } -\def\Etoc@updatestackofends#1\etoc@{\gdef\Etoc@stackofends{#1}} -\def\Etoc@stackofends{{-3}{}} -\def\Etoc@doendsandbegin{% - \expandafter\Etoc@traversestackofends\Etoc@stackofends\etoc@ -} -\def\Etoc@traversestackofends#1{% - \ifnum#1>\Etoc@level - \csname Etoc@end@#1\endcsname - \expandafter\Etoc@traversestackofends - \else - \Etoc@traversestackofends@done{#1}% - \fi -} -\def\Etoc@traversestackofends@done#1#2{#2% - \ifnum#1<\Etoc@level - \csname Etoc@begin@\the\numexpr\Etoc@level\endcsname - \Etoc@global\Etoc@isfirsttrue - \edef\Etoc@tmp{{\the\numexpr\Etoc@level}}% - \else - \Etoc@global\Etoc@isfirstfalse - \let\Etoc@tmp\@empty - \fi - \expandafter\Etoc@updatestackofends\Etoc@tmp{#1}% -} -\def\Etoc@etoccontentsline #1{% - \let\Etoc@next\Etoc@gobblethreeorfour - \ifnum\csname Etoc@#1@@\endcsname=\Etoc@maxlevel - \else - \Etoc@skipthisonefalse - \global\expandafter\let\expandafter\Etoc@level\csname Etoc@#1@@\endcsname - \if @\@car#1\@nil\else\global\let\Etoc@virtualtop\Etoc@level\fi - \ifEtoc@localtoc - \ifEtoc@stoptoc - \Etoc@skipthisonetrue - \else - \ifEtoc@notactive - \Etoc@skipthisonetrue - \else - \unless\ifnum\Etoc@level>\etoclocaltop - \Etoc@skipthisonetrue - \global\Etoc@stoptoctrue - \fi - \fi - \fi - \fi - \ifEtoc@skipthisone - \else - \unless\ifnum\Etoc@level>\c@tocdepth - \ifEtoc@standardlines - \let\Etoc@next\Etoc@savedcontentsline - \else - \let\Etoc@next\Etoc@etoccontentsline@ - \fi - \fi - \fi - \fi - \Etoc@next{#1}% -} -\def\Etoc@etoccontentsline@ #1#2#3#4{% - \Etoc@doendsandbegin - \Etoc@global\edef\Etoc@prefix {\expandafter\noexpand - \csname Etoc@prefix@\the\numexpr\Etoc@level\endcsname }% - \Etoc@global\edef\Etoc@contents{\expandafter\noexpand - \csname Etoc@contents@\the\numexpr\Etoc@level\endcsname }% - \ifEtoc@skipprefix \Etoc@global\def\Etoc@prefix{\@empty}\fi - \global\Etoc@skipprefixfalse - \Etoc@lxyz{#2}{#3}{#4}% - \Etoc@prefix - \Etoc@contents -} -\def\Etoc@lxyz #1#2#3{% - \ifEtoc@hyperref - \Etoc@global\def\etocthelink##1{\hyperlink{#3}{##1}}% - \else - \Etoc@global\let\etocthelink\@firstofone - \fi - \Etoc@global\def\etocthepage {#2}% - \ifEtoc@hyperref - \ifx\etocthepage\@empty - \Etoc@global\let\etocthelinkedpage\@empty - \else - \Etoc@global\def\etocthelinkedpage{\hyperlink {#3}{#2}}% - \fi - \else - \Etoc@global\let\etocthelinkedpage\etocthepage - \fi - \Etoc@global\def\etocthename{#1}% - \futurelet\Etoc@getnb@token\Etoc@@getnb #1\hspace\etoc@ - \ifEtoc@hyperref - \def\Etoc@tmp##1##2{\Etoc@global\def##2{\hyperlink{#3}{##1}}}% - \expandafter\Etoc@tmp\expandafter{\etocthename}\etocthelinkedname - \ifEtoc@numbered - \expandafter\Etoc@tmp\expandafter{\etocthenumber}\etocthelinkednumber - \else - \Etoc@global\let\etocthelinkednumber\@empty - \fi - \else - \Etoc@global\let\etocthelinkedname \etocthename - \Etoc@global\let\etocthelinkednumber\etocthenumber - \fi - \Etoc@global\expandafter\let\csname etoclink \endcsname \etocthelink - \Etoc@global\expandafter\let\csname etocname \endcsname \etocthename - \Etoc@global\expandafter\let\csname etocnumber \endcsname\etocthenumber - \Etoc@global\expandafter\let\csname etocpage \endcsname \etocthepage - \ifEtoc@hyperref - \Etoc@lxyz@linktoc - \fi -} -\def\Etoc@lxyz@linktoc{% - \ifcase\Hy@linktoc - \or - \Etoc@global\expandafter\let\csname etocname \endcsname\etocthelinkedname - \Etoc@global\expandafter\let\csname etocnumber \endcsname\etocthelinkednumber - \or % page - \Etoc@global\expandafter\let\csname etocpage \endcsname\etocthelinkedpage - \else % all - \Etoc@global\expandafter\let\csname etocname \endcsname\etocthelinkedname - \Etoc@global\expandafter\let\csname etocnumber \endcsname\etocthelinkednumber - \Etoc@global\expandafter\let\csname etocpage \endcsname\etocthelinkedpage - \fi -} -\def\Etoc@@getnb {% - \let\Etoc@next\Etoc@getnb - \ifx\Etoc@getnb@token\@sptoken\let\Etoc@next\Etoc@getnb@nonbr\fi - \ifx\Etoc@getnb@token\bgroup \let\Etoc@next\Etoc@getnb@nonbr\fi - \Etoc@next -} -\def\Etoc@getnb #1{% - \in@{#1}{\numberline\chapternumberline\partnumberline\booknumberline}% - \ifin@ - \let\Etoc@next\Etoc@getnb@nmbrd - \else - \ifnum\Etoc@level=\m@ne - \let\Etoc@next\Etoc@@getit - \else - \let\Etoc@next\Etoc@getnb@nonbr - \fi - \in@{#1}{\nonumberline}% - \ifin@ - \let\Etoc@next\Etoc@getnb@nonumberline - \fi - \fi - \Etoc@next #1% -} -\def\Etoc@getnb@nmbrd #1#2{% - \Etoc@global\Etoc@numberedtrue - \Etoc@global\def\etocthenumber {#2}% - \Etoc@getnb@nmbrd@getname\@empty -}% -\def\Etoc@getnb@nmbrd@getname #1\hspace\etoc@ {% - \Etoc@global\expandafter\def\expandafter\etocthename\expandafter{#1}% -} -\def\Etoc@getnb@nonbr #1\etoc@ {% - \Etoc@global\Etoc@numberedfalse - \Etoc@global\let\etocthenumber \@empty -} -\def\Etoc@getnb@nonumberline #1\hspace\etoc@ {% - \Etoc@global\Etoc@numberedfalse - \Etoc@global\let\etocthenumber \@empty - \Etoc@global\expandafter\def\expandafter\etocthename\expandafter{\@gobble#1}% -} -\def\Etoc@@getit #1\hspace#2{% - \ifx\etoc@#2% - \Etoc@global\Etoc@numberedfalse - \Etoc@global\let\etocthenumber \@empty - \else - \Etoc@global\Etoc@numberedtrue - \Etoc@global\def\etocthenumber {#1}% - \expandafter\Etoc@getit@getname \expandafter\@empty - \fi -} -\def\Etoc@getit@getname #1\hspace\etoc@ {% - \Etoc@global\expandafter\def\expandafter\etocthename\expandafter{#1}% -} -\let\etocthename \@empty -\let\etocthenumber \@empty -\let\etocthepage \@empty -\let\etocthelinkedname \@empty -\let\etocthelinkednumber \@empty -\let\etocthelinkedpage \@empty -\let\etocthelink \@firstofone -\DeclareRobustCommand*{\etocname} {} -\DeclareRobustCommand*{\etocnumber}{} -\DeclareRobustCommand*{\etocpage} {} -\DeclareRobustCommand*{\etoclink} {\@firstofone} -\DeclareRobustCommand*{\etocifnumbered} - {\ifEtoc@numbered\expandafter\@firstoftwo\else\expandafter\@secondoftwo\fi} -\expandafter\let\expandafter\etocxifnumbered\csname etocifnumbered \endcsname -\DeclareRobustCommand*{\etociffirst} - {\ifEtoc@isfirst\expandafter\@firstoftwo\else\expandafter\@secondoftwo\fi} -\expandafter\let\expandafter\etocxiffirst\csname etociffirst \endcsname -\def\Etoc@readtoc {% - \ifeof \Etoc@tf - \else - \read \Etoc@tf to \Etoc@buffer - \Etoc@toctoks=\expandafter\expandafter\expandafter - {\expandafter\the\expandafter\Etoc@toctoks\Etoc@buffer}% - \expandafter\Etoc@readtoc - \fi -} -\Etoc@toctoks {}% (superfluous, but for clarity) -\AtBeginDocument{\IfFileExists{\jobname.toc} - {{\endlinechar=\m@ne - \makeatletter - \newread\Etoc@tf - \openin\Etoc@tf\@filef@und - \Etoc@readtoc - \global\Etoc@toctoks=\expandafter{\the\Etoc@toctoks}% - \closein\Etoc@tf}} - {\typeout{No file \jobname.toc.}}} -\def\Etoc@openouttoc{% - \ifEtoc@hyperref - \ifx\hyper@last\@undefined - \IfFileExists{\jobname .toc} - {\Hy@WarningNoLine - {old toc file detected; run LaTeX again (cheers from `etoc')}% - \global\Etoc@toctoks={}% - } - {}% - \fi - \fi - \if@filesw - \newwrite \tf@toc - \immediate \openout \tf@toc \jobname .toc\relax - \fi - \global\let\Etoc@openouttoc\empty -} -\def\Etoc@toctoc{% - \gdef\Etoc@stackofends{{-3}{}}% - \global\let\Etoc@level\Etoc@minf - \global\let\Etoc@virtualtop\Etoc@minf - \the\Etoc@toctoks - \ifEtoc@notactive - \else - \gdef\Etoc@level{-\thr@@}% - \Etoc@doendsandbegin - \fi -} -\def\Etoc@@startlocaltoc#1#2{% - \ifEtoc@localtoc - \ifnum #1=#2\relax - \global\let\etoclocaltop\Etoc@virtualtop - \Etoc@@startlocaltochook - \etoclocaltableofcontentshook - \ifEtoc@etocstyle - \etocetoclocaltocmaketitle - \fi - \ifx\Etoc@aftertitlehook\@empty - \else - \ifEtoc@localtoctotoc - \ifEtoc@ouroboros - \else - \let\Etoc@tmp\contentsline - \def\contentsline{\let\contentsline\Etoc@tmp\Etoc@gobblethreeorfour}% - \fi - \fi - \fi - \global\Etoc@notactivefalse - \fi - \fi -} -\let\etoc@startlocaltoc\@gobble -\let\Etoc@@startlocaltoc@toc\Etoc@@startlocaltoc -\let\Etoc@@startlocaltochook\@empty -\unless\ifEtoc@deeplevels - \def\etocdivisionnameatlevel#1{% - \ifcase\numexpr#1\relax - \ifdefined\c@chapter chapter\else section\fi% - \or section% - \or subsection% - \or subsubsection% - \or paragraph% - \or subparagraph% - \or empty% - \else\ifnum\numexpr#1<\m@ne - book% - \else - part% - \fi - \fi - } -\else - \def\etocdivisionnameatlevel#1{% - \ifcase\numexpr#1\relax - \ifdefined\c@chapter chapter\else section\fi% - \or section% - \or subsection% - \or subsubsection% - \or subsubsubsection% - \or subsubsubsubsection% - \or subsubsubsubsubsection% - \or subsubsubsubsubsubsection% - \or paragraph% - \or subparagraph% - \else\ifnum\numexpr#1>\z@ - empty% - \else\ifnum\numexpr#1=\m@ne - part% - \else - book% - \fi\fi - \fi - } -\fi -\def\etoclocalheadtotoc#1#2{\addcontentsline{toc}{@#1}{#2}} -\def\etocglobalheadtotoc{\addcontentsline{toc}} -\providecommand*\UseName{\@nameuse} -\def\etocetoclocaltocmaketitle{% - \UseName{\etocdivisionnameatlevel{\etoclocaltop+1}}*{\localcontentsname}% - \if@noskipsec\leavevmode\par\fi - \etociflocaltoctotoc - {\etocifisstarred - {}% star variant, do not add to toc - {\etoclocalheadtotoc - {\etocdivisionnameatlevel{\etoclocaltop+1}}% - {\localcontentsname}% - }% - }% - {}% -}% -\def\localcontentsname {\contentsname}% -\let\etoclocaltableofcontentshook\@empty -\if1\ifEtoc@lof0\fi\ifEtoc@lot0\fi1% -\else -\AtBeginDocument{% - \let\Etoc@originaladdcontentsline\addcontentsline - \def\addcontentsline{\Etoc@hackedaddcontentsline}% -}% -\fi -\ifEtoc@lof - \ifEtoc@lot - \def\Etoc@hackedaddcontentsline#1{% - \expanded{\noexpand\in@{.#1,}}{.lof,.lot,}% - \ifin@\expandafter\Etoc@hackedaddcontentsline@i - \else\expandafter\Etoc@originaladdcontentsline - \fi {#1}} - \else - \def\Etoc@hackedaddcontentsline#1{% - \expanded{\noexpand\in@{.#1,}}{.lof,}% - \ifin@\expandafter\Etoc@hackedaddcontentsline@i - \else\expandafter\Etoc@originaladdcontentsline - \fi {#1}} - \fi -\else - \def\Etoc@hackedaddcontentsline#1{% - \expanded{\noexpand\in@{.#1,}}{.lot,}% - \ifin@\expandafter\Etoc@hackedaddcontentsline@i - \else\expandafter\Etoc@originaladdcontentsline - \fi {#1}} -\fi -\def\Etoc@hackedaddcontentsline@i#1#2#3{% - \expanded{\noexpand\in@{.#1;#2,}}{.lof;figure,.lot;table,}% - \ifin@ - \addtocontents {toc}{% - \protect\contentsline{#2}{#3}{\thepage}{\ifEtoc@hyperref\@currentHref\fi}% - \ifdefined\protected@file@percent\protected@file@percent\fi - }% - \fi - \Etoc@originaladdcontentsline{#1}{#2}{#3}% -} -\unless\ifdefined\expanded - \def\Etoc@hackedaddcontentsline#1{% - {\edef\Etoc@tmp{\noexpand\in@{.#1,}{\ifEtoc@lof.lof,\fi\ifEtoc@lot.lot,\fi}}\expandafter}% - \Etoc@tmp - \ifin@\expandafter\Etoc@hackedaddcontentsline@i - \else\expandafter\Etoc@originaladdcontentsline - \fi {#1}% - } - \def\Etoc@hackedaddcontentsline@i#1#2#3{% - {\edef\Etoc@tmp{\noexpand\in@{.#1;#2,}}\expandafter}% - \Etoc@tmp{.lof;figure,.lot;table,}% - \ifin@ - \addtocontents {toc}{% - \protect\contentsline{#2}{#3}{\thepage}{\ifEtoc@hyperref\@currentHref\fi}% - \ifdefined\protected@file@percent\protected@file@percent\fi - }% - \fi - \Etoc@originaladdcontentsline{#1}{#2}{#3}% - } -\fi -\def\Etoc@@startlocallistof#1#2#3{% - \ifEtoc@localtoc - \ifnum #2=#3\relax - \global\let\etoclocaltop\Etoc@virtualtop - \global\Etoc@notactivefalse - \Etoc@@startlocaltochook - \csname etoclocallistof#1shook\endcsname - \ifEtoc@etocstyle - \csname etocetoclistof#1smaketitle\endcsname - \fi - \fi - \fi -} -\def\Etoc@@startlocallistof@setlevels#1{% - \ifnum\etoclocaltop<\z@ - \expandafter\let\csname Etoc@#1@@\endcsname\@ne - \else - \expandafter\let\csname Etoc@#1@@\expandafter\endcsname - \csname Etoc@\the\numexpr\etoclocaltop+\@ne @@\endcsname - \fi - \def\Etoc@do##1{% - \ifnum\etoclevel{##1}>\etoclocaltop - \expandafter\let\csname Etoc@##1@@\endcsname\Etoc@maxlevel - \fi}% - \Etoc@dolevels -} -\def\etoclocallistoffigureshook{\etocstandardlines} -\def\etoclocallistoftableshook {\etocstandardlines} -\def\locallistfigurename{\listfigurename} -\def\locallisttablename {\listtablename} -\def\etocetoclistoffiguresmaketitle{% - \UseName{\etocdivisionnameatlevel{\etoclocaltop+1}}*{\locallistfigurename}% - \ifnum\etoclocaltop>\tw@\mbox{}\par\fi - \etociflocalloftotoc - {\etocifisstarred - {}% star variant, do not add to toc - {\etoclocalheadtotoc - {\etocdivisionnameatlevel{\etoclocaltop+1}}% - {\locallistfigurename}% - }% - }% - {}% -}% -\def\etocetoclistoftablesmaketitle{% - \UseName{\etocdivisionnameatlevel{\etoclocaltop+1}}*{\locallisttablename}% - \ifnum\etoclocaltop>\tw@\mbox{}\par\fi - \etociflocallottotoc - {\etocifisstarred - {}% star variant, do not add to toc - {\etoclocalheadtotoc - {\etocdivisionnameatlevel{\etoclocaltop+1}}% - {\locallisttablename}% - }% - }% - {}% -}% -\let\Etoc@listofreset\@empty -\ifEtoc@lof - \def\locallistoffigures{% - \def\Etoc@listofreset{% - \let\Etoc@currext\Etoc@tocext - \let\Etoc@@startlocaltoc\Etoc@@startlocaltoc@toc - \let\Etoc@@startlocaltochook\@empty - \let\Etoc@listofreset\@empty - \let\Etoc@listofhook\@empty - }% - \let\Etoc@currext\Etoc@lofext - \def\Etoc@@startlocaltoc{\Etoc@@startlocallistof{figure}}% - \def\Etoc@@startlocaltochook{\Etoc@@startlocallistof@setlevels{figure}}% - \def\Etoc@listofhook{% - \def\Etoc@do####1{% - \expandafter\let\csname Etoc@@####1@@\endcsname\Etoc@maxlevel - }% - \Etoc@dolevels - }% - \localtableofcontents - } -\else - \def\locallistoffigures{% - \PackageError{etoc}{% - \string\locallistoffigures \on@line\space but\MessageBreak - package was loaded without `lof' option}% - {Try again with \string\usepackage[lof]{etoc}}% - } -\fi -\ifEtoc@lot - \def\locallistoftables{% - \def\Etoc@listofreset{% - \let\Etoc@currext\Etoc@tocext - \let\Etoc@@startlocaltoc\Etoc@@startlocaltoc@toc - \let\Etoc@@startlocaltochook\@empty - \let\Etoc@listofreset\@empty - \let\Etoc@listofhook\@empty - }% - \let\Etoc@currext\Etoc@lotext - \def\Etoc@@startlocaltoc{\Etoc@@startlocallistof{table}}% - \def\Etoc@@startlocaltochook{\Etoc@@startlocallistof@setlevels{table}}% - \def\Etoc@listofhook{% - \def\Etoc@do####1{% - \expandafter\let\csname Etoc@@####1@@\endcsname\Etoc@maxlevel - }% - \Etoc@dolevels - }% - \localtableofcontents - } -\else - \def\locallistoftables{% - \PackageError{etoc}{% - \string\locallistoftable \on@line\space but\MessageBreak - package was loaded without `lot' option}% - {Try again with \string\usepackage[lot]{etoc}}% - } -\fi -\def\Etoc@checkifempty {% - \global\Etoc@isemptytoctrue - \global\Etoc@stoptocfalse - \global\let\Etoc@level\Etoc@minf - \global\let\Etoc@virtualtop\Etoc@minf - \gdef\Etoc@stackofends{{-3}{}}% - \begingroup - \ifEtoc@localtoc - \def\etoc@startlocaltoc##1{% - \ifnum##1=\Etoc@tocid\relax - \global\let\etoclocaltop\Etoc@virtualtop - \Etoc@@startlocaltochook - \global\Etoc@notactivefalse - \fi - }% - \let\contentsline\Etoc@testingcontentslinelocal - \else - \let\contentsline\Etoc@testingcontentsline - \fi - \Etoc@storetocdepth - \let\Etoc@setlocaltop@doendsandbegin\@empty - \the\Etoc@toctoks - \Etoc@restoretocdepth - \endgroup -} -\DeclareRobustCommand*\etocifwasempty - {\ifEtoc@isemptytoc\expandafter\@firstoftwo\else\expandafter\@secondoftwo\fi } -\expandafter\let\expandafter\etocxifwasempty\csname etocifwasempty \endcsname -\def\Etoc@testingcontentslinelocal #1{% - \ifEtoc@stoptoc - \else - \ifnum\csname Etoc@#1@@\endcsname=\Etoc@maxlevel - \else - \global\expandafter\let\expandafter\Etoc@level\csname Etoc@#1@@\endcsname - \if @\@car#1\@nil\else\global\let\Etoc@virtualtop\Etoc@level\fi - \ifEtoc@notactive - \else - \ifnum\Etoc@level>\etoclocaltop - \unless\ifnum\Etoc@level>\c@tocdepth - \global\Etoc@isemptytocfalse - \global\Etoc@stoptoctrue - \fi - \else - \global\Etoc@stoptoctrue - \fi - \fi - \fi - \fi - \Etoc@gobblethreeorfour{}% -} -\def\Etoc@testingcontentsline #1{% - \ifEtoc@stoptoc - \else - \ifnum\csname Etoc@#1@@\endcsname=\Etoc@maxlevel - \else - \unless\ifnum\csname Etoc@#1@@\endcsname>\c@tocdepth - \global\Etoc@isemptytocfalse - \global\Etoc@stoptoctrue - \fi - \fi - \fi - \Etoc@gobblethreeorfour{}% -} -\def\Etoc@localtableofcontents#1{% - \gdef\etoclocaltop{-\@m}% - \Etoc@localtoctrue - \global\Etoc@isemptytocfalse - \edef\Etoc@tocid{#1}% - \ifnum\Etoc@tocid<\@ne - \setbox0\hbox{\ref{Unknown toc ref \@secondoftwo#1. \space Rerun LaTeX}}% - \global\Etoc@stoptoctrue - \gdef\etoclocaltop{-\thr@@}% - \Etoc@tableofcontents - \expandafter\Etoc@gobtoetoc@ - \fi - \global\Etoc@notactivetrue - \ifEtoc@checksemptiness - \Etoc@checkifempty - \fi - \ifEtoc@isemptytoc - \ifEtoc@notactive - \setbox0\hbox{\ref{Unknown toc ID \number\Etoc@tocid. \space Rerun LaTeX}}% - \global\Etoc@isemptytocfalse - \global\Etoc@stoptoctrue - \gdef\etoclocaltop{-\thr@@}% - \Etoc@tableofcontents - \expandafter\expandafter\expandafter\Etoc@gobtoetoc@ - \fi - \else - \global\Etoc@stoptocfalse - \global\Etoc@notactivetrue - \edef\etoc@startlocaltoc##1% - {\noexpand\Etoc@@startlocaltoc{##1}{\Etoc@tocid}}% - \Etoc@tableofcontents - \fi - \@gobble\etoc@ - \endgroup\ifEtoc@mustclosegroup\endgroup\fi - \Etoc@tocdepthreset - \Etoc@listofreset - \etocaftertochook -}% \Etoc@localtableofcontents -\def\Etoc@getref #1{% - \@ifundefined{r@#1} - {0} - {\expandafter\Etoc@getref@i\romannumeral-`0% - \expandafter\expandafter\expandafter - \@car\csname r@#1\endcsname0\@nil\@etoc - }% -} -\def\Etoc@getref@i#1#2\@etoc{\ifnum9<1\string#1 #1#2\else 0\fi} -\def\Etoc@ref#1{\Etoc@localtableofcontents{\Etoc@getref{#1}}} -\def\Etoc@label#1{\label{#1}\futurelet\Etoc@nexttoken\Etoc@t@bleofcontents} -\@firstofone{\def\Etoc@again} {\futurelet\Etoc@nexttoken\Etoc@t@bleofcontents} -\def\Etoc@dothis #1#2\etoc@ {\fi #1} -\def\Etoc@t@bleofcontents{% - \gdef\etoclocaltop{-\@M}% - \ifx\Etoc@nexttoken\label\Etoc@dothis{\expandafter\Etoc@label\@gobble}\fi - \ifx\Etoc@nexttoken\@sptoken\Etoc@dothis{\Etoc@again}\fi - \ifx\Etoc@nexttoken\ref\Etoc@dothis{\expandafter\Etoc@ref\@gobble}\fi - \ifEtoc@tocwithid\Etoc@dothis{\Etoc@localtableofcontents{\c@etoc@tocid}}\fi - \global\Etoc@isemptytocfalse - \ifEtoc@checksemptiness\Etoc@checkifempty\fi - \ifEtoc@isemptytoc - \ifEtoc@notocifnotoc - \expandafter\expandafter\expandafter\@gobble - \fi - \fi - \Etoc@tableofcontents - \endgroup - \ifEtoc@mustclosegroup\endgroup\fi - \Etoc@tocdepthreset - \Etoc@listofreset - \etocaftertochook - \@gobble\etoc@ - }% \Etoc@t@bleofcontents -\def\Etoc@table@fcontents{% - \refstepcounter{etoc@tocid}% - \Etoc@tocwithidfalse - \futurelet\Etoc@nexttoken\Etoc@t@bleofcontents -} -\def\Etoc@localtable@fcontents{% - \refstepcounter{etoc@tocid}% - \addtocontents{toc}{\string\etoc@startlocaltoc{\the\c@etoc@tocid}}% - \Etoc@tocwithidtrue - \futurelet\Etoc@nexttoken\Etoc@t@bleofcontents -} -\def\etoctableofcontents{% - \Etoc@openouttoc - \Etoc@tocdepthset - \begingroup - \@ifstar - {\let\Etoc@aftertitlehook\@empty\Etoc@table@fcontents} - {\def\Etoc@aftertitlehook{\etocaftertitlehook}\Etoc@table@fcontents}% -}% \etoctableofcontents -\def\etocifisstarred{\ifx\Etoc@aftertitlehook\@empty - \expandafter\@firstoftwo\else - \expandafter\@secondoftwo - \fi} -\let\etocoriginaltableofcontents\tableofcontents -\let\tableofcontents\etoctableofcontents -\let\Etoc@listofhook\@empty -\newcommand*\localtableofcontents{% - \Etoc@openouttoc - \Etoc@tocdepthset - \begingroup - \Etoc@listofhook - \@ifstar - {\let\Etoc@aftertitlehook\@empty\Etoc@localtable@fcontents} - {\def\Etoc@aftertitlehook{\etocaftertitlehook}\Etoc@localtable@fcontents}% -}% \localtableofcontents -\newcommand*\localtableofcontentswithrelativedepth[1]{% - \def\Etoc@@startlocaltochook{% - \global\c@tocdepth\numexpr\etoclocaltop+#1\relax - }% - \def\Etoc@listofreset{\let\Etoc@@startlocaltochook\@empty - \let\Etoc@listofreset\@empty}% - \localtableofcontents -}% \localtableofcontentswithrelativedepth -\newcommand\etocsettocstyle[2]{% - \Etoc@etocstylefalse - \Etoc@classstylefalse - \def\Etoc@tableofcontents@user@before{#1}% - \def\Etoc@tableofcontents@user@after {#2}% -}% -\def\etocstoretocstyleinto#1{% -%% \@ifdefinable#1{% - \edef#1{\noexpand\Etoc@etocstylefalse\noexpand\Etoc@classstylefalse - \def\noexpand\Etoc@tableofcontents@user@before{% - \unexpanded\expandafter{\Etoc@tableofcontents@user@before}% - }% - \def\noexpand\Etoc@tableofcontents@user@after{% - \unexpanded\expandafter{\Etoc@tableofcontents@user@after}% - }% - }% -%% }% -}% -\def\Etoc@tableofcontents {% - \Etoc@tableofcontents@etoc@before - \ifEtoc@localtoc\ifEtoc@etocstyle\expandafter\expandafter\expandafter\@gobble\fi\fi - \Etoc@tableofcontents@user@before - \Etoc@tableofcontents@contents - \ifEtoc@localtoc\ifEtoc@etocstyle\expandafter\expandafter\expandafter\@gobble\fi\fi - \Etoc@tableofcontents@user@after - \Etoc@tableofcontents@etoc@after - \@gobble\etoc@ -} -\def\Etoc@tableofcontents@etoc@before{% - \ifnum\c@tocdepth>\Etoc@minf - \else - \expandafter\Etoc@gobtoetoc@ - \fi - \Etoc@par - \Etoc@beforetitlehook - \etocbeforetitlehook - \Etoc@storetocdepth - \let\Etoc@savedcontentsline\contentsline - \let\contentsline\Etoc@etoccontentsline - \ifEtoc@standardlines - \else - \def\Etoc@do##1{% - \expandafter\def\csname etocsaved##1tocline\endcsname - {\PackageError{etoc}{% - \expandafter\string\csname etocsaved##1tocline\endcsname\space - has been deprecated\MessageBreak - at 1.1a and is removed at 1.2.\MessageBreak - Use \expandafter\string\csname l@##1\endcsname\space directly.\MessageBreak - Reported \on@line}% - {I will use \expandafter\string - \csname l@##1\endcsname\space myself for this time.% - }% - \csname l@##1\endcsname - }% - }% - \Etoc@dolevels - \fi -}% -\def\Etoc@tableofcontents@contents{% - \Etoc@tocdepthset - \ifEtoc@parskip\parskip\z@skip\fi - \Etoc@aftertitlehook - \gdef\etoclocaltop{-\thr@@}% - \Etoc@toctoc - \etocaftercontentshook -}% -\def\Etoc@tableofcontents@etoc@after{% - \@nobreakfalse - \Etoc@restoretocdepth - \ifx\Etoc@global\global - \@ifundefined{tof@finish} - {} - {\ifx\tof@finish\@empty - \else - \global\let\contentsline\Etoc@savedcontentsline - \fi - }% - \fi -} -\def\etocsetstyle#1{\ifcsname Etoc@#1@@\endcsname - \expandafter\Etoc@setstyle@a - \else - \expandafter\Etoc@setstyle@error - \fi {#1}% -} -\def\Etoc@setstyle@error #1{% - \PackageWarning{etoc}{`#1' is unknown to etoc. \space Did you\MessageBreak - forget some \string\etocsetlevel{#1}{}?\MessageBreak - Reported}% - \@gobblefour -} -\def\Etoc@setstyle@a #1{% - \edef\Etoc@tmp{\the\numexpr\csname Etoc@#1@@\endcsname}% - \if1\unless\ifnum\Etoc@tmp<\Etoc@maxlevel 0\fi - \unless\ifnum\Etoc@tmp>\Etoc@minf 0\fi1% - \Etoc@standardlinesfalse - \expandafter\Etoc@setstyle@b\expandafter\Etoc@tmp - \else - \ifnum\Etoc@tmp=\Etoc@maxlevel - \in@{.#1,}{.figure,.table,}% - \ifin@ - \PackageWarning{etoc} - {You can not use \string\etocsetstyle\space with `#1'.\MessageBreak - Check the package documentation (in particular about\MessageBreak - \string\etoclocallistoffigureshook/\string\etoclocallistoftableshook)% - \MessageBreak on how to customize - figure and table entries in local\MessageBreak lists. Reported}% - \else - \PackageInfo{etoc} - {Attempt to set the style of `#1',\MessageBreak - whose level is currently the maximal one \etocthemaxlevel,\MessageBreak - which is never displayed. \space This will be ignored\MessageBreak - but note that we do quit compatibility mode.\MessageBreak - Reported}% - \Etoc@standardlinesfalse - \fi - \else - \PackageWarning{etoc}{This should not happen. Reported}% - \fi - \expandafter\@gobblefour - \fi -} -\long\def\Etoc@setstyle@b#1#2#3#4#5{% - \expandafter\def\csname Etoc@begin@#1\endcsname {#2}% - \expandafter\def\csname Etoc@prefix@#1\endcsname {#3}% - \expandafter\def\csname Etoc@contents@#1\endcsname {#4}% - \expandafter\def\csname Etoc@end@#1\endcsname {#5}% -} -\def\Etoc@setstyle@e#1{% - \expandafter\let\csname Etoc@begin@#1\endcsname \@empty - \expandafter\let\csname Etoc@prefix@#1\endcsname \@empty - \expandafter\let\csname Etoc@contents@#1\endcsname \@empty - \expandafter\let\csname Etoc@end@#1\endcsname \@empty -} -\def\Etoc@storelines@a#1{% - \noexpand\Etoc@setstyle@b{#1}% - {\expandafter\Etoc@expandonce\csname Etoc@begin@#1\endcsname}% - {\expandafter\Etoc@expandonce\csname Etoc@prefix@#1\endcsname}% - {\expandafter\Etoc@expandonce\csname Etoc@contents@#1\endcsname}% - {\expandafter\Etoc@expandonce\csname Etoc@end@#1\endcsname}% -} -\def\Etoc@expandonce#1{\unexpanded\expandafter{#1}} -\def\etocstorelinestylesinto#1{% - \edef#1{\Etoc@storelines@a{-2}\Etoc@storelines@a{-1}\Etoc@storelines@a{0}% - \Etoc@storelines@a {1}\Etoc@storelines@a {2}\Etoc@storelines@a{3}% - \Etoc@storelines@a {4}\Etoc@storelines@a {5}% - \ifEtoc@deeplevels - \Etoc@storelines@a{6}\Etoc@storelines@a{7}\Etoc@storelines@a{8}% - \Etoc@storelines@a{9}\Etoc@storelines@a{10}\Etoc@storelines@a{11}% - \fi - }% -} -\def\etocstorethislinestyleinto#1#2{% - \edef#2{\expandafter\Etoc@storelines@a\expandafter{\number\etoclevel{#1}}}% -}% -\def\etocfontminustwo {\normalfont \LARGE \bfseries} -\def\etocfontminusone {\normalfont \large \bfseries} -\def\etocfontzero {\normalfont \large \bfseries} -\def\etocfontone {\normalfont \normalsize \bfseries} -\def\etocfonttwo {\normalfont \normalsize} -\def\etocfontthree {\normalfont \footnotesize} -\def\etocsepminustwo {4ex \@plus .5ex \@minus .5ex} -\def\etocsepminusone {4ex \@plus .5ex \@minus .5ex} -\def\etocsepzero {2.5ex \@plus .4ex \@minus .4ex} -\def\etocsepone {1.5ex \@plus .3ex \@minus .3ex} -\def\etocseptwo {.5ex \@plus .1ex \@minus .1ex} -\def\etocsepthree {.25ex \@plus .05ex \@minus .05ex} -\def\etocbaselinespreadminustwo {1} -\def\etocbaselinespreadminusone {1} -\def\etocbaselinespreadzero {1} -\def\etocbaselinespreadone {1} -\def\etocbaselinespreadtwo {1} -\def\etocbaselinespreadthree {.9} -\def\etocminustwoleftmargin {1.5em plus 0.5fil} -\def\etocminustworightmargin {1.5em plus -0.5fil} -\def\etocminusoneleftmargin {1em} -\def\etocminusonerightmargin {1em} -\def\etoctoclineleaders - {\hbox{\normalfont\normalsize\hb@xt@2ex {\hss.\hss}}} -\def\etocabbrevpagename {p.~} -\def\etocpartname {Part} -\def\etocbookname {Book} -\def\etocdefaultlines{% - \Etoc@standardlinesfalse - \etocdefaultlines@setbook - \etocdefaultlines@setpart - \etocdefaultlines@setchapter - \etocdefaultlines@setsection - \etocdefaultlines@setsubsection - \etocdefaultlines@setsubsubsection - \etocdefaultlines@setdeeperones -} -\def\etocnoprotrusion{\leavevmode\kern-\p@\kern\p@} -\@ifclassloaded{memoir}{% - \def\etocdefaultlines@setbook{% - \Etoc@setstyle@b - {-2}% - {\addpenalty\@M\etocskipfirstprefix} - {\addpenalty\@secpenalty} - {\begingroup - \etocfontminustwo - \addvspace{\etocsepminustwo}% - \parindent \z@ - \leftskip \etocminustwoleftmargin - \rightskip \etocminustworightmargin - \parfillskip \@flushglue - \vbox{\etocifnumbered{\etoclink{\etocbookname\enspace\etocthenumber:\quad}}{}% - \etocname - \baselineskip\etocbaselinespreadminustwo\baselineskip - \par}% - \addpenalty\@M\addvspace{\etocsepminusone}% - \endgroup} - {}% - } - }{\let\etocdefaultlines@setbook\@empty} -\def\etocdefaultlines@setpart{% -\Etoc@setstyle@b - {-1}% - {\addpenalty\@M\etocskipfirstprefix} - {\addpenalty\@secpenalty} - {\begingroup - \etocfontminusone - \addvspace{\etocsepminusone}% - \parindent \z@ - \leftskip \etocminusoneleftmargin - \rightskip \etocminusonerightmargin - \parfillskip \@flushglue - \vbox{\etocifnumbered{\etoclink{\etocpartname\enspace\etocthenumber.\quad}}{}% - \etocname - \baselineskip\etocbaselinespreadminusone\baselineskip - \par}% - \addpenalty\@M\addvspace{\etocsepzero}% - \endgroup} - {}% -} -\def\etocdefaultlines@setchapter{% -\Etoc@setstyle@b - {0}% - {\addpenalty\@M\etocskipfirstprefix} - {\addpenalty\@itempenalty} - {\begingroup - \etocfontzero - \addvspace{\etocsepzero}% - \parindent \z@ \parfillskip \@flushglue - \vbox{\etocifnumbered{\etocnumber.\enspace}{}\etocname - \baselineskip\etocbaselinespreadzero\baselineskip - \par}% - \endgroup} - {\addpenalty{-\@highpenalty}\addvspace{\etocsepminusone}}% -} -\def\etocdefaultlines@setsection{% -\Etoc@setstyle@b - {1}% - {\addpenalty\@M\etocskipfirstprefix} - {\addpenalty\@itempenalty} - {\begingroup - \etocfontone - \addvspace{\etocsepone}% - \parindent \z@ \parfillskip \z@ - \setbox\z@\vbox{\parfillskip\@flushglue - \etocname\par - \setbox\tw@\lastbox - \global\setbox\@ne\hbox{\unhbox\tw@\ }}% - \dimen\z@=\wd\@ne - \setbox\z@=\etoctoclineleaders - \advance\dimen\z@\wd\z@ - \etocifnumbered - {\setbox\tw@\hbox{\etocnumber, \etocabbrevpagename\etocpage\etocnoprotrusion}} - {\setbox\tw@\hbox{\etocabbrevpagename\etocpage\etocnoprotrusion}}% - \advance\dimen\z@\wd\tw@ - \ifdim\dimen\z@ < \linewidth - \vbox{\etocname~% - \leaders\box\z@\hfil\box\tw@ - \baselineskip\etocbaselinespreadone\baselineskip - \par}% - \else - \vbox{\etocname~% - \leaders\copy\z@\hfil\break - \hbox{}\leaders\box\z@\hfil\box\tw@ - \baselineskip\etocbaselinespreadone\baselineskip - \par}% - \fi - \endgroup} - {\addpenalty\@secpenalty\addvspace{\etocsepzero}}% -} -\def\etocdefaultlines@setsubsection{% -\Etoc@setstyle@b - {2}% - {\addpenalty\@medpenalty\etocskipfirstprefix} - {\addpenalty\@itempenalty} - {\begingroup - \etocfonttwo - \addvspace{\etocseptwo}% - \parindent \z@ \parfillskip \z@ - \setbox\z@\vbox{\parfillskip\@flushglue - \etocname\par\setbox\tw@\lastbox - \global\setbox\@ne\hbox{\unhbox\tw@}}% - \dimen\z@=\wd\@ne - \setbox\z@=\etoctoclineleaders - \advance\dimen\z@\wd\z@ - \etocifnumbered - {\setbox\tw@\hbox{\etocnumber, \etocabbrevpagename\etocpage\etocnoprotrusion}} - {\setbox\tw@\hbox{\etocabbrevpagename\etocpage\etocnoprotrusion}}% - \advance\dimen\z@\wd\tw@ - \ifdim\dimen\z@ < \linewidth - \vbox{\etocname~% - \leaders\box\z@\hfil\box\tw@ - \baselineskip\etocbaselinespreadtwo\baselineskip - \par}% - \else - \vbox{\etocname~% - \leaders\copy\z@\hfil\break - \hbox{}\leaders\box\z@\hfil\box\tw@ - \baselineskip\etocbaselinespreadtwo\baselineskip - \par}% - \fi - \endgroup} - {\addpenalty\@secpenalty\addvspace{\etocsepone}}% -} -\def\etocdefaultlines@setsubsubsection{% -\Etoc@setstyle@b - {3}% - {\addpenalty\@M - \etocfontthree - \vspace{\etocsepthree}% - \noindent - \etocskipfirstprefix} - {\allowbreak\,--\,} - {\etocname} - {.\hfil - \begingroup - \baselineskip\etocbaselinespreadthree\baselineskip - \par - \endgroup - \addpenalty{-\@highpenalty}} -} -\def\etocdefaultlines@setdeeperones{% -\Etoc@setstyle@e{4}% -\Etoc@setstyle@e{5}% -\ifEtoc@deeplevels - \Etoc@setstyle@e{6}% - \Etoc@setstyle@e{7}% - \Etoc@setstyle@e{8}% - \Etoc@setstyle@e{9}% - \Etoc@setstyle@e{10}% - \Etoc@setstyle@e{11}% -\fi -} -\def\etocabovetocskip{3.5ex \@plus 1ex \@minus .2ex} -\def\etocbelowtocskip{3.5ex \@plus 1ex \@minus .2ex} -\def\etoccolumnsep{2em} -\def\etocmulticolsep{0ex} -\def\etocmulticolpretolerance{-1} -\def\etocmulticoltolerance{200} -\def\etocdefaultnbcol{2} -\def\etocinnertopsep{2ex} -\newcommand\etocmulticolstyle[2][\etocdefaultnbcol]{% -\etocsettocstyle - {\let\etocoldpar\par - \addvspace{\etocabovetocskip}% - \ifnum #1>\@ne - \expandafter\@firstoftwo - \else \expandafter\@secondoftwo - \fi - {\multicolpretolerance\etocmulticolpretolerance - \multicoltolerance\etocmulticoltolerance - \setlength{\columnsep}{\etoccolumnsep}% - \setlength{\multicolsep}{\etocmulticolsep}% - \begin{multicols}{#1}[#2\etocoldpar\addvspace{\etocinnertopsep}]} - {#2\ifvmode\else\begingroup\interlinepenalty\@M\parskip\z@skip - \@@par\endgroup - \fi - \nobreak\addvspace{\etocinnertopsep}% - \pretolerance\etocmulticolpretolerance - \tolerance\etocmulticoltolerance}% - }% - {\ifnum #1>\@ne - \expandafter\@firstofone - \else \expandafter\@gobble - \fi - {\end{multicols}}% - \addvspace{\etocbelowtocskip}}% -} -\def\etocinnerbottomsep{3.5ex} -\def\etocinnerleftsep{2em} -\def\etocinnerrightsep{2em} -\def\etoctoprule{\hrule} -\def\etocleftrule{\vrule} -\def\etocrightrule{\vrule} -\def\etocbottomrule{\hrule} -\def\etoctoprulecolorcmd{\relax} -\def\etocbottomrulecolorcmd{\relax} -\def\etocleftrulecolorcmd{\relax} -\def\etocrightrulecolorcmd{\relax} -\def\etoc@ruledheading #1{% - \hb@xt@\linewidth{\color@begingroup - \hss #1\hss\hskip-\linewidth - \etoctoprulecolorcmd\leaders\etoctoprule\hss - \phantom{#1}% - \leaders\etoctoprule\hss\color@endgroup}% - \nointerlineskip\nobreak\vskip\etocinnertopsep} -\newcommand*\etocruledstyle[2][\etocdefaultnbcol]{% -\etocsettocstyle - {\addvspace{\etocabovetocskip}% - \ifnum #1>\@ne - \expandafter\@firstoftwo - \else \expandafter\@secondoftwo - \fi - {\multicolpretolerance\etocmulticolpretolerance - \multicoltolerance\etocmulticoltolerance - \setlength{\columnsep}{\etoccolumnsep}% - \setlength{\multicolsep}{\etocmulticolsep}% - \begin{multicols}{#1}[\etoc@ruledheading{#2}]} - {\etoc@ruledheading{#2}% - \pretolerance\etocmulticolpretolerance - \tolerance\etocmulticoltolerance}} - {\ifnum #1>\@ne\expandafter\@firstofone - \else \expandafter\@gobble - \fi - {\end{multicols}}% - \addvspace{\etocbelowtocskip}}} -\def\etocframedmphook{\relax} -\long\def\etocbkgcolorcmd{\relax} -\long\def\Etoc@relax{\relax} -\newbox\etoc@framed@titlebox -\newbox\etoc@framed@contentsbox -\newcommand*\etocframedstyle[2][\etocdefaultnbcol]{% -\etocsettocstyle{% - \addvspace{\etocabovetocskip}% - \sbox\z@{#2}% - \dimen\z@\dp\z@ - \ifdim\wd\z@<\linewidth \dp\z@\z@ \else \dimen\z@\z@ \fi - \setbox\etoc@framed@titlebox=\hb@xt@\linewidth{\color@begingroup - \hss - \ifx\etocbkgcolorcmd\Etoc@relax - \else - \sbox\tw@{\color{white}% - \vrule\@width\wd\z@\@height\ht\z@\@depth\dimen\z@}% - \ifdim\wd\z@<\linewidth \dp\tw@\z@\fi - \box\tw@ - \hskip-\wd\z@ - \fi - \copy\z@ - \hss - \hskip-\linewidth - \etoctoprulecolorcmd\leaders\etoctoprule\hss - \hskip\wd\z@ - \etoctoprulecolorcmd\leaders\etoctoprule\hss\color@endgroup}% - \setbox\z@\hbox{\etocleftrule\etocrightrule}% - \dimen\tw@\linewidth\advance\dimen\tw@-\wd\z@ - \advance\dimen\tw@-\etocinnerleftsep - \advance\dimen\tw@-\etocinnerrightsep - \setbox\etoc@framed@contentsbox=\vbox\bgroup - \hsize\dimen\tw@ - \kern\dimen\z@ - \vskip\etocinnertopsep - \hbox\bgroup - \begin{minipage}{\hsize}% - \etocframedmphook - \ifnum #1>\@ne - \expandafter\@firstoftwo - \else \expandafter\@secondoftwo - \fi - {\multicolpretolerance\etocmulticolpretolerance - \multicoltolerance\etocmulticoltolerance - \setlength{\columnsep}{\etoccolumnsep}% - \setlength{\multicolsep}{\etocmulticolsep}% - \begin{multicols}{#1}} - {\pretolerance\etocmulticolpretolerance - \tolerance\etocmulticoltolerance}} - {\ifnum #1>\@ne\expandafter\@firstofone - \else \expandafter\@gobble - \fi - {\end{multicols}\unskip }% - \end{minipage}% - \egroup - \vskip\etocinnerbottomsep - \egroup - \vbox{\hsize\linewidth - \ifx\etocbkgcolorcmd\Etoc@relax - \else - \kern\ht\etoc@framed@titlebox - \kern\dp\etoc@framed@titlebox - \hb@xt@\linewidth{\color@begingroup - \etocleftrulecolorcmd\etocleftrule - \etocbkgcolorcmd - \leaders\vrule - \@height\ht\etoc@framed@contentsbox - \@depth\dp\etoc@framed@contentsbox - \hss - \etocrightrulecolorcmd\etocrightrule - \color@endgroup}\nointerlineskip - \vskip-\dp\etoc@framed@contentsbox - \vskip-\ht\etoc@framed@contentsbox - \vskip-\dp\etoc@framed@titlebox - \vskip-\ht\etoc@framed@titlebox - \fi - \box\etoc@framed@titlebox\nointerlineskip - \hb@xt@\linewidth{\color@begingroup - {\etocleftrulecolorcmd\etocleftrule}% - \hss\box\etoc@framed@contentsbox\hss - \etocrightrulecolorcmd\etocrightrule\color@endgroup} - \nointerlineskip - \vskip\ht\etoc@framed@contentsbox - \vskip\dp\etoc@framed@contentsbox - \hb@xt@\linewidth{\color@begingroup\etocbottomrulecolorcmd - \leaders\etocbottomrule\hss\color@endgroup}} - \addvspace{\etocbelowtocskip}}} -\newcommand\etoc@multicoltoc[2][\etocdefaultnbcol]{% - \etocmulticolstyle[#1]{#2}% - \tableofcontents} -\newcommand\etoc@multicoltoci[2][\etocdefaultnbcol]{% - \etocmulticolstyle[#1]{#2}% - \tableofcontents*} -\newcommand\etoc@local@multicoltoc[2][\etocdefaultnbcol]{% - \etocmulticolstyle[#1]{#2}% - \localtableofcontents} -\newcommand\etoc@local@multicoltoci[2][\etocdefaultnbcol]{% - \etocmulticolstyle[#1]{#2}% - \localtableofcontents*} -\newcommand*\etoc@ruledtoc[2][\etocdefaultnbcol]{% - \etocruledstyle[#1]{#2}% - \tableofcontents} -\newcommand*\etoc@ruledtoci[2][\etocdefaultnbcol]{% - \etocruledstyle[#1]{#2}% - \tableofcontents*} -\newcommand*\etoc@local@ruledtoc[2][\etocdefaultnbcol]{% - \etocruledstyle[#1]{#2}% - \localtableofcontents} -\newcommand*\etoc@local@ruledtoci[2][\etocdefaultnbcol]{% - \etocruledstyle[#1]{#2}% - \localtableofcontents*} -\newcommand*\etoc@framedtoc[2][\etocdefaultnbcol]{% - \etocframedstyle[#1]{#2}% - \tableofcontents} -\newcommand*\etoc@framedtoci[2][\etocdefaultnbcol]{% - \etocframedstyle[#1]{#2}% - \tableofcontents*} -\newcommand*\etoc@local@framedtoc[2][\etocdefaultnbcol]{% - \etocframedstyle[#1]{#2}% - \localtableofcontents} -\newcommand*\etoc@local@framedtoci[2][\etocdefaultnbcol]{% - \etocframedstyle[#1]{#2}% - \localtableofcontents*} -\def\etocmulticol{\begingroup - \Etoc@mustclosegrouptrue - \@ifstar - {\etoc@multicoltoci} - {\etoc@multicoltoc}} -\def\etocruled{\begingroup - \Etoc@mustclosegrouptrue - \@ifstar - {\etoc@ruledtoci} - {\etoc@ruledtoc}} -\def\etocframed{\begingroup - \Etoc@mustclosegrouptrue - \@ifstar - {\etoc@framedtoci} - {\etoc@framedtoc}} -\def\etoclocalmulticol{\begingroup - \Etoc@mustclosegrouptrue - \@ifstar - {\etoc@local@multicoltoci} - {\etoc@local@multicoltoc}} -\def\etoclocalruled{\begingroup - \Etoc@mustclosegrouptrue - \@ifstar - {\etoc@local@ruledtoci} - {\etoc@local@ruledtoc}} -\def\etoclocalframed{\begingroup - \Etoc@mustclosegrouptrue - \@ifstar - {\etoc@local@framedtoci} - {\etoc@local@framedtoc}} -\def\etocmemoirtoctotocfmt #1#2{% - \PackageWarning{etoc} - {\string\etocmemoirtoctotocfmt\space is deprecated.\MessageBreak - Use in its place \string\etocsettoclineforclasstoc,\MessageBreak - and \string\etocsettoclineforclasslistof{toc} (or {lof}, {lot}). - I will do this now.\MessageBreak - Reported}% - \etocsettoclineforclasstoc{#1}{#2}% - \etocsettoclineforclasslistof{toc}{#1}{#2}% -} -\def\etocsettoclineforclasstoc #1#2{% - \def\etocclassmaintocaddtotoc{\etocglobalheadtotoc{#1}{#2}}% -} -\def\etocsettoclineforclasslistof #1#2#3{% - \@namedef{etocclasslocal#1addtotoc}{\etoclocalheadtotoc{#2}{#3}}% -} -\let\etocclasslocaltocaddtotoc\@empty -\let\etocclasslocallofaddtotoc\@empty -\let\etocclasslocallotaddtotoc\@empty -\ifdefined\c@chapter - \def\etocclasslocaltocmaketitle{\section*{\localcontentsname}} - \def\etocclasslocallofmaketitle{\section*{\locallistfigurename}} - \def\etocclasslocallotmaketitle{\section*{\locallisttablename}} - \etocsettoclineforclasstoc {chapter}{\contentsname} - \etocsettoclineforclasslistof{toc}{section}{\localcontentsname} - \etocsettoclineforclasslistof{lof}{section}{\locallistfigurename} - \etocsettoclineforclasslistof{lot}{section}{\locallisttablename} -\else - \def\etocclasslocaltocmaketitle{\subsection*{\localcontentsname}}% - \def\etocclasslocallofmaketitle{\subsection*{\locallistfigurename}}% - \def\etocclasslocallotmaketitle{\subsection*{\locallisttablename}}% - \etocsettoclineforclasstoc {section}{\contentsname} - \etocsettoclineforclasslistof{toc}{subsection}{\localcontentsname} - \etocsettoclineforclasslistof{lof}{subsection}{\locallistfigurename} - \etocsettoclineforclasslistof{lot}{subsection}{\locallisttablename} -\fi -\def\etocclasslocalperhapsaddtotoc #1{% - \etocifisstarred - {} - {\csname ifEtoc@local#1totoc\endcsname - \csname etocclasslocal#1addtotoc\endcsname - \fi - }% -} -\def\etocarticlestyle{% - \etocsettocstyle - {\ifEtoc@localtoc - \@nameuse{etocclasslocal\Etoc@currext maketitle}% - \etocclasslocalperhapsaddtotoc\Etoc@currext - \else - \section *{\contentsname - \@mkboth {\MakeUppercase \contentsname} - {\MakeUppercase \contentsname}}% - \etocifisstarred{}{\etocifmaintoctotoc{\etocclassmaintocaddtotoc}{}}% - \fi - } - {}% -} -\def\etocarticlestylenomarks{% - \etocsettocstyle - {\ifEtoc@localtoc - \@nameuse{etocclasslocal\Etoc@currext maketitle}% - \etocclasslocalperhapsaddtotoc\Etoc@currext - \else - \section *{\contentsname}% - \etocifisstarred{}{\etocifmaintoctotoc{\etocclassmaintocaddtotoc}{}}% - \fi - } - {}% -} -\def\etocbookstyle{% - \etocsettocstyle - {\if@twocolumn \@restonecoltrue \onecolumn \else \@restonecolfalse \fi - \ifEtoc@localtoc - \@nameuse{etocclasslocal\Etoc@currext maketitle}% - \etocclasslocalperhapsaddtotoc\Etoc@currext - \else - \chapter *{\contentsname - \@mkboth {\MakeUppercase \contentsname} - {\MakeUppercase \contentsname}}% - \etocifisstarred{}{\etocifmaintoctotoc{\etocclassmaintocaddtotoc}{}}% - \fi - }% - {\if@restonecol \twocolumn \fi}% -} -\def\etocbookstylenomarks{% - \etocsettocstyle - {\if@twocolumn \@restonecoltrue \onecolumn \else \@restonecolfalse \fi - \ifEtoc@localtoc - \@nameuse{etocclasslocal\Etoc@currext maketitle}% - \etocclasslocalperhapsaddtotoc\Etoc@currext - \else - \chapter *{\contentsname}% - \etocifisstarred{}{\etocifmaintoctotoc{\etocclassmaintocaddtotoc}{}}% - \fi - }% - {\if@restonecol \twocolumn \fi}% -} -\let\etocreportstyle\etocbookstyle -\let\etocreportstylenomarks\etocbookstylenomarks -\def\etocmemoirstyle{% - \etocsettocstyle - {\ensureonecol \par \begingroup \phantomsection - \ifx\Etoc@aftertitlehook\@empty - \else - \ifmem@em@starred@listof - \else - \ifEtoc@localtoc - \etocclasslocalperhapsaddtotoc\Etoc@currext - \else - \ifEtoc@maintoctotoc - \etocclassmaintocaddtotoc - \fi - \fi - \fi - \fi - \ifEtoc@localtoc - \@namedef{@\Etoc@currext maketitle}{% - \@nameuse{etocclasslocal\Etoc@currext maketitle}% - }% - \fi - \@nameuse {@\Etoc@currext maketitle} %<< space token here from memoir code - \ifx\Etoc@aftertitlehook\@empty - \else - \Etoc@aftertitlehook \let \Etoc@aftertitlehook \relax - \fi - \parskip \cftparskip \@nameuse {cft\Etoc@currext beforelisthook}% - }% - {\@nameuse {cft\Etoc@currext afterlisthook}% - \endgroup\restorefromonecol - }% -} -\let\Etoc@beforetitlehook\@empty -\if1\@ifclassloaded{scrartcl}0{\@ifclassloaded{scrbook}0{\@ifclassloaded{scrreprt}01}}% -\expandafter\@gobble -\else - \ifdefined\setuptoc - \def\Etoc@beforetitlehook{% - \ifEtoc@localtoc - \etocclasslocalperhapsaddtotoc\Etoc@currext - \setuptoc{\Etoc@currext}{leveldown}% - \else - \etocifisstarred{}{\etocifmaintoctotoc{\setuptoc{toc}{totoc}}}% - \fi - }% - \fi -\expandafter\@firstofone -\fi -{\def\etocclasslocalperhapsaddtotoc #1{% - \etocifisstarred - {}% - {\csname ifEtoc@local#1totoc\endcsname - \setuptoc{\Etoc@currext}{totoc}% - \fi - }% - }% -} -\ifdefined\Iftocfeature - \def\etoc@Iftocfeature{\Iftocfeature}% -\else - \def\etoc@Iftocfeature{\iftocfeature}% -\fi -\def\etocscrartclstyle{% - \etocsettocstyle - {\ifx\Etoc@currext\Etoc@tocext - \expandafter\@firstofone - \else - \expandafter\@gobble - \fi - {\let\if@dynlist\if@tocleft}% - \edef\@currext{\Etoc@currext}% - \@ifundefined{listof\@currext name}% - {\def\list@fname{\listofname~\@currext}}% - {\expandafter\let\expandafter\list@fname - \csname listof\@currext name\endcsname}% - \etoc@Iftocfeature {\@currext}{onecolumn} - {\etoc@Iftocfeature {\@currext}{leveldown} - {} - {\if@twocolumn \aftergroup \twocolumn \onecolumn \fi }} - {}% - \etoc@Iftocfeature {\@currext}{numberline}% - {\def \nonumberline {\numberline {}}}{}% - \expandafter\tocbasic@listhead\expandafter {\list@fname}% - \begingroup \expandafter \expandafter \expandafter - \endgroup \expandafter - \ifx - \csname microtypesetup\endcsname \relax - \else - \etoc@Iftocfeature {\@currext}{noprotrusion}{} - {\microtypesetup {protrusion=false}% - \PackageInfo {tocbasic}% - {character protrusion at \@currext\space deactivated}}% - \fi - \etoc@Iftocfeature{\@currext}{noparskipfake}{}{% - \ifvmode \@tempskipa\lastskip \vskip-\lastskip - \addtolength{\@tempskipa}{\parskip}\vskip\@tempskipa\fi - }% - \setlength {\parskip }{\z@ }% - \setlength {\parindent }{\z@ }% - \setlength {\parfillskip }{\z@ \@plus 1fil}% - \csname tocbasic@@before@hook\endcsname - \csname tb@\@currext @before@hook\endcsname - }% end of before_toc - {% start of after_toc - \providecommand\tocbasic@end@toc@file{}\tocbasic@end@toc@file - \edef\@currext{\Etoc@currext}% - \csname tb@\@currext @after@hook\endcsname - \csname tocbasic@@after@hook\endcsname - }% end of after_toc -} -\let\etocscrbookstyle\etocscrartclstyle -\let\etocscrreprtstyle\etocscrartclstyle -\def\etocclasstocstyle{\etocarticlestyle} -\newcommand*\etocmarkboth[1]{% - \@mkboth{\MakeUppercase{#1}}{\MakeUppercase{#1}}} -\newcommand*\etocmarkbothnouc[1]{\@mkboth{#1}{#1}} -\newcommand\etoctocstyle[3][section]{\etocmulticolstyle[#2]% - {\csname #1\endcsname *{#3}}} -\newcommand\etoctocstylewithmarks[4][section]{\etocmulticolstyle[#2]% - {\csname #1\endcsname *{#3\etocmarkboth{#4}}}} -\newcommand\etoctocstylewithmarksnouc[4][section]{\etocmulticolstyle[#2]% - {\csname #1\endcsname *{#3\etocmarkbothnouc{#4}}}} -\def\Etoc@redefetocstylesforchapters{% - \renewcommand\etoctocstylewithmarks[4][chapter]{% - \etocmulticolstyle[##2]{\csname ##1\endcsname *{##3\etocmarkboth{##4}}}% - } - \renewcommand\etoctocstylewithmarksnouc[4][chapter]{% - \etocmulticolstyle[##2]{\csname ##1\endcsname *{##3\etocmarkbothnouc{##4}}}% - } - \renewcommand\etoctocstyle[3][chapter]{% - \etocmulticolstyle[##2]{\csname ##1\endcsname *{##3}} - } -} -\@ifclassloaded{scrartcl} - {\renewcommand*\etocclasstocstyle{\etocscrartclstyle}}{} -\@ifclassloaded{book} - {\renewcommand*\etocfontone{\normalfont\normalsize} - \renewcommand*\etocclasstocstyle{\etocbookstyle} - \Etoc@redefetocstylesforchapters}{} -\@ifclassloaded{report} - {\renewcommand*\etocfontone{\normalfont\normalsize} - \renewcommand*\etocclasstocstyle{\etocreportstyle} - \Etoc@redefetocstylesforchapters}{} -\@ifclassloaded{scrbook} - {\renewcommand*\etocfontone{\normalfont\normalsize} - \renewcommand*\etocclasstocstyle{\etocscrbookstyle} - \Etoc@redefetocstylesforchapters}{} -\@ifclassloaded{scrreprt} - {\renewcommand*\etocfontone{\normalfont\normalsize} - \renewcommand*\etocclasstocstyle{\etocscrreprtstyle} - \Etoc@redefetocstylesforchapters}{} -\@ifclassloaded{memoir} - {\renewcommand*\etocfontone{\normalfont\normalsize} - \renewcommand*\etocclasstocstyle{\etocmemoirstyle} - \Etoc@redefetocstylesforchapters}{} -\def\etoctocloftstyle {% - \etocsettocstyle{% - \@cfttocstart - \par - \begingroup - \parindent\z@ \parskip\cftparskip - \@nameuse{@cftmake\Etoc@currext title}% - \ifEtoc@localtoc - \etoctocloftlocalperhapsaddtotoc\Etoc@currext - \else - \etocifisstarred {}{\ifEtoc@maintoctotoc\@cftdobibtoc\fi}% - \fi - }% - {% - \endgroup - \@cfttocfinish - }% -} -\def\etoctocloftlocalperhapsaddtotoc#1{% - \etocifisstarred - {}% - {\csname ifEtoc@local#1totoc\endcsname - \ifdefined\c@chapter\def\@tocextra{@section}\else\def\@tocextra{@subsection}\fi - \csname @cftdobib#1\endcsname - \fi - }% -} -\def\etoctocbibindstyle {% - \etocsettocstyle {% - \toc@start - \ifEtoc@localtoc - \@nameuse{etocclasslocal\Etoc@currext maketitle}% - \etocclasslocalperhapsaddtotoc\Etoc@currext - \else - \etoc@tocbibind@dotoctitle - \fi - }% - {\toc@finish}% -} -\def\etoc@tocbibind@dotoctitle {% - \if@bibchapter - \etocifisstarred - {\chapter*{\contentsname}\prw@mkboth{\contentsname} % id. - }% - {\ifEtoc@maintoctotoc - \toc@chapter{\contentsname} %<-space from original - \else - \chapter*{\contentsname}\prw@mkboth{\contentsname} % id. - \fi - }% - \else - \etocifisstarred - {\@nameuse{\@tocextra}*{\contentsname\prw@mkboth{\contentsname}} %<-space - } - {\ifEtoc@maintoctotoc - \toc@section{\@tocextra}{\contentsname} %<-space from original - \else - \@nameuse{\@tocextra}*{\contentsname\prw@mkboth{\contentsname}} % id. - \fi - }% - \fi -}% -\@ifclassloaded{memoir} -{} -{% memoir not loaded - \@ifpackageloaded{tocloft} - {\if@cftnctoc\else - \ifEtoc@keeporiginaltoc - \else - \AtBeginDocument{\let\tableofcontents\etoctableofcontents}% - \fi - \fi } - {\AtBeginDocument - {\@ifpackageloaded{tocloft} - {\if@cftnctoc\else - \PackageWarningNoLine {etoc} - {Package `tocloft' was loaded after `etoc'.\MessageBreak - To prevent it from overwriting \protect\tableofcontents, it will\MessageBreak - be tricked into believing to have been loaded with its\MessageBreak - option `titles'. \space But this will cause the `tocloft'\MessageBreak - customization of the titles of the main list of figures\MessageBreak - and list of tables to not apply either.\MessageBreak - You should load `tocloft' before `etoc'.}% - \AtEndDocument{\PackageWarning{etoc} - {Please load `tocloft' before `etoc'!\@gobbletwo}}% - \fi - \@cftnctoctrue }% - {}% - }% - }% -} -\@ifclassloaded{memoir} -{} -{% memoir not loaded - \AtBeginDocument{% - \@ifpackageloaded{tocloft} - {% - \def\etocclasstocstyle{% - \etoctocloftstyle - \Etoc@classstyletrue - }% - \ifEtoc@etocstyle - \ifEtoc@classstyle - \etocclasstocstyle - \Etoc@etocstyletrue - \fi - \else - \ifEtoc@classstyle - \etocclasstocstyle - \fi - \fi - }% - {% no tocloft - \@ifpackageloaded {tocbibind} - {\if@dotoctoc - \def\etocclasstocstyle{% - \etoctocbibindstyle - \Etoc@classstyletrue - }% - \ifEtoc@etocstyle - \ifEtoc@classstyle - \etocclasstocstyle - \Etoc@etocstyletrue - \fi - \else - \ifEtoc@classstyle - \etocclasstocstyle - \fi - \fi - \ifEtoc@keeporiginaltoc - \else - \let\tableofcontents\etoctableofcontents - \fi - }% - {}% - }% - \@ifpackageloaded{tocbibind} - {% tocbibind, perhaps with tocloft - \if@dotoctoc - \ifEtoc@keeporiginaltoc - \else - \let\tableofcontents\etoctableofcontents - \fi - \etocsetup{maintoctotoc,localtoctotoc}% - \PackageInfo{etoc}{% - Setting (or re-setting) the options `maintoctotoc' and\MessageBreak - `localtoctotoc' to true as tocbibind was detected and\MessageBreak - found to be configured for `TOC to toc'.\MessageBreak - Reported at begin document}% - \fi - \if@dotoclof - \ifEtoc@lof - \etocsetup{localloftotoc}% - \PackageInfo{etoc}{% - Setting (or re-setting) `localloftotoc=true' as the\MessageBreak - package tocbibind was detected and is configured for\MessageBreak - `LOF to toc'. Reported at begin document}% - \fi - \fi - \if@dotoclot - \ifEtoc@lot - \etocsetup{locallottotoc}% - \PackageInfo{etoc}{% - Setting (or re-setting) `locallottotoc=true' as the\MessageBreak - package tocbibind was detected and is configured for\MessageBreak - `LOT to toc'. Reported at begin document}% - \fi - \fi - }% end of tocbibind branch - {}% - }% end of at begin document -}% end of not with memoir branch -\def\Etoc@addtocontents #1#2{% - \addtocontents {toc}{% - \protect\contentsline{#1}{#2}{\thepage}{\ifEtoc@hyperref\@currentHref\fi}% - \ifdefined\protected@file@percent\protected@file@percent\fi - }% -} -\def\Etoc@addcontentsline@ #1#2#3{% - \@namedef{toclevel@#1}{#3}\addcontentsline {toc}{#1}{#2}% -} -\DeclareRobustCommand*{\etoctoccontentsline} - {\@ifstar{\Etoc@addcontentsline@}{\Etoc@addtocontents}} -\def\Etoc@addtocontents@immediately#1#2{% - \begingroup - \let\Etoc@originalwrite\write - \def\write{\immediate\Etoc@originalwrite}% - \Etoc@addtocontents{#1}{#2}% - \endgroup -} -\def\Etoc@addcontentsline@@immediately#1#2#3{% - \begingroup - \let\Etoc@originalwrite\write - \def\write{\immediate\Etoc@originalwrite}% - \Etoc@addcontentsline@{#1}{#2}{#3}% - \endgoroup -} -\DeclareRobustCommand*{\etocimmediatetoccontentsline} - {\@ifstar{\Etoc@addcontentsline@@immediately}{\Etoc@addtocontents@immediately}} -\def\Etoc@storetocdepth {\xdef\Etoc@savedtocdepth{\number\c@tocdepth}} -\def\Etoc@restoretocdepth {\global\c@tocdepth\Etoc@savedtocdepth\relax} -\def\etocobeytoctocdepth {\def\etoc@settocdepth - {\afterassignment\Etoc@@nottoodeep \global\c@tocdepth}} -\def\Etoc@@nottoodeep {\ifnum\Etoc@savedtocdepth<\c@tocdepth - \global\c@tocdepth\Etoc@savedtocdepth\relax\fi } -\def\etocignoretoctocdepth {\let\etoc@settocdepth\@gobble } -\def\etocsettocdepth {\futurelet\Etoc@nexttoken\Etoc@set@tocdepth } -\def\Etoc@set@tocdepth {\ifx\Etoc@nexttoken\bgroup - \expandafter\Etoc@set@tocdepth@ - \else\expandafter\Etoc@set@toctocdepth - \fi } -\def\Etoc@set@tocdepth@ #1{\@ifundefined {Etoc@#1@@} - {\PackageWarning{etoc} - {Unknown sectioning unit #1, \protect\etocsettocdepth\space ignored}} - {\global\c@tocdepth\csname Etoc@#1@@\endcsname}% -} -\def\Etoc@set@toctocdepth #1#{\Etoc@set@toctocdepth@ } -\def\Etoc@set@toctocdepth@ #1{% - \@ifundefined{Etoc@#1@@}% - {\PackageWarning{etoc} - {Unknown sectioning depth #1, \protect\etocsettocdepth.toc ignored}}% - {\addtocontents {toc} - {\protect\etoc@settocdepth\expandafter\protect\csname Etoc@#1@@\endcsname}}% -} -\def\etocimmediatesettocdepth #1#{\Etoc@set@toctocdepth@immediately} -\def\Etoc@set@toctocdepth@immediately #1{% - \@ifundefined{Etoc@#1@@}% - {\PackageWarning{etoc} - {Unknown sectioning depth #1, \protect\etocimmediatesettocdepth.toc ignored}}% - {\begingroup - \let\Etoc@originalwrite\write - \def\write{\immediate\Etoc@originalwrite}% - \addtocontents {toc} - {\protect\etoc@settocdepth\expandafter\protect - \csname Etoc@#1@@\endcsname}% - \endgroup - }% -} -\def\etocdepthtag #1#{\Etoc@depthtag } -\def\Etoc@depthtag #1{\addtocontents {toc}{\protect\etoc@depthtag {#1}}} -\def\etocimmediatedepthtag #1#{\Etoc@depthtag@immediately } -\def\Etoc@depthtag@immediately #1{% - \begingroup - \let\Etoc@originalwrite\write - \def\write{\immediate\Etoc@originalwrite}% - \addtocontents {toc}{\protect\etoc@depthtag {#1}}% - \endgroup -} -\def\etocignoredepthtags {\let\etoc@depthtag \@gobble } -\def\etocobeydepthtags {\let\etoc@depthtag \Etoc@depthtag@ } -\def\Etoc@depthtag@ #1{\@ifundefined{Etoc@depthof@#1}% - {}% ignore in silence if tag has no associated depth - {\afterassignment\Etoc@@nottoodeep - \global\c@tocdepth\csname Etoc@depthof@#1\endcsname}% -} -\def\etocsettagdepth #1#2{\@ifundefined{Etoc@#2@@}% - {\PackageWarning{etoc} - {Unknown sectioning depth #2, \protect\etocsettagdepth\space ignored}}% - {\@namedef{Etoc@depthof@#1}{\@nameuse{Etoc@#2@@}}}% -} -\def\Etoc@tocvsec@err #1{\PackageError {etoc} - {The command \protect#1\space is incompatible with `etoc'} - {Use \protect\etocsettocdepth.toc as replacement}% -}% -\AtBeginDocument {% - \@ifclassloaded{memoir} - {\PackageInfo {etoc} - {Regarding `memoir' class command \protect\settocdepth, consider\MessageBreak - \protect\etocsettocdepth.toc as a drop-in replacement with more\MessageBreak - capabilities (see `etoc' manual). \space - Also, \protect\etocsettocdepth\MessageBreak - and \protect\etocsetnexttocdepth\space should be used in place of\MessageBreak - `memoir' command \protect\maxtocdepth\@gobble}% - }% - {\@ifpackageloaded {tocvsec2}{% - \def\maxtocdepth #1{\Etoc@tocvsec@err \maxtocdepth }% - \def\settocdepth #1{\Etoc@tocvsec@err \settocdepth }% - \def\resettocdepth {\@ifstar {\Etoc@tocvsec@err \resettocdepth }% - {\Etoc@tocvsec@err \resettocdepth }% - }% - \def\save@tocdepth #1#2#3{}% - \let\reset@tocdepth\relax - \let\remax@tocdepth\relax - \let\tableofcontents\etoctableofcontents - \PackageWarningNoLine {etoc} - {Package `tocvsec2' detected and its modification of\MessageBreak - \protect\tableofcontents\space reverted. \space Use - \protect\etocsettocdepth.toc\MessageBreak as a replacement - for `tocvsec2' toc-related commands}% - }% tocvsec2 loaded - {}% tocvsec2 not loaded - }% -}% -\def\invisibletableofcontents {\etocsetnexttocdepth {-3}\tableofcontents }% -\def\invisiblelocaltableofcontents - {\etocsetnexttocdepth {-3}\localtableofcontents }% -\def\etocsetnexttocdepth #1{% - \@ifundefined{Etoc@#1@@} - {\PackageWarning{etoc} - {Unknown sectioning unit #1, \protect\etocsetnextocdepth\space ignored}} - {\Etoc@setnexttocdepth{\csname Etoc@#1@@\endcsname}}% -}% -\def\Etoc@setnexttocdepth#1{% - \def\Etoc@tocdepthset{% - \Etoc@tocdepthreset - \edef\Etoc@tocdepthreset {% - \global\c@tocdepth\the\c@tocdepth\space - \global\let\noexpand\Etoc@tocdepthreset\noexpand\@empty - }% - \global\c@tocdepth#1% - \global\let\Etoc@tocdepthset\@empty - }% -}% -\let\Etoc@tocdepthreset\@empty -\let\Etoc@tocdepthset \@empty -\def\etocsetlocaltop #1#{\Etoc@set@localtop}% -\def\Etoc@set@localtop #1{% - \@ifundefined{Etoc@#1@@}% - {\PackageWarning{etoc} - {Unknown sectioning depth #1, \protect\etocsetlocaltop.toc ignored}}% - {\addtocontents {toc} - {\protect\etoc@setlocaltop\expandafter\protect\csname Etoc@#1@@\endcsname}}% -}% -\def\etocimmediatesetlocaltop #1#{\Etoc@set@localtop@immediately}% -\def\Etoc@set@localtop@immediately #1{% - \@ifundefined{Etoc@#1@@}% - {\PackageWarning{etoc} - {Unknown sectioning depth #1, \protect\etocimmediatesetlocaltop.toc ignored}}% - {\begingroup - \let\Etoc@originalwrite\write - \def\write{\immediate\Etoc@originalwrite}% - \addtocontents {toc} - {\protect\etoc@setlocaltop\expandafter\protect - \csname Etoc@#1@@\endcsname}% - \endgroup - }% -}% -\def\etoc@setlocaltop #1{% - \ifnum#1=\Etoc@maxlevel - \Etoc@skipthisonetrue - \else - \Etoc@skipthisonefalse - \global\let\Etoc@level #1% - \global\let\Etoc@virtualtop #1% - \ifEtoc@localtoc - \ifEtoc@stoptoc - \Etoc@skipthisonetrue - \else - \ifEtoc@notactive - \Etoc@skipthisonetrue - \else - \unless\ifnum\Etoc@level>\etoclocaltop - \Etoc@skipthisonetrue - \global\Etoc@stoptoctrue - \fi - \fi - \fi - \fi - \fi - \let\Etoc@next\@empty - \ifEtoc@skipthisone - \else - \ifnum\Etoc@level>\c@tocdepth - \else - \ifEtoc@standardlines - \else - \let\Etoc@next\Etoc@setlocaltop@doendsandbegin - \fi - \fi - \fi - \Etoc@next -}% -\def\Etoc@setlocaltop@doendsandbegin{% - \Etoc@doendsandbegin - \global\Etoc@skipprefixfalse -} -\addtocontents {toc}{\protect\@ifundefined{etoctocstyle}% - {\let\protect\etoc@startlocaltoc\protect\@gobble - \let\protect\etoc@settocdepth\protect\@gobble - \let\protect\etoc@depthtag\protect\@gobble - \let\protect\etoc@setlocaltop\protect\@gobble}{}}% -\def\etocstandardlines {\Etoc@standardlinestrue} -\def\etoctoclines {\Etoc@standardlinesfalse} -\etocdefaultlines -\etocstandardlines -\def\etocstandarddisplaystyle{% - \PackageWarningNoLine{etoc}{% - \string\etocstandarddisplaystyle \on@line\MessageBreak - is deprecated. \space Please use \string\etocclasstocstyle}% -} -\expandafter\def\expandafter\etocclasstocstyle\expandafter{% - \etocclasstocstyle - \Etoc@classstyletrue -} -\def\etocetoclocaltocstyle{\Etoc@etocstyletrue} -\def\etocusertocstyle{\Etoc@etocstylefalse} -\etocclasstocstyle -\etocetoclocaltocstyle -\etocobeytoctocdepth -\etocobeydepthtags -\let\etocbeforetitlehook \@empty -\let\etocaftertitlehook \@empty -\let\etocaftercontentshook \@empty -\let\etocaftertochook \@empty -\def\etockeeporiginaltableofcontents - {\Etoc@keeporiginaltoctrue\let\tableofcontents\etocoriginaltableofcontents}% -\endinput -%% -%% End of file `etoc.sty'. diff --git a/documentation/latex/files.tex b/documentation/latex/files.tex deleted file mode 100644 index 46645a4..0000000 --- a/documentation/latex/files.tex +++ /dev/null @@ -1,13 +0,0 @@ -\doxysection{File List} -Here is a list of all files with brief descriptions\+:\begin{DoxyCompactList} -\item\contentsline{section}{\mbox{\hyperlink{_b_n_o08x_8hpp}{BNO08x.\+hpp}} }{\pageref{_b_n_o08x_8hpp}}{} -\item\contentsline{section}{\mbox{\hyperlink{_b_n_o08x__global__types_8hpp}{BNO08x\+\_\+global\+\_\+types.\+hpp}} }{\pageref{_b_n_o08x__global__types_8hpp}}{} -\item\contentsline{section}{\mbox{\hyperlink{_b_n_o08x__macros_8hpp}{BNO08x\+\_\+macros.\+hpp}} }{\pageref{_b_n_o08x__macros_8hpp}}{} -\item\contentsline{section}{\mbox{\hyperlink{_b_n_o08x_test_helper_8hpp}{BNO08x\+Test\+Helper.\+hpp}} }{\pageref{_b_n_o08x_test_helper_8hpp}}{} -\item\contentsline{section}{\mbox{\hyperlink{_b_n_o08x_test_suite_8hpp}{BNO08x\+Test\+Suite.\+hpp}} }{\pageref{_b_n_o08x_test_suite_8hpp}}{} -\item\contentsline{section}{\mbox{\hyperlink{_b_n_o08x_8cpp}{BNO08x.\+cpp}} }{\pageref{_b_n_o08x_8cpp}}{} -\item\contentsline{section}{\mbox{\hyperlink{_callback_tests_8cpp}{Callback\+Tests.\+cpp}} }{\pageref{_callback_tests_8cpp}}{} -\item\contentsline{section}{\mbox{\hyperlink{_init_deinit_tests_8cpp}{Init\+Deinit\+Tests.\+cpp}} }{\pageref{_init_deinit_tests_8cpp}}{} -\item\contentsline{section}{\mbox{\hyperlink{_multi_report_tests_8cpp}{Multi\+Report\+Tests.\+cpp}} }{\pageref{_multi_report_tests_8cpp}}{} -\item\contentsline{section}{\mbox{\hyperlink{_single_report_tests_8cpp}{Single\+Report\+Tests.\+cpp}} }{\pageref{_single_report_tests_8cpp}}{} -\end{DoxyCompactList} diff --git a/documentation/latex/longtable_doxygen.sty b/documentation/latex/longtable_doxygen.sty deleted file mode 100644 index e94b78b..0000000 --- a/documentation/latex/longtable_doxygen.sty +++ /dev/null @@ -1,456 +0,0 @@ -%% -%% This is file `longtable.sty', -%% generated with the docstrip utility. -%% -%% The original source files were: -%% -%% longtable.dtx (with options: `package') -%% -%% This is a generated file. -%% -%% The source is maintained by the LaTeX Project team and bug -%% reports for it can be opened at http://latex-project.org/bugs.html -%% (but please observe conditions on bug reports sent to that address!) -%% -%% Copyright 1993-2016 -%% The LaTeX3 Project and any individual authors listed elsewhere -%% in this file. -%% -%% This file was generated from file(s) of the Standard LaTeX `Tools Bundle'. -%% -------------------------------------------------------------------------- -%% -%% It may be distributed and/or modified under the -%% conditions of the LaTeX Project Public License, either version 1.3c -%% of this license or (at your option) any later version. -%% The latest version of this license is in -%% http://www.latex-project.org/lppl.txt -%% and version 1.3c or later is part of all distributions of LaTeX -%% version 2005/12/01 or later. -%% -%% This file may only be distributed together with a copy of the LaTeX -%% `Tools Bundle'. You may however distribute the LaTeX `Tools Bundle' -%% without such generated files. -%% -%% The list of all files belonging to the LaTeX `Tools Bundle' is -%% given in the file `manifest.txt'. -%% -%% File: longtable.dtx Copyright (C) 1990-2001 David Carlisle -\NeedsTeXFormat{LaTeX2e}[1995/06/01] -\ProvidesPackage{longtable_doxygen} - [2014/10/28 v4.11 Multi-page Table package (DPC) - frozen version for doxygen] -\def\LT@err{\PackageError{longtable}} -\def\LT@warn{\PackageWarning{longtable}} -\def\LT@final@warn{% - \AtEndDocument{% - \LT@warn{Table \@width s have changed. Rerun LaTeX.\@gobbletwo}}% - \global\let\LT@final@warn\relax} -\DeclareOption{errorshow}{% - \def\LT@warn{\PackageInfo{longtable}}} -\DeclareOption{pausing}{% - \def\LT@warn#1{% - \LT@err{#1}{This is not really an error}}} -\DeclareOption{set}{} -\DeclareOption{final}{} -\ProcessOptions -\newskip\LTleft \LTleft=\fill -\newskip\LTright \LTright=\fill -\newskip\LTpre \LTpre=\bigskipamount -\newskip\LTpost \LTpost=\bigskipamount -\newcount\LTchunksize \LTchunksize=20 -\let\c@LTchunksize\LTchunksize -\newdimen\LTcapwidth \LTcapwidth=4in -\newbox\LT@head -\newbox\LT@firsthead -\newbox\LT@foot -\newbox\LT@lastfoot -\newcount\LT@cols -\newcount\LT@rows -\newcounter{LT@tables} -\newcounter{LT@chunks}[LT@tables] -\ifx\c@table\undefined - \newcounter{table} - \def\fnum@table{\tablename~\thetable} -\fi -\ifx\tablename\undefined - \def\tablename{Table} -\fi -\newtoks\LT@p@ftn -\mathchardef\LT@end@pen=30000 -\def\longtable{% - \par - \ifx\multicols\@undefined - \else - \ifnum\col@number>\@ne - \@twocolumntrue - \fi - \fi - \if@twocolumn - \LT@err{longtable not in 1-column mode}\@ehc - \fi - \begingroup - \@ifnextchar[\LT@array{\LT@array[x]}} -\def\LT@array[#1]#2{% - \refstepcounter{table}\stepcounter{LT@tables}% - \if l#1% - \LTleft\z@ \LTright\fill - \else\if r#1% - \LTleft\fill \LTright\z@ - \else\if c#1% - \LTleft\fill \LTright\fill - \fi\fi\fi - \let\LT@mcol\multicolumn - \let\LT@@tabarray\@tabarray - \let\LT@@hl\hline - \def\@tabarray{% - \let\hline\LT@@hl - \LT@@tabarray}% - \let\\\LT@tabularcr\let\tabularnewline\\% - \def\newpage{\noalign{\break}}% - \def\pagebreak{\noalign{\ifnum`}=0\fi\@testopt{\LT@no@pgbk-}4}% - \def\nopagebreak{\noalign{\ifnum`}=0\fi\@testopt\LT@no@pgbk4}% - \let\hline\LT@hline \let\kill\LT@kill\let\caption\LT@caption - \@tempdima\ht\strutbox - \let\@endpbox\LT@endpbox - \ifx\extrarowheight\@undefined - \let\@acol\@tabacol - \let\@classz\@tabclassz \let\@classiv\@tabclassiv - \def\@startpbox{\vtop\LT@startpbox}% - \let\@@startpbox\@startpbox - \let\@@endpbox\@endpbox - \let\LT@LL@FM@cr\@tabularcr - \else - \advance\@tempdima\extrarowheight - \col@sep\tabcolsep - \let\@startpbox\LT@startpbox\let\LT@LL@FM@cr\@arraycr - \fi - \setbox\@arstrutbox\hbox{\vrule - \@height \arraystretch \@tempdima - \@depth \arraystretch \dp \strutbox - \@width \z@}% - \let\@sharp##\let\protect\relax - \begingroup - \@mkpream{#2}% - \xdef\LT@bchunk{% - \global\advance\c@LT@chunks\@ne - \global\LT@rows\z@\setbox\z@\vbox\bgroup - \LT@setprevdepth - \tabskip\LTleft \noexpand\halign to\hsize\bgroup - \tabskip\z@ \@arstrut \@preamble \tabskip\LTright \cr}% - \endgroup - \expandafter\LT@nofcols\LT@bchunk&\LT@nofcols - \LT@make@row - \m@th\let\par\@empty - \everycr{}\lineskip\z@\baselineskip\z@ - \LT@bchunk} -\def\LT@no@pgbk#1[#2]{\penalty #1\@getpen{#2}\ifnum`{=0\fi}} -\def\LT@start{% - \let\LT@start\endgraf - \endgraf\penalty\z@\vskip\LTpre - \dimen@\pagetotal - \advance\dimen@ \ht\ifvoid\LT@firsthead\LT@head\else\LT@firsthead\fi - \advance\dimen@ \dp\ifvoid\LT@firsthead\LT@head\else\LT@firsthead\fi - \advance\dimen@ \ht\LT@foot - \dimen@ii\vfuzz - \vfuzz\maxdimen - \setbox\tw@\copy\z@ - \setbox\tw@\vsplit\tw@ to \ht\@arstrutbox - \setbox\tw@\vbox{\unvbox\tw@}% - \vfuzz\dimen@ii - \advance\dimen@ \ht - \ifdim\ht\@arstrutbox>\ht\tw@\@arstrutbox\else\tw@\fi - \advance\dimen@\dp - \ifdim\dp\@arstrutbox>\dp\tw@\@arstrutbox\else\tw@\fi - \advance\dimen@ -\pagegoal - \ifdim \dimen@>\z@\vfil\break\fi - \global\@colroom\@colht - \ifvoid\LT@foot\else - \advance\vsize-\ht\LT@foot - \global\advance\@colroom-\ht\LT@foot - \dimen@\pagegoal\advance\dimen@-\ht\LT@foot\pagegoal\dimen@ - \maxdepth\z@ - \fi - \ifvoid\LT@firsthead\copy\LT@head\else\box\LT@firsthead\fi\nobreak - \output{\LT@output}} -\def\endlongtable{% - \crcr - \noalign{% - \let\LT@entry\LT@entry@chop - \xdef\LT@save@row{\LT@save@row}}% - \LT@echunk - \LT@start - \unvbox\z@ - \LT@get@widths - \if@filesw - {\let\LT@entry\LT@entry@write\immediate\write\@auxout{% - \gdef\expandafter\noexpand - \csname LT@\romannumeral\c@LT@tables\endcsname - {\LT@save@row}}}% - \fi - \ifx\LT@save@row\LT@@save@row - \else - \LT@warn{Column \@width s have changed\MessageBreak - in table \thetable}% - \LT@final@warn - \fi - \endgraf\penalty -\LT@end@pen - \endgroup - \global\@mparbottom\z@ - \pagegoal\vsize - \endgraf\penalty\z@\addvspace\LTpost - \ifvoid\footins\else\insert\footins{}\fi} -\def\LT@nofcols#1&{% - \futurelet\@let@token\LT@n@fcols} -\def\LT@n@fcols{% - \advance\LT@cols\@ne - \ifx\@let@token\LT@nofcols - \expandafter\@gobble - \else - \expandafter\LT@nofcols - \fi} -\def\LT@tabularcr{% - \relax\iffalse{\fi\ifnum0=`}\fi - \@ifstar - {\def\crcr{\LT@crcr\noalign{\nobreak}}\let\cr\crcr - \LT@t@bularcr}% - {\LT@t@bularcr}} -\let\LT@crcr\crcr -\let\LT@setprevdepth\relax -\def\LT@t@bularcr{% - \global\advance\LT@rows\@ne - \ifnum\LT@rows=\LTchunksize - \gdef\LT@setprevdepth{% - \prevdepth\z@\global - \global\let\LT@setprevdepth\relax}% - \expandafter\LT@xtabularcr - \else - \ifnum0=`{}\fi - \expandafter\LT@LL@FM@cr - \fi} -\def\LT@xtabularcr{% - \@ifnextchar[\LT@argtabularcr\LT@ntabularcr} -\def\LT@ntabularcr{% - \ifnum0=`{}\fi - \LT@echunk - \LT@start - \unvbox\z@ - \LT@get@widths - \LT@bchunk} -\def\LT@argtabularcr[#1]{% - \ifnum0=`{}\fi - \ifdim #1>\z@ - \unskip\@xargarraycr{#1}% - \else - \@yargarraycr{#1}% - \fi - \LT@echunk - \LT@start - \unvbox\z@ - \LT@get@widths - \LT@bchunk} -\def\LT@echunk{% - \crcr\LT@save@row\cr\egroup - \global\setbox\@ne\lastbox - \unskip - \egroup} -\def\LT@entry#1#2{% - \ifhmode\@firstofone{&}\fi\omit - \ifnum#1=\c@LT@chunks - \else - \kern#2\relax - \fi} -\def\LT@entry@chop#1#2{% - \noexpand\LT@entry - {\ifnum#1>\c@LT@chunks - 1}{0pt% - \else - #1}{#2% - \fi}} -\def\LT@entry@write{% - \noexpand\LT@entry^^J% - \@spaces} -\def\LT@kill{% - \LT@echunk - \LT@get@widths - \expandafter\LT@rebox\LT@bchunk} -\def\LT@rebox#1\bgroup{% - #1\bgroup - \unvbox\z@ - \unskip - \setbox\z@\lastbox} -\def\LT@blank@row{% - \xdef\LT@save@row{\expandafter\LT@build@blank - \romannumeral\number\LT@cols 001 }} -\def\LT@build@blank#1{% - \if#1m% - \noexpand\LT@entry{1}{0pt}% - \expandafter\LT@build@blank - \fi} -\def\LT@make@row{% - \global\expandafter\let\expandafter\LT@save@row - \csname LT@\romannumeral\c@LT@tables\endcsname - \ifx\LT@save@row\relax - \LT@blank@row - \else - {\let\LT@entry\or - \if!% - \ifcase\expandafter\expandafter\expandafter\LT@cols - \expandafter\@gobble\LT@save@row - \or - \else - \relax - \fi - !% - \else - \aftergroup\LT@blank@row - \fi}% - \fi} -\let\setlongtables\relax -\def\LT@get@widths{% - \setbox\tw@\hbox{% - \unhbox\@ne - \let\LT@old@row\LT@save@row - \global\let\LT@save@row\@empty - \count@\LT@cols - \loop - \unskip - \setbox\tw@\lastbox - \ifhbox\tw@ - \LT@def@row - \advance\count@\m@ne - \repeat}% - \ifx\LT@@save@row\@undefined - \let\LT@@save@row\LT@save@row - \fi} -\def\LT@def@row{% - \let\LT@entry\or - \edef\@tempa{% - \ifcase\expandafter\count@\LT@old@row - \else - {1}{0pt}% - \fi}% - \let\LT@entry\relax - \xdef\LT@save@row{% - \LT@entry - \expandafter\LT@max@sel\@tempa - \LT@save@row}} -\def\LT@max@sel#1#2{% - {\ifdim#2=\wd\tw@ - #1% - \else - \number\c@LT@chunks - \fi}% - {\the\wd\tw@}} -\def\LT@hline{% - \noalign{\ifnum0=`}\fi - \penalty\@M - \futurelet\@let@token\LT@@hline} -\def\LT@@hline{% - \ifx\@let@token\hline - \global\let\@gtempa\@gobble - \gdef\LT@sep{\penalty-\@medpenalty\vskip\doublerulesep}% - \else - \global\let\@gtempa\@empty - \gdef\LT@sep{\penalty-\@lowpenalty\vskip-\arrayrulewidth}% - \fi - \ifnum0=`{\fi}% - \multispan\LT@cols - \unskip\leaders\hrule\@height\arrayrulewidth\hfill\cr - \noalign{\LT@sep}% - \multispan\LT@cols - \unskip\leaders\hrule\@height\arrayrulewidth\hfill\cr - \noalign{\penalty\@M}% - \@gtempa} -\def\LT@caption{% - \noalign\bgroup - \@ifnextchar[{\egroup\LT@c@ption\@firstofone}\LT@capti@n} -\def\LT@c@ption#1[#2]#3{% - \LT@makecaption#1\fnum@table{#3}% - \def\@tempa{#2}% - \ifx\@tempa\@empty\else - {\let\\\space - \addcontentsline{lot}{table}{\protect\numberline{\thetable}{#2}}}% - \fi} -\def\LT@capti@n{% - \@ifstar - {\egroup\LT@c@ption\@gobble[]}% - {\egroup\@xdblarg{\LT@c@ption\@firstofone}}} -\def\LT@makecaption#1#2#3{% - \LT@mcol\LT@cols c{\hbox to\z@{\hss\parbox[t]\LTcapwidth{% - \sbox\@tempboxa{#1{#2: }#3}% - \ifdim\wd\@tempboxa>\hsize - #1{#2: }#3% - \else - \hbox to\hsize{\hfil\box\@tempboxa\hfil}% - \fi - \endgraf\vskip\baselineskip}% - \hss}}} -\def\LT@output{% - \ifnum\outputpenalty <-\@Mi - \ifnum\outputpenalty > -\LT@end@pen - \LT@err{floats and marginpars not allowed in a longtable}\@ehc - \else - \setbox\z@\vbox{\unvbox\@cclv}% - \ifdim \ht\LT@lastfoot>\ht\LT@foot - \dimen@\pagegoal - \advance\dimen@-\ht\LT@lastfoot - \ifdim\dimen@<\ht\z@ - \setbox\@cclv\vbox{\unvbox\z@\copy\LT@foot\vss}% - \@makecol - \@outputpage - \setbox\z@\vbox{\box\LT@head}% - \fi - \fi - \global\@colroom\@colht - \global\vsize\@colht - \vbox - {\unvbox\z@\box\ifvoid\LT@lastfoot\LT@foot\else\LT@lastfoot\fi}% - \fi - \else - \setbox\@cclv\vbox{\unvbox\@cclv\copy\LT@foot\vss}% - \@makecol - \@outputpage - \global\vsize\@colroom - \copy\LT@head\nobreak - \fi} -\def\LT@end@hd@ft#1{% - \LT@echunk - \ifx\LT@start\endgraf - \LT@err - {Longtable head or foot not at start of table}% - {Increase LTchunksize}% - \fi - \setbox#1\box\z@ - \LT@get@widths - \LT@bchunk} -\def\endfirsthead{\LT@end@hd@ft\LT@firsthead} -\def\endhead{\LT@end@hd@ft\LT@head} -\def\endfoot{\LT@end@hd@ft\LT@foot} -\def\endlastfoot{\LT@end@hd@ft\LT@lastfoot} -\def\LT@startpbox#1{% - \bgroup - \let\@footnotetext\LT@p@ftntext - \setlength\hsize{#1}% - \@arrayparboxrestore - \vrule \@height \ht\@arstrutbox \@width \z@} -\def\LT@endpbox{% - \@finalstrut\@arstrutbox - \egroup - \the\LT@p@ftn - \global\LT@p@ftn{}% - \hfil} -%% added \long to prevent: -% LaTeX Warning: Command \LT@p@ftntext has changed. -% -% from the original repository (https://github.com/latex3/latex2e/blob/develop/required/tools/longtable.dtx): -% \changes{v4.15}{2021/03/28} -% {make long for gh/364} -% Inside the `p' column, just save up the footnote text in a token -% register. -\long\def\LT@p@ftntext#1{% - \edef\@tempa{\the\LT@p@ftn\noexpand\footnotetext[\the\c@footnote]}% - \global\LT@p@ftn\expandafter{\@tempa{#1}}}% - -\@namedef{ver@longtable.sty}{2014/10/28 v4.11 Multi-page Table package (DPC) - frozen version for doxygen} -\endinput -%% -%% End of file `longtable.sty'. diff --git a/documentation/latex/make.bat b/documentation/latex/make.bat deleted file mode 100644 index 96da1c8..0000000 --- a/documentation/latex/make.bat +++ /dev/null @@ -1,56 +0,0 @@ -pushd %~dp0 -if not %errorlevel% == 0 goto :end - -set ORG_LATEX_CMD=%LATEX_CMD% -set ORG_MKIDX_CMD=%MKIDX_CMD% -set ORG_BIBTEX_CMD=%BIBTEX_CMD% -set ORG_LATEX_COUNT=%LATEX_COUNT% -set ORG_MANUAL_FILE=%MANUAL_FILE% -if "X"%LATEX_CMD% == "X" set LATEX_CMD=pdflatex -if "X"%MKIDX_CMD% == "X" set MKIDX_CMD=makeindex -if "X"%BIBTEX_CMD% == "X" set BIBTEX_CMD=bibtex -if "X"%LATEX_COUNT% == "X" set LATEX_COUNT=8 -if "X"%MANUAL_FILE% == "X" set MANUAL_FILE=refman - -del /s /f *.ps *.dvi *.aux *.toc *.idx *.ind *.ilg *.log *.out *.brf *.blg *.bbl %MANUAL_FILE%.pdf - - -%LATEX_CMD% %MANUAL_FILE% -echo ---- -%MKIDX_CMD% %MANUAL_FILE%.idx -echo ---- -%LATEX_CMD% %MANUAL_FILE% - -setlocal enabledelayedexpansion -set count=%LATEX_COUNT% -:repeat -set content=X -for /F "tokens=*" %%T in ( 'findstr /C:"Rerun LaTeX" %MANUAL_FILE%.log' ) do set content="%%~T" -if !content! == X for /F "tokens=*" %%T in ( 'findstr /C:"Rerun to get cross-references right" %MANUAL_FILE%.log' ) do set content="%%~T" -if !content! == X for /F "tokens=*" %%T in ( 'findstr /C:"Rerun to get bibliographical references right" %MANUAL_FILE%.log' ) do set content="%%~T" -if !content! == X goto :skip -set /a count-=1 -if !count! EQU 0 goto :skip - -echo ---- -%LATEX_CMD% %MANUAL_FILE% -goto :repeat -:skip -endlocal -%MKIDX_CMD% %MANUAL_FILE%.idx -%LATEX_CMD% %MANUAL_FILE% - -@REM reset environment -popd -set LATEX_CMD=%ORG_LATEX_CMD% -set ORG_LATEX_CMD= -set MKIDX_CMD=%ORG_MKIDX_CMD% -set ORG_MKIDX_CMD= -set BIBTEX_CMD=%ORG_BIBTEX_CMD% -set ORG_BIBTEX_CMD= -set MANUAL_FILE=%ORG_MANUAL_FILE% -set ORG_MANUAL_FILE= -set LATEX_COUNT=%ORG_LATEX_COUNT% -set ORG_LATEX_COUNT= - -:end diff --git a/documentation/latex/md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.tex b/documentation/latex/md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.tex deleted file mode 100644 index 7c11183..0000000 --- a/documentation/latex/md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e.tex +++ /dev/null @@ -1,294 +0,0 @@ -\chapter{README} -\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e}{}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e}\index{README@{README}} -Table of Contents. - -\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_readme-top}% -\Hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_readme-top}% - - - -\begin{DoxyEnumerate} -\item \href{\#about}{\texttt{ About}} -\item \href{\#getting-started}{\texttt{ Getting Started}} -\begin{DoxyItemize} -\item \href{\#wiring}{\texttt{ Wiring}} -\item \href{\#adding-to-project}{\texttt{ Adding to Project}} -\item \href{\#menuconfig}{\texttt{ Menuconfig}} -\item \href{\#examples}{\texttt{ Examples}} -\end{DoxyItemize} -\item \href{\#unit-tests}{\texttt{ Unit Tests}} -\begin{DoxyItemize} -\item \href{\#running-tests}{\texttt{ Running Tests}} -\item \href{\#adding-tests}{\texttt{ Adding Tests}} -\end{DoxyItemize} -\item \href{\#documentation}{\texttt{ Documentation}} -\item \href{\#program-flowcharts}{\texttt{ Program Flowcharts}} -\item \href{\#acknowledgements}{\texttt{ Acknowledgements}} -\item \href{\#license}{\texttt{ License}} -\item \href{\#contact}{\texttt{ Contact}} -\end{DoxyEnumerate}\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md0}{}\doxysubsection{\texorpdfstring{About}{About}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md0} -esp32\+\_\+\+BNO08x is a C++ component for esp-\/idf v5.\+x, serving as a driver for both BNO080 and BNO085 IMUs. ~\newline - - -Originally based on the Spark\+Fun BNO080 Arduino Library, it has since diverged significantly in implementation while retaining all original features and more, including callback functions enabled by its multi-\/tasked approach. - -Currently, only SPI is supported. There are no plans to support I2C due to unpredictable behavior caused by an esp32 I2C driver silicon bug. UART support may be implemented in the future.\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md1}{}\doxysubsection{\texorpdfstring{Getting Started}{Getting Started}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md1} -(\href{\#readme-top}{\texttt{ back to top}})\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md2}{}\doxysubsubsection{\texorpdfstring{Wiring}{Wiring}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md2} -The default wiring is depicted below, it can be changed at driver initialization (see example section). ~\newline - - -If your ESP does not have the GPIO pin numbers depicted below, you {\bfseries{must change the default GPIO settings in menuconfig}}. See the Menuconfig section. - - - -(\href{\#readme-top}{\texttt{ back to top}})\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md3}{}\doxysubsubsection{\texorpdfstring{Adding to Project}{Adding to Project}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md3} - -\begin{DoxyEnumerate} -\item Create a "{}components"{} directory in the root workspace directory of your esp-\/idf project if it does not exist already. ~\newline - - -In workspace directory\+: ~\newline - -\begin{DoxyCode}{0} -\DoxyCodeLine{mkdir\ components} - -\end{DoxyCode} - -\item Cd into the components directory and clone the esp32\+\_\+\+BNO08x repo. - - -\begin{DoxyCode}{0} -\DoxyCodeLine{cd\ components} -\DoxyCodeLine{git\ clone\ https://github.com/myles-\/parfeniuk/esp32\_BNO08x.git} - -\end{DoxyCode} - -\item Ensure you clean your esp-\/idf project before rebuilding. ~\newline - Within esp-\/idf enabled terminal\+: -\begin{DoxyCode}{0} -\DoxyCodeLine{idf.py\ fullclean} - -\end{DoxyCode} - -\end{DoxyEnumerate} - -(\href{\#readme-top}{\texttt{ back to top}})\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md4}{}\doxysubsubsection{\texorpdfstring{Menuconfig}{Menuconfig}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md4} -This library provides a menuconfig menu configured in Kconfig.\+projbuild. It contains settings to control the default GPIO and a few other things. ~\newline - - -To access the menu\+: - - -\begin{DoxyEnumerate} -\item Within esp-\/idf enabled terminal, execute the menuconfig command\+: -\begin{DoxyCode}{0} -\DoxyCodeLine{idf.py\ menuconfig} - -\end{DoxyCode} - -\item Scroll down to the esp\+\_\+\+BNO08x menu and enter it, if you\textquotesingle{}re using vs\+Code you may have to use the "{}j"{} and "{}k"{} keys instead of the arrow keys. -\item Modify whatever settings you\textquotesingle{}d like from the sub menus. The GPIO Configuration menu allows for the default GPIO pins to be modified, the SPI Configuration menu allows for the default host peripheral, SCLK frequency, and queue size to be modified, the Logging menu allows for the enabling and disabling of log/print statements, and the Callbacks menu allows for the default size of the call-\/back execution task to be modified. -\end{DoxyEnumerate} - -(\href{\#readme-top}{\texttt{ back to top}})\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md5}{}\doxysubsubsection{\texorpdfstring{Examples}{Examples}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md5} -There are two ways data returned from the \doxylink{class_b_n_o08x}{BNO08x} can be accessed with this library\+: - - -\begin{DoxyEnumerate} -\item {\bfseries{Polling Method with}} {\ttfamily data\+\_\+available()} {\bfseries{Function}}\+: -\begin{DoxyItemize} -\item Use the {\ttfamily data\+\_\+available()} function to poll for new data, similar to the Spark\+Fun library. -\item Behavior\+: It is a blocking function that returns {\ttfamily true} when new data is received or {\ttfamily false} if a timeout occurs. -\item See the {\bfseries{Polling Example}} below. -\end{DoxyItemize} -\item {\bfseries{Callback Registration with}} {\ttfamily \doxylink{_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573}{register\+\_\+cb()}} {\bfseries{Function}}\+: -\begin{DoxyItemize} -\item Register callback functions that automatically execute upon receiving new data. -\item Behavior\+: The registered callback will be invoked whenever new data is available. -\item See the {\bfseries{Call-\/\+Back Function Example}} below. -\end{DoxyItemize} -\end{DoxyEnumerate}\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md6}{}\doxyparagraph{\texorpdfstring{Polling Example}{Polling Example}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md6} - -\begin{DoxyCode}{0} -\DoxyCodeLine{\textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{\textcolor{preprocessor}{\#include\ "{}\mbox{\hyperlink{_b_n_o08x_8hpp}{BNO08x.hpp}}"{}}} -\DoxyCodeLine{} -\DoxyCodeLine{\textcolor{keyword}{extern}\ \textcolor{stringliteral}{"{}C"{}}\ \textcolor{keywordtype}{void}\ app\_main(\textcolor{keywordtype}{void})} -\DoxyCodeLine{\{} -\DoxyCodeLine{\ \ \ \ \mbox{\hyperlink{class_b_n_o08x}{BNO08x}}\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}};\ \textcolor{comment}{//create\ IMU\ object\ with\ default\ wiring\ scheme}} -\DoxyCodeLine{\ \ \ \ \textcolor{keywordtype}{float}\ x,\ y,\ z\ =\ 0;} -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \textcolor{comment}{//if\ a\ custom\ wiring\ scheme\ is\ desired\ instead\ of\ default:}} -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \textcolor{comment}{/*}} -\DoxyCodeLine{\textcolor{comment}{\ \ \ \ bno08x\_config\_t\ imu\_config;\ \ \ \ \ //create\ config\ struct}} -\DoxyCodeLine{\textcolor{comment}{\ \ \ \ imu\_config.io\_mosi\ =\ GPIO\_NUM\_X;\ //assign\ pin}} -\DoxyCodeLine{\textcolor{comment}{\ \ \ \ imu\_config.io\_miso\ =\ GPIO\_NUM\_X;\ //assign\ pin}} -\DoxyCodeLine{\textcolor{comment}{\ \ \ \ //etc...}} -\DoxyCodeLine{\textcolor{comment}{\ \ \ \ BNO08x\ imu(imu\_config);\ //pass\ config\ to\ BNO08x\ constructor}} -\DoxyCodeLine{\textcolor{comment}{\ \ \ \ */}} -\DoxyCodeLine{\ \ \ \ } -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.\mbox{\hyperlink{class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798}{initialize}}();\ \ \textcolor{comment}{//initialize\ IMU}} -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \textcolor{comment}{//enable\ gyro\ \&\ game\ rotation\ vector}} -\DoxyCodeLine{\ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.\mbox{\hyperlink{class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947}{enable\_game\_rotation\_vector}}(100000UL);\ \textcolor{comment}{//100,000us\ ==\ 100ms\ report\ interval}} -\DoxyCodeLine{\ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.enable\_gyro(150000UL);\ \textcolor{comment}{//150,000us\ ==\ 150ms\ report\ interval\ }} -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \textcolor{keywordflow}{while}(1)} -\DoxyCodeLine{\ \ \ \ \{} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \textcolor{comment}{//print\ absolute\ heading\ in\ degrees\ and\ angular\ velocity\ in\ Rad/s}} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}(\mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.\mbox{\hyperlink{class_b_n_o08x_ab56b185d6c9e972a2b28c2621387bb86}{data\_available}}())} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ x\ =\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.get\_gyro\_calibrated\_velocity\_X();} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ y\ =\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.get\_gyro\_calibrated\_velocity\_Y();} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ z\ =\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.get\_gyro\_calibrated\_velocity\_Z();} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ ESP\_LOGW(\textcolor{stringliteral}{"{}Main"{}},\ \textcolor{stringliteral}{"{}Velocity:\ x:\ \%.3f\ y:\ \%.3f\ z:\ \%.3f"{}},\ x,\ y,\ z);} -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ x\ =\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.\mbox{\hyperlink{class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6}{get\_roll\_deg}}();} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ y\ =\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.\mbox{\hyperlink{class_b_n_o08x_af50010400cbd1445e9ddfa259384b412}{get\_pitch\_deg}}();} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ z\ =\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.\mbox{\hyperlink{class_b_n_o08x_af80f7795656e695e036d3b1557aed94c}{get\_yaw\_deg}}();} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ ESP\_LOGI(\textcolor{stringliteral}{"{}Main"{}},\ \textcolor{stringliteral}{"{}Euler\ Angle:\ x\ (roll):\ \%.3f\ y\ (pitch):\ \%.3f\ z\ (yaw):\ \%.3f"{}},\ x,\ y,\ z);} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \}} -\DoxyCodeLine{\ \ \ \ \}} -\DoxyCodeLine{} -\DoxyCodeLine{\}} - -\end{DoxyCode} -\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md7}{}\doxyparagraph{\texorpdfstring{Call-\/\+Back Function Example}{Call-\/\+Back Function Example}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md7} - -\begin{DoxyCode}{0} -\DoxyCodeLine{\textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{\textcolor{preprocessor}{\#include\ "{}\mbox{\hyperlink{_b_n_o08x_8hpp}{BNO08x.hpp}}"{}}} -\DoxyCodeLine{} -\DoxyCodeLine{\textcolor{keyword}{extern}\ \textcolor{stringliteral}{"{}C"{}}\ \textcolor{keywordtype}{void}\ app\_main(\textcolor{keywordtype}{void})} -\DoxyCodeLine{\{} -\DoxyCodeLine{\ \ \ \ \mbox{\hyperlink{class_b_n_o08x}{BNO08x}}\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}};\ \textcolor{comment}{//\ create\ IMU\ object\ with\ default\ wiring\ scheme}} -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \textcolor{comment}{//\ if\ a\ custom\ wiring\ scheme\ is\ desired\ instead\ of\ default:}} -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \textcolor{comment}{/*}} -\DoxyCodeLine{\textcolor{comment}{\ \ \ \ bno08x\_config\_t\ imu\_config;\ \ \ \ \ //create\ config\ struct}} -\DoxyCodeLine{\textcolor{comment}{\ \ \ \ imu\_config.io\_mosi\ =\ GPIO\_NUM\_X;\ //assign\ pin}} -\DoxyCodeLine{\textcolor{comment}{\ \ \ \ imu\_config.io\_miso\ =\ GPIO\_NUM\_X;\ //assign\ pin}} -\DoxyCodeLine{\textcolor{comment}{\ \ \ \ //etc...}} -\DoxyCodeLine{\textcolor{comment}{\ \ \ \ BNO08x\ imu(imu\_config);\ //pass\ config\ to\ BNO08x\ constructor}} -\DoxyCodeLine{\textcolor{comment}{\ \ \ \ */}} -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.\mbox{\hyperlink{class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798}{initialize}}();\ \textcolor{comment}{//\ initialize\ IMU}} -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \textcolor{comment}{//\ enable\ gyro\ \&\ game\ rotation\ vector}} -\DoxyCodeLine{\ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.\mbox{\hyperlink{class_b_n_o08x_abe04c38b5bd52d331bd8aefae1f51947}{enable\_game\_rotation\_vector}}(100000UL);\ \textcolor{comment}{//\ 100,000us\ ==\ 100ms\ report\ interval}} -\DoxyCodeLine{\ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.enable\_gyro(150000UL);\ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ 150,000us\ ==\ 150ms\ report\ interval}} -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \textcolor{comment}{//\ register\ a\ callback\ function\ (in\ this\ case\ a\ lambda\ function,\ but\ it\ doesn't\ have\ to\ be)}} -\DoxyCodeLine{\ \ \ \ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.\mbox{\hyperlink{class_b_n_o08x_a06bb0c70305421b5357e64f31579fdc7}{register\_cb}}(} -\DoxyCodeLine{\ \ \ \ \ \ \ \ [\&\mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}]()} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \{} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ callback\ function\ contents,\ executed\ whenever\ new\ data\ is\ parsed}} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \textcolor{comment}{//\ print\ absolute\ heading\ in\ degrees\ and\ angular\ velocity\ in\ Rad/s}} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ x,\ y,\ z\ =\ 0;} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ x\ =\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.get\_gyro\_calibrated\_velocity\_X();} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ y\ =\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.get\_gyro\_calibrated\_velocity\_Y();} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ z\ =\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.get\_gyro\_calibrated\_velocity\_Z();} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ ESP\_LOGW(\textcolor{stringliteral}{"{}Main"{}},\ \textcolor{stringliteral}{"{}Velocity:\ x:\ \%.3f\ y:\ \%.3f\ z:\ \%.3f"{}},\ x,\ y,\ z);} -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ x\ =\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.\mbox{\hyperlink{class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6}{get\_roll\_deg}}();} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ y\ =\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.\mbox{\hyperlink{class_b_n_o08x_af50010400cbd1445e9ddfa259384b412}{get\_pitch\_deg}}();} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ z\ =\ \mbox{\hyperlink{_callback_tests_8cpp_ac36e56130d5d806898f3545d4cdf0f70}{imu}}.\mbox{\hyperlink{class_b_n_o08x_af80f7795656e695e036d3b1557aed94c}{get\_yaw\_deg}}();} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ ESP\_LOGI(\textcolor{stringliteral}{"{}Main"{}},\ \textcolor{stringliteral}{"{}Euler\ Angle:\ x\ (roll):\ \%.3f\ y\ (pitch):\ \%.3f\ z\ (yaw):\ \%.3f"{}},\ x,\ y,\ z);} -\DoxyCodeLine{\ \ \ \ \ \ \ \ \});} -\DoxyCodeLine{} -\DoxyCodeLine{\ \ \ \ \textcolor{keywordflow}{while}\ (1)} -\DoxyCodeLine{\ \ \ \ \{} -\DoxyCodeLine{\ \ \ \ \ \ \ \ vTaskDelay(300\ /\ portTICK\_PERIOD\_MS);\ \textcolor{comment}{//\ delay\ here\ is\ irrelevant,\ we\ just\ don't\ want\ to\ trip\ cpu\ watchdog}} -\DoxyCodeLine{\ \ \ \ \}} -\DoxyCodeLine{\}} - -\end{DoxyCode} - - -(\href{\#readme-top}{\texttt{ back to top}})\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md8}{}\doxysubsection{\texorpdfstring{Unit Tests}{Unit Tests}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md8} -A basic unit testing suite is included with this library, but it is very rudimentary. ~\newline - It can be used to verify some of the basic features of a \doxylink{class_b_n_o08x}{BNO08x} device and this library. - -(\href{\#readme-top}{\texttt{ back to top}})\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md9}{}\doxysubsubsection{\texorpdfstring{Running Tests}{Running Tests}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md9} - -\begin{DoxyEnumerate} -\item Create a project and add the component as described in the getting started guide. -\item Open the outermost CMake\+Lists.\+txt file in the project root directory, as depicted below. ~\newline - - - -\item Modify the file by adding "{}set(\+TEST\+\_\+\+COMPONENTS "{}esp32\+\_\+\+BNO08x"{} CACHE STRING "{}Components to test."{})"{} as depicted below\+: ~\newline - - - -\begin{DoxyCode}{0} -\DoxyCodeLine{\#\ For\ more\ information\ about\ build\ system\ see} -\DoxyCodeLine{\#\ https://docs.espressif.com/projects/esp-\/idf/en/latest/api-\/guides/build-\/system.html} -\DoxyCodeLine{\#\ The\ following\ five\ lines\ of\ boilerplate\ have\ to\ be\ in\ your\ project's} -\DoxyCodeLine{\#\ CMakeLists\ in\ this\ exact\ order\ for\ cmake\ to\ work\ correctly} -\DoxyCodeLine{cmake\_minimum\_required(VERSION\ 3.16)} -\DoxyCodeLine{add\_compile\_definitions("{}ESP32C3\_IMU\_CONFIG"{})} -\DoxyCodeLine{set(TEST\_COMPONENTS\ "{}esp32\_BNO08x"{}\ CACHE\ STRING\ "{}Components\ to\ test."{})} -\DoxyCodeLine{include(\$ENV\{IDF\_PATH\}/tools/cmake/project.cmake)} -\DoxyCodeLine{project(bno08x\_update)} - -\end{DoxyCode} - -\item Include the test suite in your main file and launch into the test suite\+: ~\newline - - - -\begin{DoxyCode}{0} -\DoxyCodeLine{\textcolor{preprocessor}{\#include\ }} -\DoxyCodeLine{\textcolor{preprocessor}{\#include\ "{}\mbox{\hyperlink{_b_n_o08x_test_suite_8hpp}{BNO08xTestSuite.hpp}}"{}}} -\DoxyCodeLine{} -\DoxyCodeLine{\textcolor{keyword}{extern}\ \textcolor{stringliteral}{"{}C"{}}\ \textcolor{keywordtype}{void}\ app\_main(\textcolor{keywordtype}{void})} -\DoxyCodeLine{\{} -\DoxyCodeLine{\ \ \ \ \mbox{\hyperlink{class_b_n_o08x_test_suite_ac12545fe311a98e9c0ae6fea77da95fd}{BNO08xTestSuite::run\_all\_tests}}();\ } -\DoxyCodeLine{\}} - -\end{DoxyCode} - -\item Ensure you run {\ttfamily idf.\+py fullclean} or delete your build directory before building for the first time after modifying the CMake\+Lists.\+txt file in step 3. -\end{DoxyEnumerate} - -(\href{\#readme-top}{\texttt{ back to top}})\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md10}{}\doxysubsubsection{\texorpdfstring{Adding Tests}{Adding Tests}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md10} -Tests are implemented with the \href{https://docs.espressif.com/projects/esp-idf/en/stable/esp32/api-guides/unit-tests.html}{\texttt{ unity unit testing component}}. - -To add a test, create a new .cpp file, or modify one of the existing ones in {\ttfamily esp32\+\_\+\+BNO08x/test/}. Follow the existing test structure as an example, use the {\ttfamily \doxylink{_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa}{TEST\+\_\+\+CASE()}\{\}} macro. ~\newline - - -Any tests added will automatically be detected at build time. - -(\href{\#readme-top}{\texttt{ back to top}})\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md11}{}\doxysubsection{\texorpdfstring{Documentation}{Documentation}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md11} -API documentation generated with doxygen can be found in the documentation directory of the master branch. ~\newline - - -(\href{\#readme-top}{\texttt{ back to top}})\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md12}{}\doxysubsection{\texorpdfstring{Program Flowcharts}{Program Flowcharts}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md12} -The following charts illustrate the program flow this library implements for sending and receiving data from \doxylink{class_b_n_o08x}{BNO08x}. ~\newline - These are here to aid development for anyone looking to modify, fork, or contribute. ~\newline - - - - -(\href{\#readme-top}{\texttt{ back to top}})\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md13}{}\doxysubsection{\texorpdfstring{Acknowledgements}{Acknowledgements}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md13} -Special thanks to the original creators of the sparkfun BNO080 library. Developing this without a reference would have been much more time consuming. ~\newline - \href{https://github.com/sparkfun/SparkFun_BNO080_Arduino_Library}{\texttt{ https\+://github.\+com/sparkfun/\+Spark\+Fun\+\_\+\+BNO080\+\_\+\+Arduino\+\_\+\+Library}} ~\newline - - -Special thanks to Anton Babiy, aka hw\+Birdy007 for helping with debugging SPI. ~\newline - \href{https://github.com/hwBirdy007}{\texttt{ https\+://github.\+com/hw\+Birdy007}} ~\newline - - -(\href{\#readme-top}{\texttt{ back to top}})\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md14}{}\doxysubsection{\texorpdfstring{License}{License}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md14} -Distributed under the MIT License. See {\ttfamily LICENSE.\+md} for more information. - -(\href{\#readme-top}{\texttt{ back to top}})\hypertarget{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md15}{}\doxysubsection{\texorpdfstring{Contact}{Contact}}\label{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md15} -Myles Parfeniuk -\/ \href{mailto:myles.parfenyuk@gmail.com}{\texttt{ myles.\+parfenyuk@gmail.\+com}} - -Project Link\+: \href{https://github.com/myles-parfeniuk/esp32_BNO08x.git}{\texttt{ https\+://github.\+com/myles-\/parfeniuk/esp32\+\_\+\+BNO08x.\+git}} - -(\href{\#readme-top}{\texttt{ back to top}}) \ No newline at end of file diff --git a/documentation/latex/refman.tex b/documentation/latex/refman.tex deleted file mode 100644 index 7425341..0000000 --- a/documentation/latex/refman.tex +++ /dev/null @@ -1,251 +0,0 @@ - % Handle batch mode - % to overcome problems with too many open files - \let\mypdfximage\pdfximage\def\pdfximage{\immediate\mypdfximage} - \pdfminorversion=7 - % Set document class depending on configuration - \documentclass[twoside]{book} - %% moved from doxygen.sty due to workaround for LaTex 2019 version and unmaintained tabu package - \usepackage{ifthen} - \ifx\requestedLaTeXdate\undefined - \usepackage{array} - \else - \usepackage{array}[=2016-10-06] - \fi - %% - % Packages required by doxygen - \makeatletter - \providecommand\IfFormatAtLeastTF{\@ifl@t@r\fmtversion} - % suppress package identification of infwarerr as it contains the word "warning" - \let\@@protected@wlog\protected@wlog - \def\protected@wlog#1{\wlog{package info suppressed}} - \RequirePackage{infwarerr} - \let\protected@wlog\@@protected@wlog - \makeatother - \IfFormatAtLeastTF{2016/01/01}{}{\usepackage{fixltx2e}} % for \textsubscript - \IfFormatAtLeastTF{2015/01/01}{\pdfsuppresswarningpagegroup=1}{} - \usepackage{doxygen} - \usepackage{graphicx} - \usepackage[utf8]{inputenc} - \usepackage{makeidx} - \PassOptionsToPackage{warn}{textcomp} - \usepackage{textcomp} - \usepackage[nointegrals]{wasysym} - \usepackage{ifxetex} - % NLS support packages - % Define default fonts - % Font selection - \usepackage[T1]{fontenc} - % set main and monospaced font - \usepackage[scaled=.90]{helvet} -\usepackage{courier} -\renewcommand{\familydefault}{\sfdefault} - \doxyallsectionsfont{% - \fontseries{bc}\selectfont% - \color{darkgray}% - } - \renewcommand{\DoxyLabelFont}{% - \fontseries{bc}\selectfont% - \color{darkgray}% - } - \newcommand{\+}{\discretionary{\mbox{\scriptsize$\hookleftarrow$}}{}{}} - % Arguments of doxygenemoji: - % 1) '::' form of the emoji, already LaTeX-escaped - % 2) file with the name of the emoji without the .png extension - % in case image exist use this otherwise use the '::' form - \newcommand{\doxygenemoji}[2]{% - \IfFileExists{./#2.png}{\raisebox{-0.1em}{\includegraphics[height=0.9em]{./#2.png}}}{#1}% - } - % Page & text layout - \usepackage{geometry} - \geometry{% - a4paper,% - top=2.5cm,% - bottom=2.5cm,% - left=2.5cm,% - right=2.5cm% - } - \usepackage{changepage} - % Allow a bit of overflow to go unnoticed by other means - \tolerance=750 - \hfuzz=15pt - \hbadness=750 - \setlength{\emergencystretch}{15pt} - \setlength{\parindent}{0cm} - \newcommand{\doxynormalparskip}{\setlength{\parskip}{3ex plus 2ex minus 2ex}} - \newcommand{\doxytocparskip}{\setlength{\parskip}{1ex plus 0ex minus 0ex}} - \doxynormalparskip - % Redefine paragraph/subparagraph environments, using sectsty fonts - \makeatletter - \renewcommand{\paragraph}{% - \@startsection{paragraph}{4}{0ex}{-1.0ex}{1.0ex}{% - \normalfont\normalsize\bfseries\SS@parafont% - }% - } - \renewcommand{\subparagraph}{% - \@startsection{subparagraph}{5}{0ex}{-1.0ex}{1.0ex}{% - \normalfont\normalsize\bfseries\SS@subparafont% - }% - } - \makeatother - \makeatletter - \newcommand\hrulefilll{\leavevmode\leaders\hrule\hskip 0pt plus 1filll\kern\z@} - \makeatother - % Headers & footers - \usepackage{fancyhdr} - \pagestyle{fancyplain} - \renewcommand{\footrulewidth}{0.4pt} - \fancypagestyle{fancyplain}{ - \fancyhf{} - \fancyhead[LE, RO]{\bfseries\thepage} - \fancyhead[LO]{\bfseries\rightmark} - \fancyhead[RE]{\bfseries\leftmark} - \fancyfoot[LO, RE]{\bfseries\scriptsize Generated by Doxygen } - } - \fancypagestyle{plain}{ - \fancyhf{} - \fancyfoot[LO, RE]{\bfseries\scriptsize Generated by Doxygen } - \renewcommand{\headrulewidth}{0pt} - } - \pagestyle{fancyplain} - \renewcommand{\chaptermark}[1]{% - \markboth{#1}{}% - } - \renewcommand{\sectionmark}[1]{% - \markright{\thesection\ #1}% - } - % ToC, LoF, LoT, bibliography, and index - % Indices & bibliography - \usepackage{natbib} - \usepackage[titles]{tocloft} - \setcounter{tocdepth}{3} - \setcounter{secnumdepth}{5} - % creating indexes - \makeindex - \usepackage{newunicodechar} - \makeatletter - \def\doxynewunicodechar#1#2{% - \@tempswafalse - \edef\nuc@tempa{\detokenize{#1}}% - \if\relax\nuc@tempa\relax - \nuc@emptyargerr - \else - \edef\@tempb{\expandafter\@car\nuc@tempa\@nil}% - \nuc@check - \if@tempswa - \@namedef{u8:\nuc@tempa}{#2}% - \fi - \fi - } - \makeatother - \doxynewunicodechar{⁻}{${}^{-}$}% Superscript minus - \doxynewunicodechar{²}{${}^{2}$}% Superscript two - \doxynewunicodechar{³}{${}^{3}$}% Superscript three - % Hyperlinks - % Hyperlinks (required, but should be loaded last) - \ifpdf - \usepackage[pdftex,pagebackref=true]{hyperref} - \else - \ifxetex - \usepackage[pagebackref=true]{hyperref} - \else - \usepackage[ps2pdf,pagebackref=true]{hyperref} - \fi - \fi - \hypersetup{% - colorlinks=true,% - linkcolor=blue,% - citecolor=blue,% - unicode,% - pdftitle={esp32\+\_\+\+BNO08x},% - pdfsubject={C++ BNO08x IMU driver component for esp-\/idf.}% - } - % Custom commands used by the header - % Custom commands - \newcommand{\clearemptydoublepage}{% - \newpage{\pagestyle{empty}\cleardoublepage}% - } - % caption style definition - \usepackage{caption} - \captionsetup{labelsep=space,justification=centering,font={bf},singlelinecheck=off,skip=4pt,position=top} - % in page table of contents - \IfFormatAtLeastTF{2023/05/01}{\usepackage[deeplevels]{etoc}}{\usepackage[deeplevels]{etoc_doxygen}} - \etocsettocstyle{\doxytocparskip}{\doxynormalparskip} - \etocsetlevel{subsubsubsection}{4} - \etocsetlevel{subsubsubsubsection}{5} - \etocsetlevel{subsubsubsubsubsection}{6} - \etocsetlevel{subsubsubsubsubsubsection}{7} - \etocsetlevel{paragraph}{8} - \etocsetlevel{subparagraph}{9} - % prevent numbers overlap the titles in toc - \renewcommand{\numberline}[1]{#1~} -% End of preamble, now comes the document contents -%===== C O N T E N T S ===== -\begin{document} - \raggedbottom - % Titlepage & ToC - % To avoid duplicate page anchors due to reuse of same numbers for - % the index (be it as roman numbers) - \hypersetup{pageanchor=false, - bookmarksnumbered=true, - pdfencoding=unicode - } - \pagenumbering{alph} - \begin{titlepage} - \vspace*{7cm} - \begin{center}% - {\Large esp32\+\_\+\+BNO08x}\\ - [1ex]\large 1.\+2 \\ - \vspace*{1cm} - {\large Generated by Doxygen 1.10.0}\\ - \end{center} - \end{titlepage} - \clearemptydoublepage - \pagenumbering{roman} - \tableofcontents - \clearemptydoublepage - \pagenumbering{arabic} - % re-enable anchors again - \hypersetup{pageanchor=true} -%--- Begin generated contents --- -\input{md__d_1_2development_2git_2imu__update_2bno08x__update_2components_2esp32___b_n_o08x_2_r_e_a_d_m_e} -\chapter{Class Index} -\input{annotated} -\chapter{File Index} -\input{files} -\chapter{Class Documentation} -\input{class_b_n_o08x} -\input{structbno08x__config__t} -\input{struct_b_n_o08x_1_1bno08x__init__status__t} -\input{struct_b_n_o08x_1_1bno08x__report__period__tracker__t} -\input{struct_b_n_o08x_1_1bno08x__rx__packet__t} -\input{struct_b_n_o08x_1_1bno08x__tx__packet__t} -\input{class_b_n_o08x_test_helper} -\input{class_b_n_o08x_test_suite} -\input{struct_b_n_o08x_test_helper_1_1imu__report__data__t} -\chapter{File Documentation} -\input{_b_n_o08x_8hpp} -\input{_b_n_o08x_8hpp_source} -\input{_b_n_o08x__global__types_8hpp} -\input{_b_n_o08x__global__types_8hpp_source} -\input{_b_n_o08x__macros_8hpp} -\input{_b_n_o08x__macros_8hpp_source} -\input{_b_n_o08x_test_helper_8hpp} -\input{_b_n_o08x_test_helper_8hpp_source} -\input{_b_n_o08x_test_suite_8hpp} -\input{_b_n_o08x_test_suite_8hpp_source} -\input{_r_e_a_d_m_e_8md} -\input{_b_n_o08x_8cpp} -\input{_callback_tests_8cpp} -\input{_init_deinit_tests_8cpp} -\input{_multi_report_tests_8cpp} -\input{_single_report_tests_8cpp} -%--- End generated contents --- -% Index - \backmatter - \newpage - \phantomsection - \clearemptydoublepage - \addcontentsline{toc}{chapter}{\indexname} - \printindex -% Required for some languages (in combination with latexdocumentpre from the header) -\end{document} diff --git a/documentation/latex/struct_b_n_o08x_1_1bno08x__init__status__t.tex b/documentation/latex/struct_b_n_o08x_1_1bno08x__init__status__t.tex deleted file mode 100644 index 7275273..0000000 --- a/documentation/latex/struct_b_n_o08x_1_1bno08x__init__status__t.tex +++ /dev/null @@ -1,143 +0,0 @@ -\doxysection{BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t Struct Reference} -\hypertarget{struct_b_n_o08x_1_1bno08x__init__status__t}{}\label{struct_b_n_o08x_1_1bno08x__init__status__t}\index{BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}} - - -Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup). - - -\doxysubsubsection*{Public Member Functions} -\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a26db0bb1cf4ad4272a363c9995cc6851}{bno08x\+\_\+init\+\_\+status\+\_\+t}} () -\end{DoxyCompactItemize} -\doxysubsubsection*{Public Attributes} -\begin{DoxyCompactItemize} -\item -bool \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a918d393541f260ae059614ed477887df}{gpio\+\_\+outputs}} -\begin{DoxyCompactList}\small\item\em True if GPIO outputs have been initialized. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a7439c3e0e98c3c2276f8607e5a36b557}{gpio\+\_\+inputs}} -\begin{DoxyCompactList}\small\item\em True if GPIO inputs have been initialized. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a277d28ef5596d4777476d64de3f2d905}{isr\+\_\+service}} -\begin{DoxyCompactList}\small\item\em True if global ISR service has been initialized. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_aa04ab662c6a1a052944312ca79a17bc3}{isr\+\_\+handler}} -\begin{DoxyCompactList}\small\item\em True if HINT ISR handler has been initialized. \end{DoxyCompactList}\item -uint8\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a6b2d0002d0e817d6384a1064453eb84d}{task\+\_\+count}} -\begin{DoxyCompactList}\small\item\em How many successfully initialized tasks (max of TSK\+\_\+\+CNT) \end{DoxyCompactList}\item -bool \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a04ef18c7f80f305a621b6cc3e5b6107d}{data\+\_\+proc\+\_\+task}} -\begin{DoxyCompactList}\small\item\em True if x\+Task\+Create has been called successfully for data\+\_\+proc\+\_\+task. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a92f78cc3fd3161bbc1fcad08b9c6bcb5}{spi\+\_\+task}} -\begin{DoxyCompactList}\small\item\em True if x\+Task\+Create has been called successfully for spi\+\_\+task. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_a9855844dee2cd51e734693294d5cc438}{spi\+\_\+bus}} -\begin{DoxyCompactList}\small\item\em True if spi\+\_\+bus\+\_\+initialize() has been called successfully. \end{DoxyCompactList}\item -bool \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__init__status__t_aa7c583b48551710dd4f71bb5a72c029a}{spi\+\_\+device}} -\begin{DoxyCompactList}\small\item\em True if spi\+\_\+bus\+\_\+add\+\_\+device() has been called successfully. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup). - -\doxysubsection{Constructor \& Destructor Documentation} -\Hypertarget{struct_b_n_o08x_1_1bno08x__init__status__t_a26db0bb1cf4ad4272a363c9995cc6851}\label{struct_b_n_o08x_1_1bno08x__init__status__t_a26db0bb1cf4ad4272a363c9995cc6851} -\index{BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}!bno08x\_init\_status\_t@{bno08x\_init\_status\_t}} -\index{bno08x\_init\_status\_t@{bno08x\_init\_status\_t}!BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}} -\doxysubsubsection{\texorpdfstring{bno08x\_init\_status\_t()}{bno08x\_init\_status\_t()}} -{\footnotesize\ttfamily BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t\+::bno08x\+\_\+init\+\_\+status\+\_\+t (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}} - - - -\doxysubsection{Member Data Documentation} -\Hypertarget{struct_b_n_o08x_1_1bno08x__init__status__t_a04ef18c7f80f305a621b6cc3e5b6107d}\label{struct_b_n_o08x_1_1bno08x__init__status__t_a04ef18c7f80f305a621b6cc3e5b6107d} -\index{BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}!data\_proc\_task@{data\_proc\_task}} -\index{data\_proc\_task@{data\_proc\_task}!BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}} -\doxysubsubsection{\texorpdfstring{data\_proc\_task}{data\_proc\_task}} -{\footnotesize\ttfamily bool BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t\+::data\+\_\+proc\+\_\+task} - - - -True if x\+Task\+Create has been called successfully for data\+\_\+proc\+\_\+task. - -\Hypertarget{struct_b_n_o08x_1_1bno08x__init__status__t_a7439c3e0e98c3c2276f8607e5a36b557}\label{struct_b_n_o08x_1_1bno08x__init__status__t_a7439c3e0e98c3c2276f8607e5a36b557} -\index{BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}!gpio\_inputs@{gpio\_inputs}} -\index{gpio\_inputs@{gpio\_inputs}!BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}} -\doxysubsubsection{\texorpdfstring{gpio\_inputs}{gpio\_inputs}} -{\footnotesize\ttfamily bool BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t\+::gpio\+\_\+inputs} - - - -True if GPIO inputs have been initialized. - -\Hypertarget{struct_b_n_o08x_1_1bno08x__init__status__t_a918d393541f260ae059614ed477887df}\label{struct_b_n_o08x_1_1bno08x__init__status__t_a918d393541f260ae059614ed477887df} -\index{BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}!gpio\_outputs@{gpio\_outputs}} -\index{gpio\_outputs@{gpio\_outputs}!BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}} -\doxysubsubsection{\texorpdfstring{gpio\_outputs}{gpio\_outputs}} -{\footnotesize\ttfamily bool BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t\+::gpio\+\_\+outputs} - - - -True if GPIO outputs have been initialized. - -\Hypertarget{struct_b_n_o08x_1_1bno08x__init__status__t_aa04ab662c6a1a052944312ca79a17bc3}\label{struct_b_n_o08x_1_1bno08x__init__status__t_aa04ab662c6a1a052944312ca79a17bc3} -\index{BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}!isr\_handler@{isr\_handler}} -\index{isr\_handler@{isr\_handler}!BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}} -\doxysubsubsection{\texorpdfstring{isr\_handler}{isr\_handler}} -{\footnotesize\ttfamily bool BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t\+::isr\+\_\+handler} - - - -True if HINT ISR handler has been initialized. - -\Hypertarget{struct_b_n_o08x_1_1bno08x__init__status__t_a277d28ef5596d4777476d64de3f2d905}\label{struct_b_n_o08x_1_1bno08x__init__status__t_a277d28ef5596d4777476d64de3f2d905} -\index{BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}!isr\_service@{isr\_service}} -\index{isr\_service@{isr\_service}!BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}} -\doxysubsubsection{\texorpdfstring{isr\_service}{isr\_service}} -{\footnotesize\ttfamily bool BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t\+::isr\+\_\+service} - - - -True if global ISR service has been initialized. - -\Hypertarget{struct_b_n_o08x_1_1bno08x__init__status__t_a9855844dee2cd51e734693294d5cc438}\label{struct_b_n_o08x_1_1bno08x__init__status__t_a9855844dee2cd51e734693294d5cc438} -\index{BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}!spi\_bus@{spi\_bus}} -\index{spi\_bus@{spi\_bus}!BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}} -\doxysubsubsection{\texorpdfstring{spi\_bus}{spi\_bus}} -{\footnotesize\ttfamily bool BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t\+::spi\+\_\+bus} - - - -True if spi\+\_\+bus\+\_\+initialize() has been called successfully. - -\Hypertarget{struct_b_n_o08x_1_1bno08x__init__status__t_aa7c583b48551710dd4f71bb5a72c029a}\label{struct_b_n_o08x_1_1bno08x__init__status__t_aa7c583b48551710dd4f71bb5a72c029a} -\index{BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}!spi\_device@{spi\_device}} -\index{spi\_device@{spi\_device}!BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}} -\doxysubsubsection{\texorpdfstring{spi\_device}{spi\_device}} -{\footnotesize\ttfamily bool BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t\+::spi\+\_\+device} - - - -True if spi\+\_\+bus\+\_\+add\+\_\+device() has been called successfully. - -\Hypertarget{struct_b_n_o08x_1_1bno08x__init__status__t_a92f78cc3fd3161bbc1fcad08b9c6bcb5}\label{struct_b_n_o08x_1_1bno08x__init__status__t_a92f78cc3fd3161bbc1fcad08b9c6bcb5} -\index{BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}!spi\_task@{spi\_task}} -\index{spi\_task@{spi\_task}!BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}} -\doxysubsubsection{\texorpdfstring{spi\_task}{spi\_task}} -{\footnotesize\ttfamily bool BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t\+::spi\+\_\+task} - - - -True if x\+Task\+Create has been called successfully for spi\+\_\+task. - -\Hypertarget{struct_b_n_o08x_1_1bno08x__init__status__t_a6b2d0002d0e817d6384a1064453eb84d}\label{struct_b_n_o08x_1_1bno08x__init__status__t_a6b2d0002d0e817d6384a1064453eb84d} -\index{BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}!task\_count@{task\_count}} -\index{task\_count@{task\_count}!BNO08x::bno08x\_init\_status\_t@{BNO08x::bno08x\_init\_status\_t}} -\doxysubsubsection{\texorpdfstring{task\_count}{task\_count}} -{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::bno08x\+\_\+init\+\_\+status\+\_\+t\+::task\+\_\+count} - - - -How many successfully initialized tasks (max of TSK\+\_\+\+CNT) - - - -The documentation for this struct was generated from the following file\+:\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_b_n_o08x_8hpp}{BNO08x.\+hpp}}\end{DoxyCompactItemize} diff --git a/documentation/latex/struct_b_n_o08x_1_1bno08x__report__period__tracker__t.tex b/documentation/latex/struct_b_n_o08x_1_1bno08x__report__period__tracker__t.tex deleted file mode 100644 index a1f742c..0000000 --- a/documentation/latex/struct_b_n_o08x_1_1bno08x__report__period__tracker__t.tex +++ /dev/null @@ -1,29 +0,0 @@ -\doxysection{BNO08x\+::bno08x\+\_\+report\+\_\+period\+\_\+tracker\+\_\+t Struct Reference} -\hypertarget{struct_b_n_o08x_1_1bno08x__report__period__tracker__t}{}\label{struct_b_n_o08x_1_1bno08x__report__period__tracker__t}\index{BNO08x::bno08x\_report\_period\_tracker\_t@{BNO08x::bno08x\_report\_period\_tracker\_t}} -\doxysubsubsection*{Public Attributes} -\begin{DoxyCompactItemize} -\item -uint8\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__report__period__tracker__t_a05dd1697e0b5fda59d112af2c396295c}{report\+\_\+\+ID}} -\item -uint32\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__report__period__tracker__t_a7fe1403bb26f5f4dd845df019bac8614}{period}} -\end{DoxyCompactItemize} - - -\doxysubsection{Member Data Documentation} -\Hypertarget{struct_b_n_o08x_1_1bno08x__report__period__tracker__t_a7fe1403bb26f5f4dd845df019bac8614}\label{struct_b_n_o08x_1_1bno08x__report__period__tracker__t_a7fe1403bb26f5f4dd845df019bac8614} -\index{BNO08x::bno08x\_report\_period\_tracker\_t@{BNO08x::bno08x\_report\_period\_tracker\_t}!period@{period}} -\index{period@{period}!BNO08x::bno08x\_report\_period\_tracker\_t@{BNO08x::bno08x\_report\_period\_tracker\_t}} -\doxysubsubsection{\texorpdfstring{period}{period}} -{\footnotesize\ttfamily uint32\+\_\+t BNO08x\+::bno08x\+\_\+report\+\_\+period\+\_\+tracker\+\_\+t\+::period} - -\Hypertarget{struct_b_n_o08x_1_1bno08x__report__period__tracker__t_a05dd1697e0b5fda59d112af2c396295c}\label{struct_b_n_o08x_1_1bno08x__report__period__tracker__t_a05dd1697e0b5fda59d112af2c396295c} -\index{BNO08x::bno08x\_report\_period\_tracker\_t@{BNO08x::bno08x\_report\_period\_tracker\_t}!report\_ID@{report\_ID}} -\index{report\_ID@{report\_ID}!BNO08x::bno08x\_report\_period\_tracker\_t@{BNO08x::bno08x\_report\_period\_tracker\_t}} -\doxysubsubsection{\texorpdfstring{report\_ID}{report\_ID}} -{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::bno08x\+\_\+report\+\_\+period\+\_\+tracker\+\_\+t\+::report\+\_\+\+ID} - - - -The documentation for this struct was generated from the following file\+:\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_b_n_o08x_8hpp}{BNO08x.\+hpp}}\end{DoxyCompactItemize} diff --git a/documentation/latex/struct_b_n_o08x_1_1bno08x__rx__packet__t.tex b/documentation/latex/struct_b_n_o08x_1_1bno08x__rx__packet__t.tex deleted file mode 100644 index 993b8de..0000000 --- a/documentation/latex/struct_b_n_o08x_1_1bno08x__rx__packet__t.tex +++ /dev/null @@ -1,53 +0,0 @@ -\doxysection{BNO08x\+::bno08x\+\_\+rx\+\_\+packet\+\_\+t Struct Reference} -\hypertarget{struct_b_n_o08x_1_1bno08x__rx__packet__t}{}\label{struct_b_n_o08x_1_1bno08x__rx__packet__t}\index{BNO08x::bno08x\_rx\_packet\_t@{BNO08x::bno08x\_rx\_packet\_t}} - - -Holds data that is received over spi. - - -\doxysubsubsection*{Public Attributes} -\begin{DoxyCompactItemize} -\item -uint8\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t_a667d671ccb272bd375008716e26e0b5b}{header}} \mbox{[}4\mbox{]} -\begin{DoxyCompactList}\small\item\em Header of SHTP packet. \end{DoxyCompactList}\item -uint8\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t_ab422d75e1fcd776ef412f4d623cc293e}{body}} \mbox{[}300\mbox{]} -\item -uint16\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__rx__packet__t_a645adb6ba8fb2afbb99ec58fe678e205}{length}} -\begin{DoxyCompactList}\small\item\em Body of SHTP packet. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -Holds data that is received over spi. - -\doxysubsection{Member Data Documentation} -\Hypertarget{struct_b_n_o08x_1_1bno08x__rx__packet__t_ab422d75e1fcd776ef412f4d623cc293e}\label{struct_b_n_o08x_1_1bno08x__rx__packet__t_ab422d75e1fcd776ef412f4d623cc293e} -\index{BNO08x::bno08x\_rx\_packet\_t@{BNO08x::bno08x\_rx\_packet\_t}!body@{body}} -\index{body@{body}!BNO08x::bno08x\_rx\_packet\_t@{BNO08x::bno08x\_rx\_packet\_t}} -\doxysubsubsection{\texorpdfstring{body}{body}} -{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::bno08x\+\_\+rx\+\_\+packet\+\_\+t\+::body\mbox{[}300\mbox{]}} - -\Hypertarget{struct_b_n_o08x_1_1bno08x__rx__packet__t_a667d671ccb272bd375008716e26e0b5b}\label{struct_b_n_o08x_1_1bno08x__rx__packet__t_a667d671ccb272bd375008716e26e0b5b} -\index{BNO08x::bno08x\_rx\_packet\_t@{BNO08x::bno08x\_rx\_packet\_t}!header@{header}} -\index{header@{header}!BNO08x::bno08x\_rx\_packet\_t@{BNO08x::bno08x\_rx\_packet\_t}} -\doxysubsubsection{\texorpdfstring{header}{header}} -{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::bno08x\+\_\+rx\+\_\+packet\+\_\+t\+::header\mbox{[}4\mbox{]}} - - - -Header of SHTP packet. - -\Hypertarget{struct_b_n_o08x_1_1bno08x__rx__packet__t_a645adb6ba8fb2afbb99ec58fe678e205}\label{struct_b_n_o08x_1_1bno08x__rx__packet__t_a645adb6ba8fb2afbb99ec58fe678e205} -\index{BNO08x::bno08x\_rx\_packet\_t@{BNO08x::bno08x\_rx\_packet\_t}!length@{length}} -\index{length@{length}!BNO08x::bno08x\_rx\_packet\_t@{BNO08x::bno08x\_rx\_packet\_t}} -\doxysubsubsection{\texorpdfstring{length}{length}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::bno08x\+\_\+rx\+\_\+packet\+\_\+t\+::length} - - - -Body of SHTP packet. - -Packet length in bytes. - -The documentation for this struct was generated from the following file\+:\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_b_n_o08x_8hpp}{BNO08x.\+hpp}}\end{DoxyCompactItemize} diff --git a/documentation/latex/struct_b_n_o08x_1_1bno08x__tx__packet__t.tex b/documentation/latex/struct_b_n_o08x_1_1bno08x__tx__packet__t.tex deleted file mode 100644 index dc206e8..0000000 --- a/documentation/latex/struct_b_n_o08x_1_1bno08x__tx__packet__t.tex +++ /dev/null @@ -1,45 +0,0 @@ -\doxysection{BNO08x\+::bno08x\+\_\+tx\+\_\+packet\+\_\+t Struct Reference} -\hypertarget{struct_b_n_o08x_1_1bno08x__tx__packet__t}{}\label{struct_b_n_o08x_1_1bno08x__tx__packet__t}\index{BNO08x::bno08x\_tx\_packet\_t@{BNO08x::bno08x\_tx\_packet\_t}} - - -Holds data that is sent over spi. - - -\doxysubsubsection*{Public Attributes} -\begin{DoxyCompactItemize} -\item -uint8\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__tx__packet__t_a4478c6cd9e87907eacc56dd06ad4a69d}{body}} \mbox{[}50\mbox{]} -\begin{DoxyCompactList}\small\item\em Body of SHTP the packet (header + body) \end{DoxyCompactList}\item -uint16\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_1_1bno08x__tx__packet__t_a73180537ea7605340c5e6b2132e2cbf5}{length}} -\begin{DoxyCompactList}\small\item\em Packet length in bytes. \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -Holds data that is sent over spi. - -\doxysubsection{Member Data Documentation} -\Hypertarget{struct_b_n_o08x_1_1bno08x__tx__packet__t_a4478c6cd9e87907eacc56dd06ad4a69d}\label{struct_b_n_o08x_1_1bno08x__tx__packet__t_a4478c6cd9e87907eacc56dd06ad4a69d} -\index{BNO08x::bno08x\_tx\_packet\_t@{BNO08x::bno08x\_tx\_packet\_t}!body@{body}} -\index{body@{body}!BNO08x::bno08x\_tx\_packet\_t@{BNO08x::bno08x\_tx\_packet\_t}} -\doxysubsubsection{\texorpdfstring{body}{body}} -{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::bno08x\+\_\+tx\+\_\+packet\+\_\+t\+::body\mbox{[}50\mbox{]}} - - - -Body of SHTP the packet (header + body) - -\Hypertarget{struct_b_n_o08x_1_1bno08x__tx__packet__t_a73180537ea7605340c5e6b2132e2cbf5}\label{struct_b_n_o08x_1_1bno08x__tx__packet__t_a73180537ea7605340c5e6b2132e2cbf5} -\index{BNO08x::bno08x\_tx\_packet\_t@{BNO08x::bno08x\_tx\_packet\_t}!length@{length}} -\index{length@{length}!BNO08x::bno08x\_tx\_packet\_t@{BNO08x::bno08x\_tx\_packet\_t}} -\doxysubsubsection{\texorpdfstring{length}{length}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::bno08x\+\_\+tx\+\_\+packet\+\_\+t\+::length} - - - -Packet length in bytes. - - - -The documentation for this struct was generated from the following file\+:\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_b_n_o08x_8hpp}{BNO08x.\+hpp}}\end{DoxyCompactItemize} diff --git a/documentation/latex/struct_b_n_o08x_test_helper_1_1imu__report__data__t.tex b/documentation/latex/struct_b_n_o08x_test_helper_1_1imu__report__data__t.tex deleted file mode 100644 index 67eccb0..0000000 --- a/documentation/latex/struct_b_n_o08x_test_helper_1_1imu__report__data__t.tex +++ /dev/null @@ -1,353 +0,0 @@ -\doxysection{BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t Struct Reference} -\hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t}{}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t}\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} - - -IMU configuration settings passed into constructor. - - - - -{\ttfamily \#include $<$BNO08x\+Test\+Helper.\+hpp$>$} - -\doxysubsubsection*{Public Attributes} -\begin{DoxyCompactItemize} -\item -uint32\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae5e8705ad014ed3f70e5de527cb2cb66}{time\+\_\+stamp}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8d2c3cd33943cb1b4fd0e800f822607e}{quat\+\_\+I}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a20a09d197d5128aae64b7449df576c27}{quat\+\_\+J}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3c74d4c93fc4390f52b75e6ff2bea95b}{quat\+\_\+K}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a80525c4943154f825a62539b10337976}{quat\+\_\+real}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae0a8fef0227dd4304d08466c43d901a5}{quat\+\_\+radian\+\_\+accuracy}} -\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_aac84ad10b65403ae1ee21dab5cdc77db}{quat\+\_\+accuracy}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a077a94b4de0b5c280d69611325208cf7}{integrated\+\_\+gyro\+\_\+vel\+\_\+x}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af4b75b320bc390c90656905711f1c791}{integrated\+\_\+gyro\+\_\+vel\+\_\+y}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a1aa67da9c3c6449dfce361a528c418d3}{integrated\+\_\+gyro\+\_\+vel\+\_\+z}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5c01b349cc9e4e45c78c576882d633fd}{accel\+\_\+x}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a7e594d0a1e86fb575f72c6f330c8983c}{accel\+\_\+y}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af134cb789c29120033d81916e0c100d4}{accel\+\_\+z}} -\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac5d393de0f15176ba81bc63a80b49ca3}{accel\+\_\+accuracy}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3a62ed280657cd409d723e64f0c313b5}{lin\+\_\+accel\+\_\+x}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a553942aa784c35c833543ecc9a05f606}{lin\+\_\+accel\+\_\+y}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5bf43fc0daf3a86954924e066cad3a9b}{lin\+\_\+accel\+\_\+z}} -\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a48a249994c27f59ca4167b56bdda311a}{lin\+\_\+accel\+\_\+accuracy}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ad2c17ea111250ebc1a4a763dae3c072a}{grav\+\_\+x}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a19fc4af8a26c10a027cbd859d67dba4a}{grav\+\_\+y}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af1887bdfef4fc2c683fe2134cb5cfb50}{grav\+\_\+z}} -\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a735d099f3dd0ead4b8d986fd139af43d}{grav\+\_\+accuracy}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a89b427579a281440ab94a340c0ec8443}{calib\+\_\+gyro\+\_\+vel\+\_\+x}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af9e11fd749123f5723b2e281c8d2fd16}{calib\+\_\+gyro\+\_\+vel\+\_\+y}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a769ddae74a6c89a2d319c28f95ed6479}{calib\+\_\+gyro\+\_\+vel\+\_\+z}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a292b1c36fed6a9c9742edf730299c4f4}{uncalib\+\_\+gyro\+\_\+vel\+\_\+x}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_adfd6bf2e2264cf25bd02814446600ab4}{uncalib\+\_\+gyro\+\_\+vel\+\_\+y}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ab39fd6f409288bb35fb1542ff4b9cbe4}{uncalib\+\_\+gyro\+\_\+vel\+\_\+z}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac70a65027c3e740eca2b1f172b7cefa3}{uncalib\+\_\+gyro\+\_\+drift\+\_\+x}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a29d5ae3e0ed3463cb9297f9cdc0e8472}{uncalib\+\_\+gyro\+\_\+drift\+\_\+y}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a27b52e2d96cb948c4257de4553053f72}{uncalib\+\_\+gyro\+\_\+drift\+\_\+z}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0e72f6dde1411e4aa1c616cedcc556c1}{magf\+\_\+x}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8738f60a2b9bd49d2b8dd0487db7ac97}{magf\+\_\+y}} -\item -float \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a55187ebe06fa77def93681bcdf62595c}{magf\+\_\+z}} -\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0c962609a3bf7927204542521e9c5113}{magf\+\_\+accuracy}} -\item -uint16\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a94befe7132d3a6a6ce2a7890e96ec091}{raw\+\_\+mems\+\_\+gyro\+\_\+x}} -\item -uint16\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a7e9cd7e43d70932c5f84e3cfadf8bb47}{raw\+\_\+mems\+\_\+gyro\+\_\+y}} -\item -uint16\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a9df84179bd44a7febfa1058afe3dad6c}{raw\+\_\+mems\+\_\+gyro\+\_\+z}} -\item -uint16\+\_\+t \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae8435a931eac7f4376a94acfcbf6a784}{step\+\_\+count}} -\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}{BNO08x\+Stability}} \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a86473c2bd8cbe2c76276393ee20d568b}{stability\+\_\+classifier}} -\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}{BNO08x\+Activity}} \mbox{\hyperlink{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0455033deba9570f248e8059cf6a3ce1}{activity\+\_\+classifier}} -\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -IMU configuration settings passed into constructor. - -\doxysubsection{Member Data Documentation} -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac5d393de0f15176ba81bc63a80b49ca3}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac5d393de0f15176ba81bc63a80b49ca3} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!accel\_accuracy@{accel\_accuracy}} -\index{accel\_accuracy@{accel\_accuracy}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{accel\_accuracy}{accel\_accuracy}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::accel\+\_\+accuracy} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5c01b349cc9e4e45c78c576882d633fd}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5c01b349cc9e4e45c78c576882d633fd} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!accel\_x@{accel\_x}} -\index{accel\_x@{accel\_x}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{accel\_x}{accel\_x}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::accel\+\_\+x} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a7e594d0a1e86fb575f72c6f330c8983c}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a7e594d0a1e86fb575f72c6f330c8983c} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!accel\_y@{accel\_y}} -\index{accel\_y@{accel\_y}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{accel\_y}{accel\_y}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::accel\+\_\+y} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af134cb789c29120033d81916e0c100d4}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af134cb789c29120033d81916e0c100d4} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!accel\_z@{accel\_z}} -\index{accel\_z@{accel\_z}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{accel\_z}{accel\_z}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::accel\+\_\+z} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0455033deba9570f248e8059cf6a3ce1}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0455033deba9570f248e8059cf6a3ce1} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!activity\_classifier@{activity\_classifier}} -\index{activity\_classifier@{activity\_classifier}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{activity\_classifier}{activity\_classifier}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_abcc5d57e21ea6ed79e792deafcb62187}{BNO08x\+Activity}} BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::activity\+\_\+classifier} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a89b427579a281440ab94a340c0ec8443}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a89b427579a281440ab94a340c0ec8443} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!calib\_gyro\_vel\_x@{calib\_gyro\_vel\_x}} -\index{calib\_gyro\_vel\_x@{calib\_gyro\_vel\_x}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{calib\_gyro\_vel\_x}{calib\_gyro\_vel\_x}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::calib\+\_\+gyro\+\_\+vel\+\_\+x} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af9e11fd749123f5723b2e281c8d2fd16}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af9e11fd749123f5723b2e281c8d2fd16} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!calib\_gyro\_vel\_y@{calib\_gyro\_vel\_y}} -\index{calib\_gyro\_vel\_y@{calib\_gyro\_vel\_y}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{calib\_gyro\_vel\_y}{calib\_gyro\_vel\_y}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::calib\+\_\+gyro\+\_\+vel\+\_\+y} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a769ddae74a6c89a2d319c28f95ed6479}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a769ddae74a6c89a2d319c28f95ed6479} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!calib\_gyro\_vel\_z@{calib\_gyro\_vel\_z}} -\index{calib\_gyro\_vel\_z@{calib\_gyro\_vel\_z}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{calib\_gyro\_vel\_z}{calib\_gyro\_vel\_z}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::calib\+\_\+gyro\+\_\+vel\+\_\+z} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a735d099f3dd0ead4b8d986fd139af43d}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a735d099f3dd0ead4b8d986fd139af43d} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!grav\_accuracy@{grav\_accuracy}} -\index{grav\_accuracy@{grav\_accuracy}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{grav\_accuracy}{grav\_accuracy}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::grav\+\_\+accuracy} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ad2c17ea111250ebc1a4a763dae3c072a}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ad2c17ea111250ebc1a4a763dae3c072a} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!grav\_x@{grav\_x}} -\index{grav\_x@{grav\_x}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{grav\_x}{grav\_x}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::grav\+\_\+x} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a19fc4af8a26c10a027cbd859d67dba4a}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a19fc4af8a26c10a027cbd859d67dba4a} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!grav\_y@{grav\_y}} -\index{grav\_y@{grav\_y}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{grav\_y}{grav\_y}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::grav\+\_\+y} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af1887bdfef4fc2c683fe2134cb5cfb50}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af1887bdfef4fc2c683fe2134cb5cfb50} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!grav\_z@{grav\_z}} -\index{grav\_z@{grav\_z}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{grav\_z}{grav\_z}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::grav\+\_\+z} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a077a94b4de0b5c280d69611325208cf7}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a077a94b4de0b5c280d69611325208cf7} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!integrated\_gyro\_vel\_x@{integrated\_gyro\_vel\_x}} -\index{integrated\_gyro\_vel\_x@{integrated\_gyro\_vel\_x}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{integrated\_gyro\_vel\_x}{integrated\_gyro\_vel\_x}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::integrated\+\_\+gyro\+\_\+vel\+\_\+x} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af4b75b320bc390c90656905711f1c791}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_af4b75b320bc390c90656905711f1c791} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!integrated\_gyro\_vel\_y@{integrated\_gyro\_vel\_y}} -\index{integrated\_gyro\_vel\_y@{integrated\_gyro\_vel\_y}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{integrated\_gyro\_vel\_y}{integrated\_gyro\_vel\_y}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::integrated\+\_\+gyro\+\_\+vel\+\_\+y} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a1aa67da9c3c6449dfce361a528c418d3}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a1aa67da9c3c6449dfce361a528c418d3} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!integrated\_gyro\_vel\_z@{integrated\_gyro\_vel\_z}} -\index{integrated\_gyro\_vel\_z@{integrated\_gyro\_vel\_z}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{integrated\_gyro\_vel\_z}{integrated\_gyro\_vel\_z}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::integrated\+\_\+gyro\+\_\+vel\+\_\+z} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a48a249994c27f59ca4167b56bdda311a}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a48a249994c27f59ca4167b56bdda311a} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!lin\_accel\_accuracy@{lin\_accel\_accuracy}} -\index{lin\_accel\_accuracy@{lin\_accel\_accuracy}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{lin\_accel\_accuracy}{lin\_accel\_accuracy}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::lin\+\_\+accel\+\_\+accuracy} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3a62ed280657cd409d723e64f0c313b5}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3a62ed280657cd409d723e64f0c313b5} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!lin\_accel\_x@{lin\_accel\_x}} -\index{lin\_accel\_x@{lin\_accel\_x}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{lin\_accel\_x}{lin\_accel\_x}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::lin\+\_\+accel\+\_\+x} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a553942aa784c35c833543ecc9a05f606}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a553942aa784c35c833543ecc9a05f606} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!lin\_accel\_y@{lin\_accel\_y}} -\index{lin\_accel\_y@{lin\_accel\_y}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{lin\_accel\_y}{lin\_accel\_y}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::lin\+\_\+accel\+\_\+y} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5bf43fc0daf3a86954924e066cad3a9b}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a5bf43fc0daf3a86954924e066cad3a9b} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!lin\_accel\_z@{lin\_accel\_z}} -\index{lin\_accel\_z@{lin\_accel\_z}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{lin\_accel\_z}{lin\_accel\_z}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::lin\+\_\+accel\+\_\+z} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0c962609a3bf7927204542521e9c5113}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0c962609a3bf7927204542521e9c5113} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!magf\_accuracy@{magf\_accuracy}} -\index{magf\_accuracy@{magf\_accuracy}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{magf\_accuracy}{magf\_accuracy}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::magf\+\_\+accuracy} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0e72f6dde1411e4aa1c616cedcc556c1}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a0e72f6dde1411e4aa1c616cedcc556c1} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!magf\_x@{magf\_x}} -\index{magf\_x@{magf\_x}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{magf\_x}{magf\_x}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::magf\+\_\+x} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8738f60a2b9bd49d2b8dd0487db7ac97}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8738f60a2b9bd49d2b8dd0487db7ac97} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!magf\_y@{magf\_y}} -\index{magf\_y@{magf\_y}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{magf\_y}{magf\_y}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::magf\+\_\+y} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a55187ebe06fa77def93681bcdf62595c}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a55187ebe06fa77def93681bcdf62595c} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!magf\_z@{magf\_z}} -\index{magf\_z@{magf\_z}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{magf\_z}{magf\_z}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::magf\+\_\+z} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_aac84ad10b65403ae1ee21dab5cdc77db}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_aac84ad10b65403ae1ee21dab5cdc77db} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!quat\_accuracy@{quat\_accuracy}} -\index{quat\_accuracy@{quat\_accuracy}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{quat\_accuracy}{quat\_accuracy}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_aed7bab8e55be415938e078ebe72562a0}{BNO08x\+Accuracy}} BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::quat\+\_\+accuracy} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8d2c3cd33943cb1b4fd0e800f822607e}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a8d2c3cd33943cb1b4fd0e800f822607e} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!quat\_I@{quat\_I}} -\index{quat\_I@{quat\_I}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{quat\_I}{quat\_I}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::quat\+\_\+I} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a20a09d197d5128aae64b7449df576c27}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a20a09d197d5128aae64b7449df576c27} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!quat\_J@{quat\_J}} -\index{quat\_J@{quat\_J}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{quat\_J}{quat\_J}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::quat\+\_\+J} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3c74d4c93fc4390f52b75e6ff2bea95b}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a3c74d4c93fc4390f52b75e6ff2bea95b} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!quat\_K@{quat\_K}} -\index{quat\_K@{quat\_K}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{quat\_K}{quat\_K}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::quat\+\_\+K} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae0a8fef0227dd4304d08466c43d901a5}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae0a8fef0227dd4304d08466c43d901a5} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!quat\_radian\_accuracy@{quat\_radian\_accuracy}} -\index{quat\_radian\_accuracy@{quat\_radian\_accuracy}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{quat\_radian\_accuracy}{quat\_radian\_accuracy}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::quat\+\_\+radian\+\_\+accuracy} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a80525c4943154f825a62539b10337976}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a80525c4943154f825a62539b10337976} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!quat\_real@{quat\_real}} -\index{quat\_real@{quat\_real}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{quat\_real}{quat\_real}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::quat\+\_\+real} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a94befe7132d3a6a6ce2a7890e96ec091}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a94befe7132d3a6a6ce2a7890e96ec091} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!raw\_mems\_gyro\_x@{raw\_mems\_gyro\_x}} -\index{raw\_mems\_gyro\_x@{raw\_mems\_gyro\_x}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{raw\_mems\_gyro\_x}{raw\_mems\_gyro\_x}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::raw\+\_\+mems\+\_\+gyro\+\_\+x} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a7e9cd7e43d70932c5f84e3cfadf8bb47}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a7e9cd7e43d70932c5f84e3cfadf8bb47} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!raw\_mems\_gyro\_y@{raw\_mems\_gyro\_y}} -\index{raw\_mems\_gyro\_y@{raw\_mems\_gyro\_y}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{raw\_mems\_gyro\_y}{raw\_mems\_gyro\_y}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::raw\+\_\+mems\+\_\+gyro\+\_\+y} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a9df84179bd44a7febfa1058afe3dad6c}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a9df84179bd44a7febfa1058afe3dad6c} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!raw\_mems\_gyro\_z@{raw\_mems\_gyro\_z}} -\index{raw\_mems\_gyro\_z@{raw\_mems\_gyro\_z}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{raw\_mems\_gyro\_z}{raw\_mems\_gyro\_z}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::raw\+\_\+mems\+\_\+gyro\+\_\+z} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a86473c2bd8cbe2c76276393ee20d568b}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a86473c2bd8cbe2c76276393ee20d568b} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!stability\_classifier@{stability\_classifier}} -\index{stability\_classifier@{stability\_classifier}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{stability\_classifier}{stability\_classifier}} -{\footnotesize\ttfamily \mbox{\hyperlink{_b_n_o08x__global__types_8hpp_a498b35f9e00b24e51f8f60b029751ab5}{BNO08x\+Stability}} BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::stability\+\_\+classifier} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae8435a931eac7f4376a94acfcbf6a784}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae8435a931eac7f4376a94acfcbf6a784} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!step\_count@{step\_count}} -\index{step\_count@{step\_count}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{step\_count}{step\_count}} -{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::step\+\_\+count} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae5e8705ad014ed3f70e5de527cb2cb66}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ae5e8705ad014ed3f70e5de527cb2cb66} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!time\_stamp@{time\_stamp}} -\index{time\_stamp@{time\_stamp}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{time\_stamp}{time\_stamp}} -{\footnotesize\ttfamily uint32\+\_\+t BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::time\+\_\+stamp} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac70a65027c3e740eca2b1f172b7cefa3}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ac70a65027c3e740eca2b1f172b7cefa3} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!uncalib\_gyro\_drift\_x@{uncalib\_gyro\_drift\_x}} -\index{uncalib\_gyro\_drift\_x@{uncalib\_gyro\_drift\_x}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{uncalib\_gyro\_drift\_x}{uncalib\_gyro\_drift\_x}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::uncalib\+\_\+gyro\+\_\+drift\+\_\+x} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a29d5ae3e0ed3463cb9297f9cdc0e8472}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a29d5ae3e0ed3463cb9297f9cdc0e8472} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!uncalib\_gyro\_drift\_y@{uncalib\_gyro\_drift\_y}} -\index{uncalib\_gyro\_drift\_y@{uncalib\_gyro\_drift\_y}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{uncalib\_gyro\_drift\_y}{uncalib\_gyro\_drift\_y}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::uncalib\+\_\+gyro\+\_\+drift\+\_\+y} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a27b52e2d96cb948c4257de4553053f72}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a27b52e2d96cb948c4257de4553053f72} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!uncalib\_gyro\_drift\_z@{uncalib\_gyro\_drift\_z}} -\index{uncalib\_gyro\_drift\_z@{uncalib\_gyro\_drift\_z}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{uncalib\_gyro\_drift\_z}{uncalib\_gyro\_drift\_z}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::uncalib\+\_\+gyro\+\_\+drift\+\_\+z} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a292b1c36fed6a9c9742edf730299c4f4}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_a292b1c36fed6a9c9742edf730299c4f4} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!uncalib\_gyro\_vel\_x@{uncalib\_gyro\_vel\_x}} -\index{uncalib\_gyro\_vel\_x@{uncalib\_gyro\_vel\_x}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{uncalib\_gyro\_vel\_x}{uncalib\_gyro\_vel\_x}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::uncalib\+\_\+gyro\+\_\+vel\+\_\+x} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_adfd6bf2e2264cf25bd02814446600ab4}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_adfd6bf2e2264cf25bd02814446600ab4} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!uncalib\_gyro\_vel\_y@{uncalib\_gyro\_vel\_y}} -\index{uncalib\_gyro\_vel\_y@{uncalib\_gyro\_vel\_y}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{uncalib\_gyro\_vel\_y}{uncalib\_gyro\_vel\_y}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::uncalib\+\_\+gyro\+\_\+vel\+\_\+y} - -\Hypertarget{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ab39fd6f409288bb35fb1542ff4b9cbe4}\label{struct_b_n_o08x_test_helper_1_1imu__report__data__t_ab39fd6f409288bb35fb1542ff4b9cbe4} -\index{BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}!uncalib\_gyro\_vel\_z@{uncalib\_gyro\_vel\_z}} -\index{uncalib\_gyro\_vel\_z@{uncalib\_gyro\_vel\_z}!BNO08xTestHelper::imu\_report\_data\_t@{BNO08xTestHelper::imu\_report\_data\_t}} -\doxysubsubsection{\texorpdfstring{uncalib\_gyro\_vel\_z}{uncalib\_gyro\_vel\_z}} -{\footnotesize\ttfamily float BNO08x\+Test\+Helper\+::imu\+\_\+report\+\_\+data\+\_\+t\+::uncalib\+\_\+gyro\+\_\+vel\+\_\+z} - - - -The documentation for this struct was generated from the following file\+:\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_b_n_o08x_test_helper_8hpp}{BNO08x\+Test\+Helper.\+hpp}}\end{DoxyCompactItemize} diff --git a/documentation/latex/structbno08x__config__t.tex b/documentation/latex/structbno08x__config__t.tex deleted file mode 100644 index c820f6a..0000000 --- a/documentation/latex/structbno08x__config__t.tex +++ /dev/null @@ -1,171 +0,0 @@ -\doxysection{bno08x\+\_\+config\+\_\+t Struct Reference} -\hypertarget{structbno08x__config__t}{}\label{structbno08x__config__t}\index{bno08x\_config\_t@{bno08x\_config\_t}} - - -IMU configuration settings passed into constructor. - - - - -{\ttfamily \#include $<$BNO08x\+\_\+global\+\_\+types.\+hpp$>$} - -\doxysubsubsection*{Public Member Functions} -\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{structbno08x__config__t_a68e051212415a62e64c23678e7b40552}{bno08x\+\_\+config\+\_\+t}} (bool \mbox{\hyperlink{structbno08x__config__t_a0f629aaef6756aa80fec96b34476c627}{install\+\_\+isr\+\_\+service}}=true) -\begin{DoxyCompactList}\small\item\em Default IMU configuration settings constructor. To modify default GPIO pins, run "{}idf.\+py menuconfig"{} esp32\+\_\+\+BNO08x-\/\texorpdfstring{$>$}{>}GPIO Configuration. Alternatively, edit the default values in "{}\+Kconfig.\+projbuild"{}. \end{DoxyCompactList}\item -\mbox{\hyperlink{structbno08x__config__t_a3a4ef8ef437403592278110a73cafe70}{bno08x\+\_\+config\+\_\+t}} (spi\+\_\+host\+\_\+device\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a020d2343750bb7debc2a108ae038c9ec}{spi\+\_\+peripheral}}, gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a79023fd80039e41a22b7f73ccd5fc861}{io\+\_\+mosi}}, gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a9468180a773892977db39cc5ed9368e3}{io\+\_\+miso}}, gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a639685b91ae3198909d722316495246a}{io\+\_\+sclk}}, gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_ab1b5351b63da0c172c942463d0dc2505}{io\+\_\+cs}}, gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a3cfe965659cfbc6b0c5269bd0211975f}{io\+\_\+int}}, gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a62745c761219139f66ecd173b51577fc}{io\+\_\+rst}}, gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a90ad7f316dc443874d19dc7e723a0ce0}{io\+\_\+wake}}, uint32\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a231614c3b20888360def2ce9db83f52a}{sclk\+\_\+speed}}, bool \mbox{\hyperlink{structbno08x__config__t_a0f629aaef6756aa80fec96b34476c627}{install\+\_\+isr\+\_\+service}}=true) -\begin{DoxyCompactList}\small\item\em Overloaded IMU configuration settings constructor for custom pin settings. \end{DoxyCompactList}\end{DoxyCompactItemize} -\doxysubsubsection*{Public Attributes} -\begin{DoxyCompactItemize} -\item -spi\+\_\+host\+\_\+device\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a020d2343750bb7debc2a108ae038c9ec}{spi\+\_\+peripheral}} -\begin{DoxyCompactList}\small\item\em SPI peripheral to be used. \end{DoxyCompactList}\item -gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a79023fd80039e41a22b7f73ccd5fc861}{io\+\_\+mosi}} -\begin{DoxyCompactList}\small\item\em MOSI GPIO pin (connects to \doxylink{class_b_n_o08x}{BNO08x} DI pin) \end{DoxyCompactList}\item -gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a9468180a773892977db39cc5ed9368e3}{io\+\_\+miso}} -\begin{DoxyCompactList}\small\item\em MISO GPIO pin (connects to \doxylink{class_b_n_o08x}{BNO08x} SDA pin) \end{DoxyCompactList}\item -gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a639685b91ae3198909d722316495246a}{io\+\_\+sclk}} -\begin{DoxyCompactList}\small\item\em SCLK pin (connects to \doxylink{class_b_n_o08x}{BNO08x} SCL pin) \end{DoxyCompactList}\item -gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_ab1b5351b63da0c172c942463d0dc2505}{io\+\_\+cs}} -\item -gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a3cfe965659cfbc6b0c5269bd0211975f}{io\+\_\+int}} -\begin{DoxyCompactList}\small\item\em Chip select pin (connects to \doxylink{class_b_n_o08x}{BNO08x} CS pin) \end{DoxyCompactList}\item -gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a62745c761219139f66ecd173b51577fc}{io\+\_\+rst}} -\begin{DoxyCompactList}\small\item\em Host interrupt pin (connects to \doxylink{class_b_n_o08x}{BNO08x} INT pin) \end{DoxyCompactList}\item -gpio\+\_\+num\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a90ad7f316dc443874d19dc7e723a0ce0}{io\+\_\+wake}} -\begin{DoxyCompactList}\small\item\em Reset pin (connects to \doxylink{class_b_n_o08x}{BNO08x} RST pin) \end{DoxyCompactList}\item -uint32\+\_\+t \mbox{\hyperlink{structbno08x__config__t_a231614c3b20888360def2ce9db83f52a}{sclk\+\_\+speed}} -\begin{DoxyCompactList}\small\item\em Desired SPI SCLK speed in Hz (max 3MHz) \end{DoxyCompactList}\item -bool \mbox{\hyperlink{structbno08x__config__t_a0f629aaef6756aa80fec96b34476c627}{install\+\_\+isr\+\_\+service}} -\begin{DoxyCompactList}\small\item\em Indicates whether the ISR service for the HINT should be installed at IMU initialization, (if gpio\+\_\+install\+\_\+isr\+\_\+service() is called before initialize() set this to false) \end{DoxyCompactList}\end{DoxyCompactItemize} - - -\doxysubsection{Detailed Description} -IMU configuration settings passed into constructor. - -\doxysubsection{Constructor \& Destructor Documentation} -\Hypertarget{structbno08x__config__t_a68e051212415a62e64c23678e7b40552}\label{structbno08x__config__t_a68e051212415a62e64c23678e7b40552} -\index{bno08x\_config\_t@{bno08x\_config\_t}!bno08x\_config\_t@{bno08x\_config\_t}} -\index{bno08x\_config\_t@{bno08x\_config\_t}!bno08x\_config\_t@{bno08x\_config\_t}} -\doxysubsubsection{\texorpdfstring{bno08x\_config\_t()}{bno08x\_config\_t()}\hspace{0.1cm}{\footnotesize\ttfamily [1/2]}} -{\footnotesize\ttfamily bno08x\+\_\+config\+\_\+t\+::bno08x\+\_\+config\+\_\+t (\begin{DoxyParamCaption}\item[{bool}]{install\+\_\+isr\+\_\+service = {\ttfamily true} }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}} - - - -Default IMU configuration settings constructor. To modify default GPIO pins, run "{}idf.\+py menuconfig"{} esp32\+\_\+\+BNO08x-\/\texorpdfstring{$>$}{>}GPIO Configuration. Alternatively, edit the default values in "{}\+Kconfig.\+projbuild"{}. - -\Hypertarget{structbno08x__config__t_a3a4ef8ef437403592278110a73cafe70}\label{structbno08x__config__t_a3a4ef8ef437403592278110a73cafe70} -\index{bno08x\_config\_t@{bno08x\_config\_t}!bno08x\_config\_t@{bno08x\_config\_t}} -\index{bno08x\_config\_t@{bno08x\_config\_t}!bno08x\_config\_t@{bno08x\_config\_t}} -\doxysubsubsection{\texorpdfstring{bno08x\_config\_t()}{bno08x\_config\_t()}\hspace{0.1cm}{\footnotesize\ttfamily [2/2]}} -{\footnotesize\ttfamily bno08x\+\_\+config\+\_\+t\+::bno08x\+\_\+config\+\_\+t (\begin{DoxyParamCaption}\item[{spi\+\_\+host\+\_\+device\+\_\+t}]{spi\+\_\+peripheral, }\item[{gpio\+\_\+num\+\_\+t}]{io\+\_\+mosi, }\item[{gpio\+\_\+num\+\_\+t}]{io\+\_\+miso, }\item[{gpio\+\_\+num\+\_\+t}]{io\+\_\+sclk, }\item[{gpio\+\_\+num\+\_\+t}]{io\+\_\+cs, }\item[{gpio\+\_\+num\+\_\+t}]{io\+\_\+int, }\item[{gpio\+\_\+num\+\_\+t}]{io\+\_\+rst, }\item[{gpio\+\_\+num\+\_\+t}]{io\+\_\+wake, }\item[{uint32\+\_\+t}]{sclk\+\_\+speed, }\item[{bool}]{install\+\_\+isr\+\_\+service = {\ttfamily true} }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [inline]}} - - - -Overloaded IMU configuration settings constructor for custom pin settings. - - - -\doxysubsection{Member Data Documentation} -\Hypertarget{structbno08x__config__t_a0f629aaef6756aa80fec96b34476c627}\label{structbno08x__config__t_a0f629aaef6756aa80fec96b34476c627} -\index{bno08x\_config\_t@{bno08x\_config\_t}!install\_isr\_service@{install\_isr\_service}} -\index{install\_isr\_service@{install\_isr\_service}!bno08x\_config\_t@{bno08x\_config\_t}} -\doxysubsubsection{\texorpdfstring{install\_isr\_service}{install\_isr\_service}} -{\footnotesize\ttfamily bool bno08x\+\_\+config\+\_\+t\+::install\+\_\+isr\+\_\+service} - - - -Indicates whether the ISR service for the HINT should be installed at IMU initialization, (if gpio\+\_\+install\+\_\+isr\+\_\+service() is called before initialize() set this to false) - -\Hypertarget{structbno08x__config__t_ab1b5351b63da0c172c942463d0dc2505}\label{structbno08x__config__t_ab1b5351b63da0c172c942463d0dc2505} -\index{bno08x\_config\_t@{bno08x\_config\_t}!io\_cs@{io\_cs}} -\index{io\_cs@{io\_cs}!bno08x\_config\_t@{bno08x\_config\_t}} -\doxysubsubsection{\texorpdfstring{io\_cs}{io\_cs}} -{\footnotesize\ttfamily gpio\+\_\+num\+\_\+t bno08x\+\_\+config\+\_\+t\+::io\+\_\+cs} - -\Hypertarget{structbno08x__config__t_a3cfe965659cfbc6b0c5269bd0211975f}\label{structbno08x__config__t_a3cfe965659cfbc6b0c5269bd0211975f} -\index{bno08x\_config\_t@{bno08x\_config\_t}!io\_int@{io\_int}} -\index{io\_int@{io\_int}!bno08x\_config\_t@{bno08x\_config\_t}} -\doxysubsubsection{\texorpdfstring{io\_int}{io\_int}} -{\footnotesize\ttfamily gpio\+\_\+num\+\_\+t bno08x\+\_\+config\+\_\+t\+::io\+\_\+int} - - - -Chip select pin (connects to \doxylink{class_b_n_o08x}{BNO08x} CS pin) - -\Hypertarget{structbno08x__config__t_a9468180a773892977db39cc5ed9368e3}\label{structbno08x__config__t_a9468180a773892977db39cc5ed9368e3} -\index{bno08x\_config\_t@{bno08x\_config\_t}!io\_miso@{io\_miso}} -\index{io\_miso@{io\_miso}!bno08x\_config\_t@{bno08x\_config\_t}} -\doxysubsubsection{\texorpdfstring{io\_miso}{io\_miso}} -{\footnotesize\ttfamily gpio\+\_\+num\+\_\+t bno08x\+\_\+config\+\_\+t\+::io\+\_\+miso} - - - -MISO GPIO pin (connects to \doxylink{class_b_n_o08x}{BNO08x} SDA pin) - -\Hypertarget{structbno08x__config__t_a79023fd80039e41a22b7f73ccd5fc861}\label{structbno08x__config__t_a79023fd80039e41a22b7f73ccd5fc861} -\index{bno08x\_config\_t@{bno08x\_config\_t}!io\_mosi@{io\_mosi}} -\index{io\_mosi@{io\_mosi}!bno08x\_config\_t@{bno08x\_config\_t}} -\doxysubsubsection{\texorpdfstring{io\_mosi}{io\_mosi}} -{\footnotesize\ttfamily gpio\+\_\+num\+\_\+t bno08x\+\_\+config\+\_\+t\+::io\+\_\+mosi} - - - -MOSI GPIO pin (connects to \doxylink{class_b_n_o08x}{BNO08x} DI pin) - -\Hypertarget{structbno08x__config__t_a62745c761219139f66ecd173b51577fc}\label{structbno08x__config__t_a62745c761219139f66ecd173b51577fc} -\index{bno08x\_config\_t@{bno08x\_config\_t}!io\_rst@{io\_rst}} -\index{io\_rst@{io\_rst}!bno08x\_config\_t@{bno08x\_config\_t}} -\doxysubsubsection{\texorpdfstring{io\_rst}{io\_rst}} -{\footnotesize\ttfamily gpio\+\_\+num\+\_\+t bno08x\+\_\+config\+\_\+t\+::io\+\_\+rst} - - - -Host interrupt pin (connects to \doxylink{class_b_n_o08x}{BNO08x} INT pin) - -\Hypertarget{structbno08x__config__t_a639685b91ae3198909d722316495246a}\label{structbno08x__config__t_a639685b91ae3198909d722316495246a} -\index{bno08x\_config\_t@{bno08x\_config\_t}!io\_sclk@{io\_sclk}} -\index{io\_sclk@{io\_sclk}!bno08x\_config\_t@{bno08x\_config\_t}} -\doxysubsubsection{\texorpdfstring{io\_sclk}{io\_sclk}} -{\footnotesize\ttfamily gpio\+\_\+num\+\_\+t bno08x\+\_\+config\+\_\+t\+::io\+\_\+sclk} - - - -SCLK pin (connects to \doxylink{class_b_n_o08x}{BNO08x} SCL pin) - -\Hypertarget{structbno08x__config__t_a90ad7f316dc443874d19dc7e723a0ce0}\label{structbno08x__config__t_a90ad7f316dc443874d19dc7e723a0ce0} -\index{bno08x\_config\_t@{bno08x\_config\_t}!io\_wake@{io\_wake}} -\index{io\_wake@{io\_wake}!bno08x\_config\_t@{bno08x\_config\_t}} -\doxysubsubsection{\texorpdfstring{io\_wake}{io\_wake}} -{\footnotesize\ttfamily gpio\+\_\+num\+\_\+t bno08x\+\_\+config\+\_\+t\+::io\+\_\+wake} - - - -Reset pin (connects to \doxylink{class_b_n_o08x}{BNO08x} RST pin) - -Wake pin (optional, connects to \doxylink{class_b_n_o08x}{BNO08x} P0) \Hypertarget{structbno08x__config__t_a231614c3b20888360def2ce9db83f52a}\label{structbno08x__config__t_a231614c3b20888360def2ce9db83f52a} -\index{bno08x\_config\_t@{bno08x\_config\_t}!sclk\_speed@{sclk\_speed}} -\index{sclk\_speed@{sclk\_speed}!bno08x\_config\_t@{bno08x\_config\_t}} -\doxysubsubsection{\texorpdfstring{sclk\_speed}{sclk\_speed}} -{\footnotesize\ttfamily uint32\+\_\+t bno08x\+\_\+config\+\_\+t\+::sclk\+\_\+speed} - - - -Desired SPI SCLK speed in Hz (max 3MHz) - -\Hypertarget{structbno08x__config__t_a020d2343750bb7debc2a108ae038c9ec}\label{structbno08x__config__t_a020d2343750bb7debc2a108ae038c9ec} -\index{bno08x\_config\_t@{bno08x\_config\_t}!spi\_peripheral@{spi\_peripheral}} -\index{spi\_peripheral@{spi\_peripheral}!bno08x\_config\_t@{bno08x\_config\_t}} -\doxysubsubsection{\texorpdfstring{spi\_peripheral}{spi\_peripheral}} -{\footnotesize\ttfamily spi\+\_\+host\+\_\+device\+\_\+t bno08x\+\_\+config\+\_\+t\+::spi\+\_\+peripheral} - - - -SPI peripheral to be used. - - - -The documentation for this struct was generated from the following file\+:\begin{DoxyCompactItemize} -\item -\mbox{\hyperlink{_b_n_o08x__global__types_8hpp}{BNO08x\+\_\+global\+\_\+types.\+hpp}}\end{DoxyCompactItemize} diff --git a/documentation/latex/tabu_doxygen.sty b/documentation/latex/tabu_doxygen.sty deleted file mode 100644 index 3f17d1d..0000000 --- a/documentation/latex/tabu_doxygen.sty +++ /dev/null @@ -1,2557 +0,0 @@ -%% -%% This is file `tabu.sty', -%% generated with the docstrip utility. -%% -%% The original source files were: -%% -%% tabu.dtx (with options: `package') -%% -%% This is a generated file. -%% Copyright (FC) 2010-2011 - lppl -%% -%% tabu : 2011/02/26 v2.8 - tabu : Flexible LaTeX tabulars -%% -%% ********************************************************************************************** -%% \begin{tabu} { preamble } => default target: \linewidth or \linegoal -%% \begin{tabu} to { preamble } => target specified -%% \begin{tabu} spread { preamble } => target relative to the ``natural width'' -%% -%% tabu works in text and in math modes. -%% -%% X columns: automatic width adjustment + horizontal and vertical alignment -%% \begin{tabu} { X[4c] X[1c] X[-2ml] } -%% -%% Horizontal lines and / or leaders: -%% \hline\hline => double horizontal line -%% \firsthline\hline => for nested tabulars -%% \lasthline\hline => for nested tabulars -%% \tabucline[line spec]{column-column} => ``funny'' lines (dash/leader) -%% Automatic lines / leaders : -%% \everyrow{\hline\hline} -%% -%% Vertical lines and / or leaders: -%% \begin{tabu} { |[3pt red] X[4c] X[1c] X[-2ml] |[3pt blue] } -%% \begin{tabu} { |[3pt red] X[4c] X[1c] X[-2ml] |[3pt on 2pt off 4pt blue] } -%% -%% Fixed vertical spacing adjustment: -%% \extrarowheight= \extrarowdepth= -%% or: \extrarowsep= => may be prefixed by \global -%% -%% Dynamic vertical spacing adjustment: -%% \abovetabulinesep= \belowtabulinesep= -%% or: \tabulinesep= => may be prefixed by \global -%% -%% delarray.sty shortcuts: in math and text modes -%% \begin{tabu} .... \({ preamble }\) -%% -%% Algorithms reports: -%% \tracingtabu=1 \tracingtabu=2 -%% -%% ********************************************************************************************** -%% -%% This work may be distributed and/or modified under the -%% conditions of the LaTeX Project Public License, either -%% version 1.3 of this license or (at your option) any later -%% version. The latest version of this license is in -%% http://www.latex-project.org/lppl.txt -%% -%% This work consists of the main source file tabu.dtx -%% and the derived files -%% tabu.sty, tabu.pdf, tabu.ins -%% -%% tabu : Flexible LaTeX tabulars -%% lppl copyright 2010-2011 by FC -%% - -\NeedsTeXFormat{LaTeX2e}[2005/12/01] -\ProvidesPackage{tabu_doxygen}[2011/02/26 v2.8 - flexible LaTeX tabulars (FC), frozen version for doxygen] -\RequirePackage{array}[2008/09/09] -\RequirePackage{varwidth}[2009/03/30] -\AtEndOfPackage{\tabu@AtEnd \let\tabu@AtEnd \@undefined} -\let\tabu@AtEnd\@empty -\def\TMP@EnsureCode#1={% - \edef\tabu@AtEnd{\tabu@AtEnd - \catcode#1 \the\catcode#1}% - \catcode#1=% -}% \TMP@EnsureCode -\TMP@EnsureCode 33 = 12 % ! -\TMP@EnsureCode 58 = 12 % : (for siunitx) -\TMP@EnsureCode124 = 12 % | -\TMP@EnsureCode 36 = 3 % $ = math shift -\TMP@EnsureCode 38 = 4 % & = tab alignment character -\TMP@EnsureCode 32 = 10 % space -\TMP@EnsureCode 94 = 7 % ^ -\TMP@EnsureCode 95 = 8 % _ -%% Constants -------------------------------------------------------- -\newcount \c@taburow \def\thetaburow {\number\c@taburow} -\newcount \tabu@nbcols -\newcount \tabu@cnt -\newcount \tabu@Xcol -\let\tabu@start \@tempcnta -\let\tabu@stop \@tempcntb -\newcount \tabu@alloc \tabu@alloc=\m@ne -\newcount \tabu@nested -\def\tabu@alloc@{\global\advance\tabu@alloc \@ne \tabu@nested\tabu@alloc} -\newdimen \tabu@target -\newdimen \tabu@spreadtarget -\newdimen \tabu@naturalX -\newdimen \tabucolX -\let\tabu@DELTA \@tempdimc -\let\tabu@thick \@tempdima -\let\tabu@on \@tempdimb -\let\tabu@off \@tempdimc -\newdimen \tabu@Xsum -\newdimen \extrarowdepth -\newdimen \abovetabulinesep -\newdimen \belowtabulinesep -\newdimen \tabustrutrule \tabustrutrule \z@ -\newtoks \tabu@thebody -\newtoks \tabu@footnotes -\newsavebox \tabu@box -\newsavebox \tabu@arstrutbox -\newsavebox \tabu@hleads -\newsavebox \tabu@vleads -\newif \iftabu@colortbl -\newif \iftabu@siunitx -\newif \iftabu@measuring -\newif \iftabu@spread -\newif \iftabu@negcoef -\newif \iftabu@everyrow -\def\tabu@everyrowtrue {\global\let\iftabu@everyrow \iftrue} -\def\tabu@everyrowfalse{\global\let\iftabu@everyrow \iffalse} -\newif \iftabu@long -\newif \iftabuscantokens -\def\tabu@rescan {\tabu@verbatim \scantokens } -%% Utilities (for internal usage) ----------------------------------- -\def\tabu@gobblespace #1 {#1} -\def\tabu@gobbletoken #1#2{#1} -\def\tabu@gobbleX{\futurelet\@let@token \tabu@gobblex} -\def\tabu@gobblex{\if ^^J\noexpand\@let@token \expandafter\@gobble - \else\ifx \@sptoken\@let@token - \expandafter\tabu@gobblespace\expandafter\tabu@gobbleX - \fi\fi -}% \tabu@gobblex -\def\tabu@X{^^J} -{\obeyspaces -\global\let\tabu@spxiii= % saves an active space (for \ifx) -\gdef\tabu@@spxiii{ }} -\def\tabu@ifenvir {% only for \multicolumn - \expandafter\tabu@if@nvir\csname\@currenvir\endcsname -}% \tabu@ifenvir -\def\tabu@if@nvir #1{\csname @\ifx\tabu#1first\else - \ifx\longtabu#1first\else - second\fi\fi oftwo\endcsname -}% \tabu@ifenvir -\def\tabu@modulo #1#2{\numexpr\ifnum\numexpr#1=\z@ 0\else #1-(#1-(#2-1)/2)/(#2)*(#2)\fi} -{\catcode`\&=3 -\gdef\tabu@strtrim #1{% #1 = control sequence to trim - \ifodd 1\ifx #1\@empty \else \ifx #1\space \else 0\fi \fi - \let\tabu@c@l@r \@empty \let#1\@empty - \else \expandafter \tabu@trimspaces #1\@nnil - \fi -}% \tabu@strtrim -\gdef\tabu@trimspaces #1\@nnil{\let\tabu@c@l@r=#2\tabu@firstspace .#1& }% -\gdef\tabu@firstspace #1#2#3 &{\tabu@lastspace #2#3&} -\gdef\tabu@lastspace #1{\def #3{#1}% - \ifx #3\tabu@c@l@r \def\tabu@c@l@r{\protect\color{#1}}\expandafter\remove@to@nnil \fi - \tabu@trimspaces #1\@nnil} -}% \catcode -\def\tabu@sanitizearg #1#2{{% - \csname \ifcsname if@safe@actives\endcsname % - @safe@activestrue\else - relax\fi \endcsname - \edef#2{#1}\tabu@strtrim#2\@onelevel@sanitize#2% - \expandafter}\expandafter\def\expandafter#2\expandafter{#2}% -}% \tabu@sanitizearg -\def\tabu@textbar #1{\begingroup \endlinechar\m@ne \scantokens{\def\:{|}}% - \expandafter\endgroup \expandafter#1\:% !!! semi simple group !!! -}% \tabu@textbar -\def\tabu@everyrow@bgroup{\iftabu@everyrow \begingroup \else \noalign{\ifnum0=`}\fi \fi} -\def\tabu@everyrow@egroup{% - \iftabu@everyrow \expandafter \endgroup \the\toks@ - \else \ifnum0=`{\fi}% - \fi -}% \tabu@everyrow@egroup -\def\tabu@arstrut {\global\setbox\@arstrutbox \hbox{\vrule - height \arraystretch \dimexpr\ht\strutbox+\extrarowheight - depth \arraystretch \dimexpr\dp\strutbox+\extrarowdepth - width \z@}% -}% \tabu@arstrut -\def\tabu@rearstrut {% - \@tempdima \arraystretch\dimexpr\ht\strutbox+\extrarowheight \relax - \@tempdimb \arraystretch\dimexpr\dp\strutbox+\extrarowdepth \relax - \ifodd 1\ifdim \ht\@arstrutbox=\@tempdima - \ifdim \dp\@arstrutbox=\@tempdimb 0 \fi\fi - \tabu@mkarstrut - \fi -}% \tabu@rearstrut -\def\tabu@@DBG #1{\ifdim\tabustrutrule>\z@ \color{#1}\fi} -\def\tabu@DBG@arstrut {\global\setbox\@arstrutbox - \hbox to\z@{\hbox to\z@{\hss - {\tabu@DBG{cyan}\vrule - height \arraystretch \dimexpr\ht\strutbox+\extrarowheight - depth \z@ - width \tabustrutrule}\kern-\tabustrutrule - {\tabu@DBG{pink}\vrule - height \z@ - depth \arraystretch \dimexpr\dp\strutbox+\extrarowdepth - width \tabustrutrule}}}% -}% \tabu@DBG@arstrut -\def\tabu@save@decl{\toks\count@ \expandafter{\the\toks\expandafter\count@ - \@nextchar}}% -\def\tabu@savedecl{\ifcat$\d@llarend\else - \let\save@decl \tabu@save@decl \fi % no inversion of tokens in text mode -}% \tabu@savedecl -\def\tabu@finalstrut #1{\unskip\ifhmode\nobreak\fi\vrule height\z@ depth\z@ width\z@} -\newcommand*\tabuDisableCommands {\g@addto@macro\tabu@trialh@@k } -\let\tabu@trialh@@k \@empty -\def\tabu@nowrite #1#{{\afterassignment}\toks@} -\let\tabu@write\write -\let\tabu@immediate\immediate -\def\tabu@WRITE{\begingroup - \def\immediate\write{\aftergroup\endgroup - \tabu@immediate\tabu@write}% -}% \tabu@WRITE -\expandafter\def\expandafter\tabu@GenericError\expandafter{% - \expandafter\tabu@WRITE\GenericError} -\def\tabu@warn{\tabu@WRITE\PackageWarning{tabu}} -\def\tabu@noxfootnote [#1]{\@gobble} -\def\tabu@nocolor #1#{\@gobble} -\newcommand*\tabu@norowcolor[2][]{} -\def\tabu@maybesiunitx #1{\def\tabu@temp{#1}% - \futurelet\@let@token \tabu@m@ybesiunitx} -\def\tabu@m@ybesiunitx #1{\def\tabu@m@ybesiunitx {% - \ifx #1\@let@token \let\tabu@cellleft \@empty \let\tabu@cellright \@empty \fi - \tabu@temp}% \tabu@m@ybesiunitx -}\expandafter\tabu@m@ybesiunitx \csname siunitx_table_collect_begin:Nn\endcsname -\def\tabu@celllalign@def #1{\def\tabu@celllalign{\tabu@maybesiunitx{#1}}}% -%% Fixed vertical spacing adjustment: \extrarowsep ------------------ -\newcommand*\extrarowsep{\edef\tabu@C@extra{\the\numexpr\tabu@C@extra+1}% - \iftabu@everyrow \aftergroup\tabu@Gextra - \else \aftergroup\tabu@n@Gextra - \fi - \@ifnextchar={\tabu@gobbletoken\tabu@extra} \tabu@extra -}% \extrarowsep -\def\tabu@extra {\@ifnextchar_% - {\tabu@gobbletoken{\tabu@setextra\extrarowheight \extrarowdepth}} - {\ifx ^\@let@token \def\tabu@temp{% - \tabu@gobbletoken{\tabu@setextra\extrarowdepth \extrarowheight}}% - \else \let\tabu@temp \@empty - \afterassignment \tabu@setextrasep \extrarowdepth - \fi \tabu@temp}% -}% \tabu@extra -\def\tabu@setextra #1#2{\def\tabu@temp{\tabu@extr@#1#2}\afterassignment\tabu@temp#2} -\def\tabu@extr@ #1#2{\@ifnextchar^% - {\tabu@gobbletoken{\tabu@setextra\extrarowdepth \extrarowheight}} - {\ifx _\@let@token \def\tabu@temp{% - \tabu@gobbletoken{\tabu@setextra\extrarowheight \extrarowdepth}}% - \else \let\tabu@temp \@empty - \tabu@Gsave \tabu@G@extra \tabu@C@extra \extrarowheight \extrarowdepth - \fi \tabu@temp}% -}% \tabu@extr@ -\def\tabu@setextrasep {\extrarowheight=\extrarowdepth - \tabu@Gsave \tabu@G@extra \tabu@C@extra \extrarowheight \extrarowdepth -}% \tabu@setextrasep -\def\tabu@Gextra{\ifx \tabu@G@extra\@empty \else {\tabu@Rextra}\fi} -\def\tabu@n@Gextra{\ifx \tabu@G@extra\@empty \else \noalign{\tabu@Rextra}\fi} -\def\tabu@Rextra{\tabu@Grestore \tabu@G@extra \tabu@C@extra} -\let\tabu@C@extra \z@ -\let\tabu@G@extra \@empty -%% Dynamic vertical spacing adjustment: \tabulinesep ---------------- -\newcommand*\tabulinesep{\edef\tabu@C@linesep{\the\numexpr\tabu@C@linesep+1}% - \iftabu@everyrow \aftergroup\tabu@Glinesep - \else \aftergroup\tabu@n@Glinesep - \fi - \@ifnextchar={\tabu@gobbletoken\tabu@linesep} \tabu@linesep -}% \tabulinesep -\def\tabu@linesep {\@ifnextchar_% - {\tabu@gobbletoken{\tabu@setsep\abovetabulinesep \belowtabulinesep}} - {\ifx ^\@let@token \def\tabu@temp{% - \tabu@gobbletoken{\tabu@setsep\belowtabulinesep \abovetabulinesep}}% - \else \let\tabu@temp \@empty - \afterassignment \tabu@setlinesep \abovetabulinesep - \fi \tabu@temp}% -}% \tabu@linesep -\def\tabu@setsep #1#2{\def\tabu@temp{\tabu@sets@p#1#2}\afterassignment\tabu@temp#2} -\def\tabu@sets@p #1#2{\@ifnextchar^% - {\tabu@gobbletoken{\tabu@setsep\belowtabulinesep \abovetabulinesep}} - {\ifx _\@let@token \def\tabu@temp{% - \tabu@gobbletoken{\tabu@setsep\abovetabulinesep \belowtabulinesep}}% - \else \let\tabu@temp \@empty - \tabu@Gsave \tabu@G@linesep \tabu@C@linesep \abovetabulinesep \belowtabulinesep - \fi \tabu@temp}% -}% \tabu@sets@p -\def\tabu@setlinesep {\belowtabulinesep=\abovetabulinesep - \tabu@Gsave \tabu@G@linesep \tabu@C@linesep \abovetabulinesep \belowtabulinesep -}% \tabu@setlinesep -\def\tabu@Glinesep{\ifx \tabu@G@linesep\@empty \else {\tabu@Rlinesep}\fi} -\def\tabu@n@Glinesep{\ifx \tabu@G@linesep\@empty \else \noalign{\tabu@Rlinesep}\fi} -\def\tabu@Rlinesep{\tabu@Grestore \tabu@G@linesep \tabu@C@linesep} -\let\tabu@C@linesep \z@ -\let\tabu@G@linesep \@empty -%% \global\extrarowsep and \global\tabulinesep ------------------- -\def\tabu@Gsave #1#2#3#4{\xdef#1{#1% - \toks#2{\toks\the\currentgrouplevel{\global#3\the#3\global#4\the#4}}}% -}% \tabu@Gsave -\def\tabu@Grestore#1#2{% - \toks#2{}#1\toks\currentgrouplevel\expandafter{\expandafter}\the\toks#2\relax - \ifcat$\the\toks\currentgrouplevel$\else - \global\let#1\@empty \global\let#2\z@ - \the\toks\currentgrouplevel - \fi -}% \tabu@Grestore -%% Setting code for every row --------------------------------------- -\newcommand*\everyrow{\tabu@everyrow@bgroup - \tabu@start \z@ \tabu@stop \z@ \tabu@evrstartstop -}% \everyrow -\def\tabu@evrstartstop {\@ifnextchar^% - {\afterassignment \tabu@evrstartstop \tabu@stop=}% - {\ifx ^\@let@token - \afterassignment\tabu@evrstartstop \tabu@start=% - \else \afterassignment\tabu@everyr@w \toks@ - \fi}% -}% \tabu@evrstartstop -\def\tabu@everyr@w {% - \xdef\tabu@everyrow{% - \noexpand\tabu@everyrowfalse - \let\noalign \relax - \noexpand\tabu@rowfontreset - \iftabu@colortbl \noexpand\tabu@rc@ \fi % \taburowcolors - \let\noexpand\tabu@docline \noexpand\tabu@docline@evr - \the\toks@ - \noexpand\tabu@evrh@@k - \noexpand\tabu@rearstrut - \global\advance\c@taburow \@ne}% - \iftabu@everyrow \toks@\expandafter - {\expandafter\def\expandafter\tabu@evr@L\expandafter{\the\toks@}\ignorespaces}% - \else \xdef\tabu@evr@G{\the\toks@}% - \fi - \tabu@everyrow@egroup -}% \tabu@everyr@w -\def\tabu@evr {\def\tabu@evrh@@k} % for internal use only -\tabu@evr{} -%% line style and leaders ------------------------------------------- -\newcommand*\newtabulinestyle [1]{% - {\@for \@tempa :=#1\do{\expandafter\tabu@newlinestyle \@tempa==\@nil}}% -}% \newtabulinestyle -\def\tabu@newlinestyle #1=#2=#3\@nil{\tabu@getline {#2}% - \tabu@sanitizearg {#1}\@tempa - \ifodd 1\ifx \@tempa\@empty \ifdefined\tabu@linestyle@ 0 \fi\fi - \global\expandafter\let - \csname tabu@linestyle@\@tempa \endcsname =\tabu@thestyle \fi -}% \tabu@newlinestyle -\newcommand*\tabulinestyle [1]{\tabu@everyrow@bgroup \tabu@getline{#1}% - \iftabu@everyrow - \toks@\expandafter{\expandafter \def \expandafter - \tabu@ls@L\expandafter{\tabu@thestyle}\ignorespaces}% - \gdef\tabu@ls@{\tabu@ls@L}% - \else - \global\let\tabu@ls@G \tabu@thestyle - \gdef\tabu@ls@{\tabu@ls@G}% - \fi - \tabu@everyrow@egroup -}% \tabulinestyle -\newcommand*\taburulecolor{\tabu@everyrow@bgroup \tabu@textbar \tabu@rulecolor} -\def\tabu@rulecolor #1{\toks@{}% - \def\tabu@temp #1##1#1{\tabu@ruledrsc{##1}}\@ifnextchar #1% - \tabu@temp - \tabu@rulearc -}% \tabu@rulecolor -\def\tabu@ruledrsc #1{\edef\tabu@temp{#1}\tabu@strtrim\tabu@temp - \ifx \tabu@temp\@empty \def\tabu@temp{\tabu@rule@drsc@ {}{}}% - \else \edef\tabu@temp{\noexpand\tabu@rule@drsc@ {}{\tabu@temp}}% - \fi - \tabu@temp -}% \tabu@ruledrsc@ -\def\tabu@ruledrsc@ #1#{\tabu@rule@drsc@ {#1}} -\def\tabu@rule@drsc@ #1#2{% - \iftabu@everyrow - \ifx \\#1#2\\\toks@{\let\CT@drsc@ \relax}% - \else \toks@{\def\CT@drsc@{\color #1{#2}}}% - \fi - \else - \ifx \\#1#2\\\global\let\CT@drsc@ \relax - \else \gdef\CT@drsc@{\color #1{#2}}% - \fi - \fi - \tabu@rulearc -}% \tabu@rule@drsc@ -\def\tabu@rulearc #1#{\tabu@rule@arc@ {#1}} -\def\tabu@rule@arc@ #1#2{% - \iftabu@everyrow - \ifx \\#1#2\\\toks@\expandafter{\the\toks@ \def\CT@arc@{}}% - \else \toks@\expandafter{\the\toks@ \def\CT@arc@{\color #1{#2}}}% - \fi - \toks@\expandafter{\the\toks@ - \let\tabu@arc@L \CT@arc@ - \let\tabu@drsc@L \CT@drsc@ - \ignorespaces}% - \else - \ifx \\#1#2\\\gdef\CT@arc@{}% - \else \gdef\CT@arc@{\color #1{#2}}% - \fi - \global\let\tabu@arc@G \CT@arc@ - \global\let\tabu@drsc@G \CT@drsc@ - \fi - \tabu@everyrow@egroup -}% \tabu@rule@arc@ -\def\taburowcolors {\tabu@everyrow@bgroup \@testopt \tabu@rowcolors 1} -\def\tabu@rowcolors [#1]#2#{\tabu@rowc@lors{#1}{#2}} -\def\tabu@rowc@lors #1#2#3{% - \toks@{}\@defaultunits \count@ =\number0#2\relax \@nnil - \@defaultunits \tabu@start =\number0#1\relax \@nnil - \ifnum \count@<\tw@ \count@=\tw@ \fi - \advance\tabu@start \m@ne - \ifnum \tabu@start<\z@ \tabu@start \z@ \fi - \tabu@rowcolorseries #3\in@..\in@ \@nnil -}% \tabu@rowcolors -\def\tabu@rowcolorseries #1..#2\in@ #3\@nnil {% - \ifx \in@#1\relax - \iftabu@everyrow \toks@{\def\tabu@rc@{}\let\tabu@rc@L \tabu@rc@}% - \else \gdef\tabu@rc@{}\global\let\tabu@rc@G \tabu@rc@ - \fi - \else - \ifx \\#2\\\tabu@rowcolorserieserror \fi - \tabu@sanitizearg{#1}\tabu@temp - \tabu@sanitizearg{#2}\@tempa - \advance\count@ \m@ne - \iftabu@everyrow - \def\tabu@rc@ ##1##2##3##4{\def\tabu@rc@{% - \ifnum ##2=\c@taburow - \definecolorseries{tabu@rcseries@\the\tabu@nested}{rgb}{last}{##3}{##4}\fi - \ifnum \c@taburow<##2 \else - \ifnum \tabu@modulo {\c@taburow-##2}{##1+1}=\z@ - \resetcolorseries[{##1}]{tabu@rcseries@\the\tabu@nested}\fi - \xglobal\colorlet{tabu@rc@\the\tabu@nested}{tabu@rcseries@\the\tabu@nested!!+}% - \rowcolor{tabu@rc@\the\tabu@nested}\fi}% - }\edef\x{\noexpand\tabu@rc@ {\the\count@} - {\the\tabu@start} - {\tabu@temp} - {\@tempa}% - }\x - \toks@\expandafter{\expandafter\def\expandafter\tabu@rc@\expandafter{\tabu@rc@}}% - \toks@\expandafter{\the\toks@ \let\tabu@rc@L \tabu@rc@ \ignorespaces}% - \else % inside \noalign - \definecolorseries{tabu@rcseries@\the\tabu@nested}{rgb}{last}{\tabu@temp}{\@tempa}% - \expandafter\resetcolorseries\expandafter[\the\count@]{tabu@rcseries@\the\tabu@nested}% - \xglobal\colorlet{tabu@rc@\the\tabu@nested}{tabu@rcseries@\the\tabu@nested!!+}% - \let\noalign \relax \rowcolor{tabu@rc@\the\tabu@nested}% - \def\tabu@rc@ ##1##2{\gdef\tabu@rc@{% - \ifnum \tabu@modulo {\c@taburow-##2}{##1+1}=\@ne - \resetcolorseries[{##1}]{tabu@rcseries@\the\tabu@nested}\fi - \xglobal\colorlet{tabu@rc@\the\tabu@nested}{tabu@rcseries@\the\tabu@nested!!+}% - \rowcolor{tabu@rc@\the\tabu@nested}}% - }\edef\x{\noexpand\tabu@rc@{\the\count@}{\the\c@taburow}}\x - \global\let\tabu@rc@G \tabu@rc@ - \fi - \fi - \tabu@everyrow@egroup -}% \tabu@rowcolorseries -\tabuDisableCommands {\let\tabu@rc@ \@empty } -\def\tabu@rowcolorserieserror {\PackageError{tabu} - {Invalid syntax for \string\taburowcolors - \MessageBreak Please look at the documentation!}\@ehd -}% \tabu@rowcolorserieserror -\newcommand*\tabureset {% - \tabulinesep=\z@ \extrarowsep=\z@ \extratabsurround=\z@ - \tabulinestyle{}\everyrow{}\taburulecolor||{}\taburowcolors{}% -}% \tabureset -%% Parsing the line styles ------------------------------------------ -\def\tabu@getline #1{\begingroup - \csname \ifcsname if@safe@actives\endcsname % - @safe@activestrue\else - relax\fi \endcsname - \edef\tabu@temp{#1}\tabu@sanitizearg{#1}\@tempa - \let\tabu@thestyle \relax - \ifcsname tabu@linestyle@\@tempa \endcsname - \edef\tabu@thestyle{\endgroup - \def\tabu@thestyle{\expandafter\noexpand - \csname tabu@linestyle@\@tempa\endcsname}% - }\tabu@thestyle - \else \expandafter\tabu@definestyle \tabu@temp \@nil - \fi -}% \tabu@getline -\def\tabu@definestyle #1#2\@nil {\endlinechar \m@ne \makeatletter - \tabu@thick \maxdimen \tabu@on \maxdimen \tabu@off \maxdimen - \let\tabu@c@lon \@undefined \let\tabu@c@loff \@undefined - \ifodd 1\ifcat .#1\else\ifcat\relax #1\else 0\fi\fi % catcode 12 or non expandable cs - \def\tabu@temp{\tabu@getparam{thick}}% - \else \def\tabu@temp{\tabu@getparam{thick}\maxdimen}% - \fi - {% - \let\tabu@ \relax - \def\:{\obeyspaces \tabu@oXIII \tabu@commaXIII \edef\:}% (space active \: happy ;-)) - \scantokens{\:{\tabu@temp #1#2 \tabu@\tabu@}}% - \expandafter}\expandafter - \def\expandafter\:\expandafter{\:}% line spec rewritten now ;-) - \def\;{\def\:}% - \scantokens\expandafter{\expandafter\;\expandafter{\:}}% space is now inactive (catcode 10) - \let\tabu@ \tabu@getcolor \:% all arguments are ready now ;-) - \ifdefined\tabu@c@lon \else \let\tabu@c@lon\@empty \fi - \ifx \tabu@c@lon\@empty \def\tabu@c@lon{\CT@arc@}\fi - \ifdefined\tabu@c@loff \else \let\tabu@c@loff \@empty \fi - \ifdim \tabu@on=\maxdimen \ifdim \tabu@off<\maxdimen - \tabu@on \tabulineon \fi\fi - \ifdim \tabu@off=\maxdimen \ifdim \tabu@on<\maxdimen - \tabu@off \tabulineoff \fi\fi - \ifodd 1\ifdim \tabu@off=\maxdimen \ifdim \tabu@on=\maxdimen 0 \fi\fi - \in@true % - \else \in@false % - \fi - \ifdim\tabu@thick=\maxdimen \def\tabu@thick{\arrayrulewidth}% - \else \edef\tabu@thick{\the\tabu@thick}% - \fi - \edef \tabu@thestyle ##1##2{\endgroup - \def\tabu@thestyle{% - \ifin@ \noexpand\tabu@leadersstyle {\tabu@thick} - {\the\tabu@on}{##1} - {\the\tabu@off}{##2}% - \else \noexpand\tabu@rulesstyle - {##1\vrule width \tabu@thick}% - {##1\leaders \hrule height \tabu@thick \hfil}% - \fi}% - }\expandafter \expandafter - \expandafter \tabu@thestyle \expandafter - \expandafter \expandafter - {\expandafter\tabu@c@lon\expandafter}\expandafter{\tabu@c@loff}% -}% \tabu@definestyle -{\catcode`\O=\active \lccode`\O=`\o \catcode`\,=\active - \lowercase{\gdef\tabu@oXIII {\catcode`\o=\active \let O=\tabu@oxiii}} - \gdef\tabu@commaXIII {\catcode`\,=\active \let ,=\space} -}% \catcode -\def\tabu@oxiii #1{% - \ifcase \ifx n#1\z@ \else - \ifx f#1\@ne\else - \tw@ \fi\fi - \expandafter\tabu@onxiii - \or \expandafter\tabu@ofxiii - \else o% - \fi#1}% -\def\tabu@onxiii #1#2{% - \ifcase \ifx !#2\tw@ \else - \ifcat.\noexpand#2\z@ \else - \ifx \tabu@spxiii#2\@ne\else - \tw@ \fi\fi\fi - \tabu@getparam{on}#2\expandafter\@gobble - \or \expandafter\tabu@onxiii % (space is active) - \else o\expandafter\@firstofone - \fi{#1#2}}% -\def\tabu@ofxiii #1#2{% - \ifx #2f\expandafter\tabu@offxiii - \else o\expandafter\@firstofone - \fi{#1#2}} -\def\tabu@offxiii #1#2{% - \ifcase \ifx !#2\tw@ \else - \ifcat.\noexpand#2\z@ \else - \ifx\tabu@spxiii#2\@ne \else - \tw@ \fi\fi\fi - \tabu@getparam{off}#2\expandafter\@gobble - \or \expandafter\tabu@offxiii % (space is active) - \else o\expandafter\@firstofone - \fi{#1#2}} -\def\tabu@getparam #1{\tabu@ \csname tabu@#1\endcsname=} -\def\tabu@getcolor #1{% \tabu@ <- \tabu@getcolor after \edef - \ifx \tabu@#1\else % no more spec - \let\tabu@theparam=#1\afterassignment \tabu@getc@l@r #1\fi -}% \tabu@getcolor -\def\tabu@getc@l@r #1\tabu@ {% - \def\tabu@temp{#1}\tabu@strtrim \tabu@temp - \ifx \tabu@temp\@empty - \else%\ifcsname \string\color@\tabu@temp \endcsname % if the color exists - \ifx \tabu@theparam \tabu@off \let\tabu@c@loff \tabu@c@l@r - \else \let\tabu@c@lon \tabu@c@l@r - \fi - %\else \tabu@warncolour{\tabu@temp}% - \fi%\fi - \tabu@ % next spec -}% \tabu@getc@l@r -\def\tabu@warncolour #1{\PackageWarning{tabu} - {Color #1 is not defined. Default color used}% -}% \tabu@warncolour -\def\tabu@leadersstyle #1#2#3#4#5{\def\tabu@leaders{{#1}{#2}{#3}{#4}{#5}}% - \ifx \tabu@leaders\tabu@leaders@G \else - \tabu@LEADERS{#1}{#2}{#3}{#4}{#5}\fi -}% \tabu@leadersstyle -\def\tabu@rulesstyle #1#2{\let\tabu@leaders \@undefined - \gdef\tabu@thevrule{#1}\gdef\tabu@thehrule{#2}% -}% \tabu@rulesstyle -%% The leaders boxes ------------------------------------------------ -\def\tabu@LEADERS #1#2#3#4#5{%% width, dash, dash color, gap, gap color - {\let\color \tabu@color % => during trials -> \color = \tabu@nocolor - {% % but the leaders boxes should have colors ! - \def\@therule{\vrule}\def\@thick{height}\def\@length{width}% - \def\@box{\hbox}\def\@unbox{\unhbox}\def\@elt{\wd}% - \def\@skip{\hskip}\def\@ss{\hss}\def\tabu@leads{\tabu@hleads}% - \tabu@l@@d@rs {#1}{#2}{#3}{#4}{#5}% - \global\let\tabu@thehleaders \tabu@theleaders - }% - {% - \def\@therule{\hrule}\def\@thick{width}\def\@length{height}% - \def\@box{\vbox}\def\@unbox{\unvbox}\def\@elt{\ht}% - \def\@skip{\vskip}\def\@ss{\vss}\def\tabu@leads{\tabu@vleads}% - \tabu@l@@d@rs {#1}{#2}{#3}{#4}{#5}% - \global\let\tabu@thevleaders \tabu@theleaders - }% - \gdef\tabu@leaders@G{{#1}{#2}{#3}{#4}{#5}}% - }% -}% \tabu@LEADERS -\def\tabu@therule #1#2{\@therule \@thick#1\@length\dimexpr#2/2 \@depth\z@} -\def\tabu@l@@d@rs #1#2#3#4#5{%% width, dash, dash color, gap, gap color - \global\setbox \tabu@leads=\@box{% - {#3\tabu@therule{#1}{#2}}% - \ifx\\#5\\\@skip#4\else{#5\tabu@therule{#1}{#4*2}}\fi - {#3\tabu@therule{#1}{#2}}}% - \global\setbox\tabu@leads=\@box to\@elt\tabu@leads{\@ss - {#3\tabu@therule{#1}{#2}}\@unbox\tabu@leads}% - \edef\tabu@theleaders ##1{\def\noexpand\tabu@theleaders {% - {##1\tabu@therule{#1}{#2}}% - \xleaders \copy\tabu@leads \@ss - \tabu@therule{0pt}{-#2}{##1\tabu@therule{#1}{#2}}}% - }\tabu@theleaders{#3}% -}% \tabu@l@@d@rs -%% \tabu \endtabu \tabu* \longtabu \endlongtabu \longtabu* ---------- -\newcommand*\tabu {\tabu@longfalse - \ifmmode \def\tabu@ {\array}\def\endtabu {\endarray}% - \else \def\tabu@ {\tabu@tabular}\def\endtabu {\endtabular}\fi - \expandafter\let\csname tabu*\endcsname \tabu - \expandafter\def\csname endtabu*\endcsname{\endtabu}% - \tabu@spreadfalse \tabu@negcoeffalse \tabu@settarget -}% {tabu} -\let\tabu@tabular \tabular % -\expandafter\def\csname tabu*\endcsname{\tabuscantokenstrue \tabu} -\newcommand*\longtabu {\tabu@longtrue - \ifmmode\PackageError{tabu}{longtabu not allowed in math mode}\fi - \def\tabu@{\longtable}\def\endlongtabu{\endlongtable}% - \LTchunksize=\@M - \expandafter\let\csname tabu*\endcsname \tabu - \expandafter\def\csname endlongtabu*\endcsname{\endlongtabu}% - \let\LT@startpbox \tabu@LT@startpbox % \everypar{ array struts } - \tabu@spreadfalse \tabu@negcoeffalse \tabu@settarget -}% {longtabu} -\expandafter\def\csname longtabu*\endcsname{\tabuscantokenstrue \longtabu} -\def\tabu@nolongtabu{\PackageError{tabu} - {longtabu requires the longtable package}\@ehd} -%% Read the target and then : \tabular or \@array ------------------ -\def\tabu@settarget {\futurelet\@let@token \tabu@sett@rget } -\def\tabu@sett@rget {\tabu@target \z@ - \ifcase \ifx \bgroup\@let@token \z@ \else - \ifx \@sptoken\@let@token \@ne \else - \if t\@let@token \tw@ \else - \if s\@let@token \thr@@\else - \z@\fi\fi\fi\fi - \expandafter\tabu@begin - \or \expandafter\tabu@gobblespace\expandafter\tabu@settarget - \or \expandafter\tabu@to - \or \expandafter\tabu@spread - \fi -}% \tabu@sett@rget -\def\tabu@to to{\def\tabu@halignto{to}\tabu@gettarget} -\def\tabu@spread spread{\tabu@spreadtrue\def\tabu@halignto{spread}\tabu@gettarget} -\def\tabu@gettarget {\afterassignment\tabu@linegoaltarget \tabu@target } -\def\tabu@linegoaltarget {\futurelet\tabu@temp \tabu@linegoalt@rget } -\def\tabu@linegoalt@rget {% - \ifx \tabu@temp\LNGL@setlinegoal - \LNGL@setlinegoal \expandafter \@firstoftwo \fi % @gobbles \LNGL@setlinegoal - \tabu@begin -}% \tabu@linegoalt@rget -\def\tabu@begin #1#{% - \iftabu@measuring \expandafter\tabu@nestedmeasure \fi - \ifdim \tabu@target=\z@ \let\tabu@halignto \@empty - \else \edef\tabu@halignto{\tabu@halignto\the\tabu@target}% - \fi - \@testopt \tabu@tabu@ \tabu@aligndefault #1\@nil -}% \tabu@begin -\long\def\tabu@tabu@ [#1]#2\@nil #3{\tabu@setup - \def\tabu@align {#1}\def\tabu@savedpream{\NC@find #3}% - \tabu@ [\tabu@align ]#2{#3\tabu@rewritefirst }% -}% \tabu@tabu@ -\def\tabu@nestedmeasure {% - \ifodd 1\iftabu@spread \else \ifdim\tabu@target=\z@ \else 0 \fi\fi\relax - \tabu@spreadtrue - \else \begingroup \iffalse{\fi \ifnum0=`}\fi - \toks@{}\def\tabu@stack{b}% - \expandafter\tabu@collectbody\expandafter\tabu@quickrule - \expandafter\endgroup - \fi -}% \tabu@nestedmeasure -\def\tabu@quickrule {\indent\vrule height\z@ depth\z@ width\tabu@target} -%% \tabu@setup \tabu@init \tabu@indent -\def\tabu@setup{\tabu@alloc@ - \ifcase \tabu@nested - \ifmmode \else \iftabu@spread\else \ifdim\tabu@target=\z@ - \let\tabu@afterendpar \par - \fi\fi\fi - \def\tabu@aligndefault{c}\tabu@init \tabu@indent - \else % - \def\tabu@aligndefault{t}\let\tabudefaulttarget \linewidth - \fi - \let\tabu@thetarget \tabudefaulttarget \let\tabu@restored \@undefined - \edef\tabu@NC@list{\the\NC@list}\NC@list{\NC@do \tabu@rewritefirst}% - \everycr{}\let\@startpbox \tabu@startpbox % for nested tabu inside longtabu... - \let\@endpbox \tabu@endpbox % idem " " " " " " - \let\@tabarray \tabu@tabarray % idem " " " " " " - \tabu@setcleanup \tabu@setreset -}% \tabu@setup -\def\tabu@init{\tabu@starttimer \tabu@measuringfalse - \edef\tabu@hfuzz {\the\dimexpr\hfuzz+1sp}\global\tabu@footnotes{}% - \let\firsthline \tabu@firsthline \let\lasthline \tabu@lasthline - \let\firstline \tabu@firstline \let\lastline \tabu@lastline - \let\hline \tabu@hline \let\@xhline \tabu@xhline - \let\color \tabu@color \let\@arstrutbox \tabu@arstrutbox - \iftabu@colortbl\else\let\LT@@hline \tabu@LT@@hline \fi - \tabu@trivlist % - \let\@footnotetext \tabu@footnotetext \let\@xfootnotetext \tabu@xfootnotetext - \let\@xfootnote \tabu@xfootnote \let\centering \tabu@centering - \let\raggedright \tabu@raggedright \let\raggedleft \tabu@raggedleft - \let\tabudecimal \tabu@tabudecimal \let\Centering \tabu@Centering - \let\RaggedRight \tabu@RaggedRight \let\RaggedLeft \tabu@RaggedLeft - \let\justifying \tabu@justifying \let\rowfont \tabu@rowfont - \let\fbox \tabu@fbox \let\color@b@x \tabu@color@b@x - \let\tabu@@everycr \everycr \let\tabu@@everypar \everypar - \let\tabu@prepnext@tokORI \prepnext@tok\let\prepnext@tok \tabu@prepnext@tok - \let\tabu@multicolumnORI\multicolumn \let\multicolumn \tabu@multicolumn - \let\tabu@startpbox \@startpbox % for nested tabu inside longtabu pfff !!! - \let\tabu@endpbox \@endpbox % idem " " " " " " " - \let\tabu@tabarray \@tabarray % idem " " " " " " " - \tabu@adl@fix \let\endarray \tabu@endarray % colortbl & arydshln (delarray) - \iftabu@colortbl\CT@everycr\expandafter{\expandafter\iftabu@everyrow \the\CT@everycr \fi}\fi -}% \tabu@init -\def\tabu@indent{% correction for indentation - \ifdim \parindent>\z@\ifx \linewidth\tabudefaulttarget - \everypar\expandafter{% - \the\everypar\everypar\expandafter{\the\everypar}% - \setbox\z@=\lastbox - \ifdim\wd\z@>\z@ \edef\tabu@thetarget - {\the\dimexpr -\wd\z@+\tabudefaulttarget}\fi - \box\z@}% - \fi\fi -}% \tabu@indent -\def\tabu@setcleanup {% saves last global assignments - \ifodd 1\ifmmode \else \iftabu@long \else 0\fi\fi\relax - \def\tabu@aftergroupcleanup{% - \def\tabu@aftergroupcleanup{\aftergroup\tabu@cleanup}}% - \else - \def\tabu@aftergroupcleanup{% - \aftergroup\aftergroup\aftergroup\tabu@cleanup - \let\tabu@aftergroupcleanup \relax}% - \fi - \let\tabu@arc@Gsave \tabu@arc@G - \let\tabu@arc@G \tabu@arc@L % - \let\tabu@drsc@Gsave \tabu@drsc@G - \let\tabu@drsc@G \tabu@drsc@L % - \let\tabu@ls@Gsave \tabu@ls@G - \let\tabu@ls@G \tabu@ls@L % - \let\tabu@rc@Gsave \tabu@rc@G - \let\tabu@rc@G \tabu@rc@L % - \let\tabu@evr@Gsave \tabu@evr@G - \let\tabu@evr@G \tabu@evr@L % - \let\tabu@celllalign@save \tabu@celllalign - \let\tabu@cellralign@save \tabu@cellralign - \let\tabu@cellleft@save \tabu@cellleft - \let\tabu@cellright@save \tabu@cellright - \let\tabu@@celllalign@save \tabu@@celllalign - \let\tabu@@cellralign@save \tabu@@cellralign - \let\tabu@@cellleft@save \tabu@@cellleft - \let\tabu@@cellright@save \tabu@@cellright - \let\tabu@rowfontreset@save \tabu@rowfontreset - \let\tabu@@rowfontreset@save\tabu@@rowfontreset - \let\tabu@rowfontreset \@empty - \edef\tabu@alloc@save {\the\tabu@alloc}% restore at \tabu@reset - \edef\c@taburow@save {\the\c@taburow}% - \edef\tabu@naturalX@save {\the\tabu@naturalX}% - \let\tabu@naturalXmin@save \tabu@naturalXmin - \let\tabu@naturalXmax@save \tabu@naturalXmax - \let\tabu@mkarstrut@save \tabu@mkarstrut - \edef\tabu@clarstrut{% - \extrarowheight \the\dimexpr \ht\@arstrutbox-\ht\strutbox \relax - \extrarowdepth \the\dimexpr \dp\@arstrutbox-\dp\strutbox \relax - \let\noexpand\@arraystretch \@ne \noexpand\tabu@rearstrut}% -}% \tabu@setcleanup -\def\tabu@cleanup {\begingroup - \globaldefs\@ne \tabu@everyrowtrue - \let\tabu@arc@G \tabu@arc@Gsave - \let\CT@arc@ \tabu@arc@G - \let\tabu@drsc@G \tabu@drsc@Gsave - \let\CT@drsc@ \tabu@drsc@G - \let\tabu@ls@G \tabu@ls@Gsave - \let\tabu@ls@ \tabu@ls@G - \let\tabu@rc@G \tabu@rc@Gsave - \let\tabu@rc@ \tabu@rc@G - \let\CT@do@color \relax - \let\tabu@evr@G \tabu@evr@Gsave - \let\tabu@celllalign \tabu@celllalign@save - \let\tabu@cellralign \tabu@cellralign@save - \let\tabu@cellleft \tabu@cellleft@save - \let\tabu@cellright \tabu@cellright@save - \let\tabu@@celllalign \tabu@@celllalign@save - \let\tabu@@cellralign \tabu@@cellralign@save - \let\tabu@@cellleft \tabu@@cellleft@save - \let\tabu@@cellright \tabu@@cellright@save - \let\tabu@rowfontreset \tabu@rowfontreset@save - \let\tabu@@rowfontreset \tabu@@rowfontreset@save - \tabu@naturalX =\tabu@naturalX@save - \let\tabu@naturalXmax \tabu@naturalXmax@save - \let\tabu@naturalXmin \tabu@naturalXmin@save - \let\tabu@mkarstrut \tabu@mkarstrut@save - \c@taburow =\c@taburow@save - \ifcase \tabu@nested \tabu@alloc \m@ne\fi - \endgroup % - \ifcase \tabu@nested - \the\tabu@footnotes \global\tabu@footnotes{}% - \tabu@afterendpar \tabu@elapsedtime - \fi - \tabu@clarstrut - \everyrow\expandafter {\tabu@evr@G}% -}% \tabu@cleanup -\let\tabu@afterendpar \relax -\def\tabu@setreset {% - \edef\tabu@savedparams {% \relax for \tabu@message@save - \ifmmode \col@sep \the\arraycolsep - \else \col@sep \the\tabcolsep \fi \relax - \arrayrulewidth \the\arrayrulewidth \relax - \doublerulesep \the\doublerulesep \relax - \extratabsurround \the\extratabsurround \relax - \extrarowheight \the\extrarowheight \relax - \extrarowdepth \the\extrarowdepth \relax - \abovetabulinesep \the\abovetabulinesep \relax - \belowtabulinesep \the\belowtabulinesep \relax - \def\noexpand\arraystretch{\arraystretch}% - \ifdefined\minrowclearance \minrowclearance\the\minrowclearance\relax\fi}% - \begingroup - \@temptokena\expandafter{\tabu@savedparams}% => only for \savetabu / \usetabu - \ifx \tabu@arc@L\relax \else \tabu@setsave \tabu@arc@L \fi - \ifx \tabu@drsc@L\relax \else \tabu@setsave \tabu@drsc@L \fi - \tabu@setsave \tabu@ls@L \tabu@setsave \tabu@evr@L - \expandafter \endgroup \expandafter - \def\expandafter\tabu@saved@ \expandafter{\the\@temptokena - \let\tabu@arc@G \tabu@arc@L - \let\tabu@drsc@G \tabu@drsc@L - \let\tabu@ls@G \tabu@ls@L - \let\tabu@rc@G \tabu@rc@L - \let\tabu@evr@G \tabu@evr@L}% - \def\tabu@reset{\tabu@savedparams - \tabu@everyrowtrue \c@taburow \z@ - \let\CT@arc@ \tabu@arc@L - \let\CT@drsc@ \tabu@drsc@L - \let\tabu@ls@ \tabu@ls@L - \let\tabu@rc@ \tabu@rc@L - \global\tabu@alloc \tabu@alloc@save - \everyrow\expandafter{\tabu@evr@L}}% -}% \tabu@reset -\def\tabu@setsave #1{\expandafter\tabu@sets@ve #1\@nil{#1}} -\long\def\tabu@sets@ve #1\@nil #2{\@temptokena\expandafter{\the\@temptokena \def#2{#1}}} -%% The Rewriting Process ------------------------------------------- -\def\tabu@newcolumntype #1{% - \expandafter\tabu@new@columntype - \csname NC@find@\string#1\expandafter\endcsname - \csname NC@rewrite@\string#1\endcsname - {#1}% -}% \tabu@newcolumntype -\def\tabu@new@columntype #1#2#3{% - \def#1##1#3{\NC@{##1}}% - \let#2\relax \newcommand*#2% -}% \tabu@new@columntype -\def\tabu@privatecolumntype #1{% - \expandafter\tabu@private@columntype - \csname NC@find@\string#1\expandafter\endcsname - \csname NC@rewrite@\string#1\expandafter\endcsname - \csname tabu@NC@find@\string#1\expandafter\endcsname - \csname tabu@NC@rewrite@\string#1\endcsname - {#1}% -}% \tabu@privatecolumntype -\def\tabu@private@columntype#1#2#3#4{% - \g@addto@macro\tabu@privatecolumns{\let#1#3\let#2#4}% - \tabu@new@columntype#3#4% -}% \tabu@private@columntype -\let\tabu@privatecolumns \@empty -\newcommand*\tabucolumn [1]{\expandafter \def \expandafter - \tabu@highprioritycolumns\expandafter{\tabu@highprioritycolumns - \NC@do #1}}% -\let\tabu@highprioritycolumns \@empty -%% The | ``column'' : rewriting process -------------------------- -\tabu@privatecolumntype |{\tabu@rewritevline} -\newcommand*\tabu@rewritevline[1][]{\tabu@vlinearg{#1}% - \expandafter \NC@find \tabu@rewritten} -\def\tabu@lines #1{% - \ifx|#1\else \tabu@privatecolumntype #1{\tabu@rewritevline}\fi - \NC@list\expandafter{\the\NC@list \NC@do #1}% -}% \tabu@lines@ -\def\tabu@vlinearg #1{% - \ifx\\#1\\\def\tabu@thestyle {\tabu@ls@}% - \else\tabu@getline {#1}% - \fi - \def\tabu@rewritten ##1{\def\tabu@rewritten{!{##1\tabu@thevline}}% - }\expandafter\tabu@rewritten\expandafter{\tabu@thestyle}% - \expandafter \tabu@keepls \tabu@thestyle \@nil -}% \tabu@vlinearg -\def\tabu@keepls #1\@nil{% - \ifcat $\@cdr #1\@nil $% - \ifx \relax#1\else - \ifx \tabu@ls@#1\else - \let#1\relax - \xdef\tabu@mkpreambuffer{\tabu@mkpreambuffer - \tabu@savels\noexpand#1}\fi\fi\fi -}% \tabu@keepls -\def\tabu@thevline {\begingroup - \ifdefined\tabu@leaders - \setbox\@tempboxa=\vtop to\dimexpr - \ht\@arstrutbox+\dp\@arstrutbox{{\tabu@thevleaders}}% - \ht\@tempboxa=\ht\@arstrutbox \dp\@tempboxa=\dp\@arstrutbox - \box\@tempboxa - \else - \tabu@thevrule - \fi \endgroup -}% \tabu@thevline -\def\tabu@savels #1{% - \expandafter\let\csname\string#1\endcsname #1% - \expandafter\def\expandafter\tabu@reset\expandafter{\tabu@reset - \tabu@resetls#1}}% -\def\tabu@resetls #1{\expandafter\let\expandafter#1\csname\string#1\endcsname}% -%% \multicolumn inside tabu environment ----------------------------- -\tabu@newcolumntype \tabu@rewritemulticolumn{% - \aftergroup \tabu@endrewritemulticolumn % after \@mkpream group - \NC@list{\NC@do *}\tabu@textbar \tabu@lines - \tabu@savedecl - \tabu@privatecolumns - \NC@list\expandafter{\the\expandafter\NC@list \tabu@NC@list}% - \let\tabu@savels \relax - \NC@find -}% \tabu@rewritemulticolumn -\def\tabu@endrewritemulticolumn{\gdef\tabu@mkpreambuffer{}\endgroup} -\def\tabu@multicolumn{\tabu@ifenvir \tabu@multic@lumn \tabu@multicolumnORI} -\long\def\tabu@multic@lumn #1#2#3{\multispan{#1}\begingroup - \tabu@everyrowtrue - \NC@list{\NC@do \tabu@rewritemulticolumn}% - \expandafter\@gobbletwo % gobbles \multispan{#1} - \tabu@multicolumnORI{#1}{\tabu@rewritemulticolumn #2}% - {\iftabuscantokens \tabu@rescan \else \expandafter\@firstofone \fi - {#3}}% -}% \tabu@multic@lumn -%% The X column(s): rewriting process ----------------------------- -\tabu@privatecolumntype X[1][]{\begingroup \tabu@siunitx{\endgroup \tabu@rewriteX {#1}}} -\def\tabu@nosiunitx #1{#1{}{}\expandafter \NC@find \tabu@rewritten } -\def\tabu@siunitx #1{\@ifnextchar \bgroup - {\tabu@rewriteX@Ss{#1}} - {\tabu@nosiunitx{#1}}} -\def\tabu@rewriteX@Ss #1#2{\@temptokena{}% - \@defaultunits \let\tabu@temp =#2\relax\@nnil - \ifodd 1\ifx S\tabu@temp \else \ifx s\tabu@temp \else 0 \fi\fi - \def\NC@find{\def\NC@find >####1####2<####3\relax{#1 {####1}{####3}% - }\expandafter\NC@find \the\@temptokena \relax - }\expandafter\NC@rewrite@S \@gobble #2\relax - \else \tabu@siunitxerror - \fi - \expandafter \NC@find \tabu@rewritten -}% \tabu@rewriteX@Ss -\def\tabu@siunitxerror {\PackageError{tabu}{Not a S nor s column ! - \MessageBreak X column can only embed siunitx S or s columns}\@ehd -}% \tabu@siunitxerror -\def\tabu@rewriteX #1#2#3{\tabu@Xarg {#1}{#2}{#3}% - \iftabu@measuring - \else \tabu@measuringtrue % first X column found in the preamble - \let\@halignto \relax \let\tabu@halignto \relax - \iftabu@spread \tabu@spreadtarget \tabu@target \tabu@target \z@ - \else \tabu@spreadtarget \z@ \fi - \ifdim \tabu@target=\z@ - \setlength\tabu@target \tabu@thetarget - \tabu@message{\tabu@message@defaulttarget}% - \else \tabu@message{\tabu@message@target}\fi - \fi -}% \tabu@rewriteX -\def\tabu@rewriteXrestore #1#2#3{\let\@halignto \relax - \def\tabu@rewritten{l}} -\def\tabu@Xarg #1#2#3{% - \advance\tabu@Xcol \@ne \let\tabu@Xlcr \@empty - \let\tabu@Xdisp \@empty \let\tabu@Xmath \@empty - \ifx\\#1\\% - \def\tabu@rewritten{p}\tabucolX \p@ % - \else - \let\tabu@rewritten \@empty \let\tabu@temp \@empty \tabucolX \z@ - \tabu@Xparse {}#1\relax - \fi - \tabu@Xrewritten{#2}{#3}% -}% \tabu@Xarg -\def\tabu@Xparse #1{\futurelet\@let@token \tabu@Xtest} -\expandafter\def\expandafter\tabu@Xparsespace\space{\tabu@Xparse{}} -\def\tabu@Xtest{% - \ifcase \ifx \relax\@let@token \z@ \else - \if ,\@let@token \m@ne\else - \if p\@let@token 1\else - \if m\@let@token 2\else - \if b\@let@token 3\else - \if l\@let@token 4\else - \if c\@let@token 5\else - \if r\@let@token 6\else - \if j\@let@token 7\else - \if L\@let@token 8\else - \if C\@let@token 9\else - \if R\@let@token 10\else - \if J\@let@token 11\else - \ifx \@sptoken\@let@token 12\else - \if .\@let@token 13\else - \if -\@let@token 13\else - \ifcat $\@let@token 14\else - 15\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\relax - \or \tabu@Xtype {p}% - \or \tabu@Xtype {m}% - \or \tabu@Xtype {b}% - \or \tabu@Xalign \raggedright\relax - \or \tabu@Xalign \centering\relax - \or \tabu@Xalign \raggedleft\relax - \or \tabu@Xalign \tabu@justify\relax - \or \tabu@Xalign \RaggedRight\raggedright - \or \tabu@Xalign \Centering\centering - \or \tabu@Xalign \RaggedLeft\raggedleft - \or \tabu@Xalign \justifying\tabu@justify - \or \expandafter \tabu@Xparsespace - \or \expandafter \tabu@Xcoef - \or \expandafter \tabu@Xm@th - \or \tabu@Xcoef{}% - \else\expandafter \tabu@Xparse - \fi -}% \tabu@Xtest -\def\tabu@Xalign #1#2{% - \ifx \tabu@Xlcr\@empty \else \PackageWarning{tabu} - {Duplicate horizontal alignment specification}\fi - \ifdefined#1\def\tabu@Xlcr{#1}\let#1\relax - \else \def\tabu@Xlcr{#2}\let#2\relax\fi - \expandafter\tabu@Xparse -}% \tabu@Xalign -\def\tabu@Xtype #1{% - \ifx \tabu@rewritten\@empty \else \PackageWarning{tabu} - {Duplicate vertical alignment specification}\fi - \def\tabu@rewritten{#1}\expandafter\tabu@Xparse -}% \tabu@Xtype -\def\tabu@Xcoef#1{\edef\tabu@temp{\tabu@temp#1}% - \afterassignment\tabu@Xc@ef \tabu@cnt\number\if-#10\fi -}% \tabu@Xcoef -\def\tabu@Xc@ef{\advance\tabucolX \tabu@temp\the\tabu@cnt\p@ - \tabu@Xparse{}% -}% \tabu@Xc@ef -\def\tabu@Xm@th #1{\futurelet \@let@token \tabu@Xd@sp} -\def\tabu@Xd@sp{\let\tabu@Xmath=$% - \ifx $\@let@token \def\tabu@Xdisp{\displaystyle}% - \expandafter\tabu@Xparse - \else \expandafter\tabu@Xparse\expandafter{\expandafter}% - \fi -}% \tabu@Xd@sp -\def\tabu@Xrewritten {% - \ifx \tabu@rewritten\@empty \def\tabu@rewritten{p}\fi - \ifdim \tabucolX<\z@ \tabu@negcoeftrue - \else\ifdim \tabucolX=\z@ \tabucolX \p@ - \fi\fi - \edef\tabu@temp{{\the\tabu@Xcol}{\tabu@strippt\tabucolX}}% - \edef\tabu@Xcoefs{\tabu@Xcoefs \tabu@ \tabu@temp}% - \edef\tabu@rewritten ##1##2{\def\noexpand\tabu@rewritten{% - >{\tabu@Xlcr \ifx$\tabu@Xmath$\tabu@Xdisp\fi ##1}% - \tabu@rewritten {\tabu@hsize \tabu@temp}% - <{##2\ifx$\tabu@Xmath$\fi}}% - }\tabu@rewritten -}% \tabu@Xrewritten -\def\tabu@hsize #1#2{% - \ifdim #2\p@<\z@ - \ifdim \tabucolX=\maxdimen \tabu@wd{#1}\else - \ifdim \tabu@wd{#1}<-#2\tabucolX \tabu@wd{#1}\else -#2\tabucolX\fi - \fi - \else #2\tabucolX - \fi -}% \tabu@hsize -%% \usetabu and \preamble: rewriting process --------------------- -\tabu@privatecolumntype \usetabu [1]{% - \ifx\\#1\\\tabu@saveerr{}\else - \@ifundefined{tabu@saved@\string#1} - {\tabu@saveerr{#1}} - {\let\tabu@rewriteX \tabu@rewriteXrestore - \csname tabu@saved@\string#1\expandafter\endcsname\expandafter\@ne}% - \fi -}% \NC@rewrite@\usetabu -\tabu@privatecolumntype \preamble [1]{% - \ifx\\#1\\\tabu@saveerr{}\else - \@ifundefined{tabu@saved@\string#1} - {\tabu@saveerr{#1}} - {\csname tabu@saved@\string#1\expandafter\endcsname\expandafter\z@}% - \fi -}% \NC@rewrite@\preamble -%% Controlling the rewriting process ------------------------------- -\tabu@newcolumntype \tabu@rewritefirst{% - \iftabu@long \aftergroup \tabu@longpream % - \else \aftergroup \tabu@pream - \fi - \let\tabu@ \relax \let\tabu@hsize \relax - \let\tabu@Xcoefs \@empty \let\tabu@savels \relax - \tabu@Xcol \z@ \tabu@cnt \tw@ - \gdef\tabu@mkpreambuffer{\tabu@{}}\tabu@measuringfalse - \global\setbox\@arstrutbox \box\@arstrutbox - \NC@list{\NC@do *}\tabu@textbar \tabu@lines - \NC@list\expandafter{\the\NC@list \NC@do X}% - \iftabu@siunitx % - \NC@list\expandafter{\the\NC@list \NC@do S\NC@do s}\fi - \NC@list\expandafter{\the\expandafter\NC@list \tabu@highprioritycolumns}% - \expandafter\def\expandafter\tabu@NC@list\expandafter{% - \the\expandafter\NC@list \tabu@NC@list}% % * | X S - \NC@list\expandafter{\expandafter \NC@do \expandafter\usetabu - \expandafter \NC@do \expandafter\preamble - \the\NC@list \NC@do \tabu@rewritemiddle - \NC@do \tabu@rewritelast}% - \tabu@savedecl - \tabu@privatecolumns - \edef\tabu@prev{\the\@temptokena}\NC@find \tabu@rewritemiddle -}% NC@rewrite@\tabu@rewritefirst -\tabu@newcolumntype \tabu@rewritemiddle{% - \edef\tabu@temp{\the\@temptokena}\NC@find \tabu@rewritelast -}% \NC@rewrite@\tabu@rewritemiddle -\tabu@newcolumntype \tabu@rewritelast{% - \ifx \tabu@temp\tabu@prev \advance\tabu@cnt \m@ne - \NC@list\expandafter{\tabu@NC@list \NC@do \tabu@rewritemiddle - \NC@do \tabu@rewritelast}% - \else \let\tabu@prev\tabu@temp - \fi - \ifcase \tabu@cnt \expandafter\tabu@endrewrite - \else \expandafter\NC@find \expandafter\tabu@rewritemiddle - \fi -}% \NC@rewrite@\tabu@rewritelast -%% Choosing the strategy -------------------------------------------- -\def\tabu@endrewrite {% - \let\tabu@temp \NC@find - \ifx \@arrayright\relax \let\@arrayright \@empty \fi - \count@=% - \ifx \@finalstrut\tabu@finalstrut \z@ % outer in mode 0 print - \iftabu@measuring - \xdef\tabu@mkpreambuffer{\tabu@mkpreambuffer - \tabu@target \csname tabu@\the\tabu@nested.T\endcsname - \tabucolX \csname tabu@\the\tabu@nested.X\endcsname - \edef\@halignto {\ifx\@arrayright\@empty to\tabu@target\fi}}% - \fi - \else\iftabu@measuring 4 % X columns - \xdef\tabu@mkpreambuffer{\tabu@{\tabu@mkpreambuffer - \tabu@target \the\tabu@target - \tabu@spreadtarget \the\tabu@spreadtarget}% - \def\noexpand\tabu@Xcoefs{\tabu@Xcoefs}% - \edef\tabu@halignto{\ifx \@arrayright\@empty to\tabu@target\fi}}% - \let\tabu@Xcoefs \relax - \else\ifcase\tabu@nested \thr@@ % outer, no X - \global\let\tabu@afterendpar \relax - \else \@ne % inner, no X, outer in mode 1 or 2 - \fi - \ifdefined\tabu@usetabu - \else \ifdim\tabu@target=\z@ - \else \let\tabu@temp \tabu@extracolsep - \fi\fi - \fi - \fi - \xdef\tabu@mkpreambuffer{\count@ \the\count@ \tabu@mkpreambuffer}% - \tabu@temp -}% \tabu@endrewrite -\def\tabu@extracolsep{\@defaultunits \expandafter\let - \expandafter\tabu@temp \expandafter=\the\@temptokena \relax\@nnil - \ifx \tabu@temp\@sptoken - \expandafter\tabu@gobblespace \expandafter\tabu@extracolsep - \else - \edef\tabu@temp{\noexpand\NC@find - \if |\noexpand\tabu@temp @% - \else\if !\noexpand\tabu@temp @% - \else !% - \fi\fi - {\noexpand\extracolsep\noexpand\@flushglue}}% - \fi - \tabu@temp -}% \tabu@extrac@lsep -%% Implementing the strategy ---------------------------------------- -\long\def\tabu@pream #1\@preamble {% - \let\tabu@ \tabu@@ \tabu@mkpreambuffer \tabu@aftergroupcleanup - \NC@list\expandafter {\tabu@NC@list}% in case of nesting... - \ifdefined\tabu@usetabu \tabu@usetabu \tabu@target \z@ \fi - \let\tabu@savedpreamble \@preamble - \global\let\tabu@elapsedtime \relax - \tabu@thebody ={#1\tabu@aftergroupcleanup}% - \tabu@thebody =\expandafter{\the\expandafter\tabu@thebody - \@preamble}% - \edef\tabuthepreamble {\the\tabu@thebody}% ( no @ allowed for \scantokens ) - \tabu@select -}% \tabu@pream -\long\def\tabu@longpream #1\LT@bchunk #2\LT@bchunk{% - \let\tabu@ \tabu@@ \tabu@mkpreambuffer \tabu@aftergroupcleanup - \NC@list\expandafter {\tabu@NC@list}% in case of nesting... - \let\tabu@savedpreamble \@preamble - \global\let\tabu@elapsedtime \relax - \tabu@thebody ={#1\LT@bchunk #2\tabu@aftergroupcleanup \LT@bchunk}% - \edef\tabuthepreamble {\the\tabu@thebody}% ( no @ allowed for \scantokens ) - \tabu@select -}% \tabu@longpream -\def\tabu@select {% - \ifnum\tabu@nested>\z@ \tabuscantokensfalse \fi - \ifnum \count@=\@ne \iftabu@measuring \count@=\tw@ \fi\fi - \ifcase \count@ - \global\let\tabu@elapsedtime \relax - \tabu@seteverycr - \expandafter \tabuthepreamble % vertical adjustment (inherited from outer) - \or % exit in vertical measure + struts per cell because no X and outer in mode 3 - \tabu@evr{\tabu@verticalinit}\tabu@celllalign@def{\tabu@verticalmeasure}% - \def\tabu@cellralign{\tabu@verticalspacing}% - \tabu@seteverycr - \expandafter \tabuthepreamble - \or % exit without measure because no X and outer in mode 4 - \tabu@evr{}\tabu@celllalign@def{}\let\tabu@cellralign \@empty - \tabu@seteverycr - \expandafter \tabuthepreamble - \else % needs trials - \tabu@evr{}\tabu@celllalign@def{}\let\tabu@cellralign \@empty - \tabu@savecounters - \expandafter \tabu@setstrategy - \fi -}% \tabu@select -\def\tabu@@ {\gdef\tabu@mkpreambuffer} -%% Protections to set up before trials ------------------------------ -\def\tabu@setstrategy {\begingroup % - \tabu@trialh@@k \tabu@cnt \z@ % number of trials - \hbadness \@M \let\hbadness \@tempcnta - \hfuzz \maxdimen \let\hfuzz \@tempdima - \let\write \tabu@nowrite\let\GenericError \tabu@GenericError - \let\savetabu \@gobble \let\tabudefaulttarget \linewidth - \let\@footnotetext \@gobble \let\@xfootnote \tabu@xfootnote - \let\color \tabu@nocolor\let\rowcolor \tabu@norowcolor - \let\tabu@aftergroupcleanup \relax % only after the last trial - \tabu@mkpreambuffer - \ifnum \count@>\thr@@ \let\@halignto \@empty \tabucolX@init - \def\tabu@lasttry{\m@ne\p@}\fi - \begingroup \iffalse{\fi \ifnum0=`}\fi - \toks@{}\def\tabu@stack{b}\iftabuscantokens \endlinechar=10 \obeyspaces \fi % - \tabu@collectbody \tabu@strategy % -}% \tabu@setstrategy -\def\tabu@savecounters{% - \def\@elt ##1{\csname c@##1\endcsname\the\csname c@##1\endcsname}% - \edef\tabu@clckpt {\begingroup \globaldefs=\@ne \cl@@ckpt \endgroup}\let\@elt \relax -}% \tabu@savecounters -\def\tabucolX@init {% \tabucolX <= \tabu@target / (sum coefs > 0) - \dimen@ \z@ \tabu@Xsum \z@ \tabucolX \z@ \let\tabu@ \tabu@Xinit \tabu@Xcoefs - \ifdim \dimen@>\z@ - \@tempdima \dimexpr \tabu@target *\p@/\dimen@ + \tabu@hfuzz\relax - \ifdim \tabucolX<\@tempdima \tabucolX \@tempdima \fi - \fi -}% \tabucolX@init -\def\tabu@Xinit #1#2{\tabu@Xcol #1 \advance \tabu@Xsum - \ifdim #2\p@>\z@ #2\p@ \advance\dimen@ #2\p@ - \else -#2\p@ \tabu@negcoeftrue - \@tempdima \dimexpr \tabu@target*\p@/\dimexpr-#2\p@\relax \relax - \ifdim \tabucolX<\@tempdima \tabucolX \@tempdima \fi - \tabu@wddef{#1}{0pt}% - \fi -}% \tabu@Xinit -%% Collecting the environment body ---------------------------------- -\long\def\tabu@collectbody #1#2\end #3{% - \edef\tabu@stack{\tabu@pushbegins #2\begin\end\expandafter\@gobble\tabu@stack}% - \ifx \tabu@stack\@empty - \toks@\expandafter{\expandafter\tabu@thebody\expandafter{\the\toks@ #2}% - \def\tabu@end@envir{\end{#3}}% - \iftabuscantokens - \iftabu@long \def\tabu@endenvir {\end{#3}\tabu@gobbleX}% - \else \def\tabu@endenvir {\let\endarray \@empty - \end{#3}\tabu@gobbleX}% - \fi - \else \def\tabu@endenvir {\end{#3}}\fi}% - \let\tabu@collectbody \tabu@endofcollect - \else\def\tabu@temp{#3}% - \ifx \tabu@temp\@empty \toks@\expandafter{\the\toks@ #2\end }% - \else \ifx\tabu@temp\tabu@@spxiii \toks@\expandafter{\the\toks@ #2\end #3}% - \else \ifx\tabu@temp\tabu@X \toks@\expandafter{\the\toks@ #2\end #3}% - \else \toks@\expandafter{\the\toks@ #2\end{#3}}% - \fi\fi\fi - \fi - \tabu@collectbody{#1}% -}% \tabu@collectbody -\long\def\tabu@pushbegins#1\begin#2{\ifx\end#2\else b\expandafter\tabu@pushbegins\fi}% -\def\tabu@endofcollect #1{\ifnum0=`{}\fi - \expandafter\endgroup \the\toks@ #1% -}% \tabu@endofcollect -%% The trials: switching between strategies ------------------------- -\def\tabu@strategy {\relax % stops \count@ assignment ! - \ifcase\count@ % case 0 = print with vertical adjustment (outer is finished) - \expandafter \tabu@endoftrials - \or % case 1 = exit in vertical measure (outer in mode 3) - \expandafter\xdef\csname tabu@\the\tabu@nested.T\endcsname{\the\tabu@target}% - \expandafter\xdef\csname tabu@\the\tabu@nested.X\endcsname{\the\tabucolX}% - \expandafter \tabu@endoftrials - \or % case 2 = exit with a rule replacing the table (outer in mode 4) - \expandafter \tabu@quickend - \or % case 3 = outer is in mode 3 because of no X - \begingroup - \tabu@evr{\tabu@verticalinit}\tabu@celllalign@def{\tabu@verticalmeasure}% - \def\tabu@cellralign{\tabu@verticalspacing}% - \expandafter \tabu@measuring - \else % case 4 = horizontal measure - \begingroup - \global\let\tabu@elapsedtime \tabu@message@etime - \long\def\multicolumn##1##2##3{\multispan{##1}}% - \let\tabu@startpboxORI \@startpbox - \iftabu@spread - \def\tabu@naturalXmax {\z@}% - \let\tabu@naturalXmin \tabu@naturalXmax - \tabu@evr{\global\tabu@naturalX \z@}% - \let\@startpbox \tabu@startpboxmeasure - \else\iftabu@negcoef - \let\@startpbox \tabu@startpboxmeasure - \else \let\@startpbox \tabu@startpboxquick - \fi\fi - \expandafter \tabu@measuring - \fi -}% \tabu@strategy -\def\tabu@measuring{\expandafter \tabu@trial \expandafter - \count@ \the\count@ \tabu@endtrial -}% \tabu@measuring -\def\tabu@trial{\iftabu@long \tabu@longtrial \else \tabu@shorttrial \fi} -\def\tabu@shorttrial {\setbox\tabu@box \hbox\bgroup \tabu@seteverycr - \ifx \tabu@savecounters\relax \else - \let\tabu@savecounters \relax \tabu@clckpt \fi - $\iftabuscantokens \tabu@rescan \else \expandafter\@secondoftwo \fi - \expandafter{\expandafter \tabuthepreamble - \the\tabu@thebody - \csname tabu@adl@endtrial\endcsname - \endarray}$\egroup % got \tabu@box -}% \tabu@shorttrial -\def\tabu@longtrial {\setbox\tabu@box \hbox\bgroup \tabu@seteverycr - \ifx \tabu@savecounters\relax \else - \let\tabu@savecounters \relax \tabu@clckpt \fi - \iftabuscantokens \tabu@rescan \else \expandafter\@secondoftwo \fi - \expandafter{\expandafter \tabuthepreamble - \the\tabu@thebody - \tabuendlongtrial}\egroup % got \tabu@box -}% \tabu@longtrial -\def\tabuendlongtrial{% no @ allowed for \scantokens - \LT@echunk \global\setbox\@ne \hbox{\unhbox\@ne}\kern\wd\@ne - \LT@get@widths -}% \tabuendlongtrial -\def\tabu@adl@endtrial{% - \crcr \noalign{\global\adl@ncol \tabu@nbcols}}% anything global is crap, junky and fails ! -\def\tabu@seteverycr {\tabu@reset - \everycr \expandafter{\the\everycr \tabu@everycr}% - \let\everycr \tabu@noeverycr % -}% \tabu@seteverycr -\def\tabu@noeverycr{{\aftergroup\tabu@restoreeverycr \afterassignment}\toks@} -\def\tabu@restoreeverycr {\let\everycr \tabu@@everycr} -\def\tabu@everycr {\iftabu@everyrow \noalign{\tabu@everyrow}\fi} -\def\tabu@endoftrials {% - \iftabuscantokens \expandafter\@firstoftwo - \else \expandafter\@secondoftwo - \fi - {\expandafter \tabu@closetrialsgroup \expandafter - \tabu@rescan \expandafter{% - \expandafter\tabuthepreamble - \the\expandafter\tabu@thebody - \iftabu@long \else \endarray \fi}} - {\expandafter\tabu@closetrialsgroup \expandafter - \tabuthepreamble - \the\tabu@thebody}% - \tabu@endenvir % Finish ! -}% \tabu@endoftrials -\def\tabu@closetrialsgroup {% - \toks@\expandafter{\tabu@endenvir}% - \edef\tabu@bufferX{\endgroup - \tabucolX \the\tabucolX - \tabu@target \the\tabu@target - \tabu@cnt \the\tabu@cnt - \def\noexpand\tabu@endenvir{\the\toks@}% - %Quid de \@halignto = \tabu@halignto ?? - }% \tabu@bufferX - \tabu@bufferX - \ifcase\tabu@nested % print out (outer in mode 0) - \global\tabu@cnt \tabu@cnt - \tabu@evr{\tabu@verticaldynamicadjustment}% - \tabu@celllalign@def{\everypar{}}\let\tabu@cellralign \@empty - \let\@finalstrut \tabu@finalstrut - \else % vertical measure of nested tabu - \tabu@evr{\tabu@verticalinit}% - \tabu@celllalign@def{\tabu@verticalmeasure}% - \def\tabu@cellralign{\tabu@verticalspacing}% - \fi - \tabu@clckpt \let\@halignto \tabu@halignto - \let\@halignto \@empty - \tabu@seteverycr - \ifdim \tabustrutrule>\z@ \ifnum\tabu@nested=\z@ - \setbox\@arstrutbox \box\voidb@x % force \@arstrutbox to be rebuilt (visible struts) - \fi\fi -}% \tabu@closetrialsgroup -\def\tabu@quickend {\expandafter \endgroup \expandafter - \tabu@target \the\tabu@target \tabu@quickrule - \let\endarray \relax \tabu@endenvir -}% \tabu@quickend -\def\tabu@endtrial {\relax % stops \count@ assignment ! - \ifcase \count@ \tabu@err % case 0 = impossible here - \or \tabu@err % case 1 = impossible here - \or \tabu@err % case 2 = impossible here - \or % case 3 = outer goes into mode 0 - \def\tabu@bufferX{\endgroup}\count@ \z@ - \else % case 4 = outer goes into mode 3 - \iftabu@spread \tabu@spreadarith % inner into mode 1 (outer in mode 3) - \else \tabu@arith % or 2 (outer in mode 4) - \fi - \count@=% - \ifcase\tabu@nested \thr@@ % outer goes into mode 3 - \else\iftabu@measuring \tw@ % outer is in mode 4 - \else \@ne % outer is in mode 3 - \fi\fi - \edef\tabu@bufferX{\endgroup - \tabucolX \the\tabucolX - \tabu@target \the\tabu@target}% - \fi - \expandafter \tabu@bufferX \expandafter - \count@ \the\count@ \tabu@strategy -}% \tabu@endtrial -\def\tabu@err{\errmessage{(tabu) Internal impossible error! (\count@=\the\count@)}} -%% The algorithms: compute the widths / stop or go on --------------- -\def\tabu@arithnegcoef {% - \@tempdima \z@ \dimen@ \z@ \let\tabu@ \tabu@arith@negcoef \tabu@Xcoefs -}% \tabu@arithnegcoef -\def\tabu@arith@negcoef #1#2{% - \ifdim #2\p@>\z@ \advance\dimen@ #2\p@ % saturated by definition - \advance\@tempdima #2\tabucolX - \else - \ifdim -#2\tabucolX <\tabu@wd{#1}% c_i X < natural width <= \tabu@target-> saturated - \advance\dimen@ -#2\p@ - \advance\@tempdima -#2\tabucolX - \else - \advance\@tempdima \tabu@wd{#1}% natural width <= c_i X => neutralised - \ifdim \tabu@wd{#1}<\tabu@target \else % neutralised - \advance\dimen@ -#2\p@ % saturated (natural width = tabu@target) - \fi - \fi - \fi -}% \tabu@arith@negcoef -\def\tabu@givespace #1#2{% here \tabu@DELTA < \z@ - \ifdim \@tempdima=\z@ - \tabu@wddef{#1}{\the\dimexpr -\tabu@DELTA*\p@/\tabu@Xsum}% - \else - \tabu@wddef{#1}{\the\dimexpr \tabu@hsize{#1}{#2} - *(\p@ -\tabu@DELTA*\p@/\@tempdima)/\p@\relax}% - \fi -}% \tabu@givespace -\def\tabu@arith {\advance\tabu@cnt \@ne - \ifnum \tabu@cnt=\@ne \tabu@message{\tabu@titles}\fi - \tabu@arithnegcoef - \@tempdimb \dimexpr \wd\tabu@box -\@tempdima \relax % - \tabu@DELTA = \dimexpr \wd\tabu@box - \tabu@target \relax - \tabu@message{\tabu@message@arith}% - \ifdim \tabu@DELTA <\tabu@hfuzz - \ifdim \tabu@DELTA<\z@ % wd (tabu)<\tabu@target ? - \let\tabu@ \tabu@givespace \tabu@Xcoefs - \advance\@tempdima \@tempdimb \advance\@tempdima -\tabu@DELTA % for message - \else % already converged: nothing to do but nearly impossible... - \fi - \tabucolX \maxdimen - \tabu@measuringfalse - \else % need for narrower X columns - \tabucolX =\dimexpr (\@tempdima -\tabu@DELTA) *\p@/\tabu@Xsum \relax - \tabu@measuringtrue - \@whilesw \iftabu@measuring\fi {% - \advance\tabu@cnt \@ne - \tabu@arithnegcoef - \tabu@DELTA =\dimexpr \@tempdima+\@tempdimb -\tabu@target \relax % always < 0 here - \tabu@message{\tabu@header - \tabu@msgalign \tabucolX { }{ }{ }{ }{ }\@@ - \tabu@msgalign \@tempdima+\@tempdimb { }{ }{ }{ }{ }\@@ - \tabu@msgalign \tabu@target { }{ }{ }{ }{ }\@@ - \tabu@msgalign@PT \dimen@ { }{}{}{}{}{}{}\@@ - \ifdim -\tabu@DELTA<\tabu@hfuzz \tabu@spaces target ok\else - \tabu@msgalign \dimexpr -\tabu@DELTA *\p@/\dimen@ {}{}{}{}{}\@@ - \fi}% - \ifdim -\tabu@DELTA<\tabu@hfuzz - \advance\@tempdima \@tempdimb % for message - \tabu@measuringfalse - \else - \advance\tabucolX \dimexpr -\tabu@DELTA *\p@/\dimen@ \relax - \fi - }% - \fi - \tabu@message{\tabu@message@reached}% - \edef\tabu@bufferX{\endgroup \tabu@cnt \the\tabu@cnt - \tabucolX \the\tabucolX - \tabu@target \the\tabu@target}% -}% \tabu@arith -\def\tabu@spreadarith {% - \dimen@ \z@ \@tempdima \tabu@naturalXmax \let\tabu@ \tabu@spread@arith \tabu@Xcoefs - \edef\tabu@naturalXmin {\the\dimexpr\tabu@naturalXmin*\dimen@/\p@}% - \@tempdimc =\dimexpr \wd\tabu@box -\tabu@naturalXmax+\tabu@naturalXmin \relax - \iftabu@measuring - \tabu@target =\dimexpr \@tempdimc+\tabu@spreadtarget \relax - \edef\tabu@bufferX{\endgroup \tabucolX \the\tabucolX \tabu@target\the\tabu@target}% - \else - \tabu@message{\tabu@message@spreadarith}% - \ifdim \dimexpr \@tempdimc+\tabu@spreadtarget >\tabu@target - \tabu@message{(tabu) spread - \ifdim \@tempdimc>\tabu@target useless here: default target used% - \else too large: reduced to fit default target\fi.}% - \else - \tabu@target =\dimexpr \@tempdimc+\tabu@spreadtarget \relax - \tabu@message{(tabu) spread: New target set to \the\tabu@target^^J}% - \fi - \begingroup \let\tabu@wddef \@gobbletwo - \@tempdimb \@tempdima - \tabucolX@init - \tabu@arithnegcoef - \wd\tabu@box =\dimexpr \wd\tabu@box +\@tempdima-\@tempdimb \relax - \expandafter\endgroup \expandafter\tabucolX \the\tabucolX - \tabu@arith - \fi -}% \tabu@spreadarith -\def\tabu@spread@arith #1#2{% - \ifdim #2\p@>\z@ \advance\dimen@ #2\p@ - \else \advance\@tempdima \tabu@wd{#1}\relax - \fi -}% \tabu@spread@arith -%% Reporting in the .log file --------------------------------------- -\def\tabu@message@defaulttarget{% - \ifnum\tabu@nested=\z@^^J(tabu) Default target: - \ifx\tabudefaulttarget\linewidth \string\linewidth - \ifdim \tabu@thetarget=\linewidth \else - -\the\dimexpr\linewidth-\tabu@thetarget\fi = - \else\ifx\tabudefaulttarget\linegoal\string\linegoal= - \fi\fi - \else (tabu) Default target (nested): \fi - \the\tabu@target \on@line - \ifnum\tabu@nested=\z@ , page \the\c@page\fi} -\def\tabu@message@target {^^J(tabu) Target specified: - \the\tabu@target \on@line, page \the\c@page} -\def\tabu@message@arith {\tabu@header - \tabu@msgalign \tabucolX { }{ }{ }{ }{ }\@@ - \tabu@msgalign \wd\tabu@box { }{ }{ }{ }{ }\@@ - \tabu@msgalign \tabu@target { }{ }{ }{ }{ }\@@ - \tabu@msgalign@PT \dimen@ { }{}{}{}{}{}{}\@@ - \ifdim \tabu@DELTA<\tabu@hfuzz giving space\else - \tabu@msgalign \dimexpr (\@tempdima-\tabu@DELTA) *\p@/\tabu@Xsum -\tabucolX {}{}{}{}{}\@@ - \fi -}% \tabu@message@arith -\def\tabu@message@spreadarith {\tabu@spreadheader - \tabu@msgalign \tabu@spreadtarget { }{ }{ }{ }{}\@@ - \tabu@msgalign \wd\tabu@box { }{ }{ }{ }{}\@@ - \tabu@msgalign -\tabu@naturalXmax { }{}{}{}{}\@@ - \tabu@msgalign \tabu@naturalXmin { }{ }{ }{ }{}\@@ - \tabu@msgalign \ifdim \dimexpr\@tempdimc>\tabu@target \tabu@target - \else \@tempdimc+\tabu@spreadtarget \fi - {}{}{}{}{}\@@} -\def\tabu@message@negcoef #1#2{ - \tabu@spaces\tabu@spaces\space * #1. X[\rem@pt#2]: - \space width = \tabu@wd {#1} - \expandafter\string\csname tabu@\the\tabu@nested.W\number#1\endcsname - \ifdim -\tabu@pt#2\tabucolX<\tabu@target - < \number-\rem@pt#2 X - = \the\dimexpr -\tabu@pt#2\tabucolX \relax - \else - <= \the\tabu@target\space < \number-\rem@pt#2 X\fi} -\def\tabu@message@reached{\tabu@header - ******* Reached Target: - hfuzz = \tabu@hfuzz\on@line\space *******} -\def\tabu@message@etime{\edef\tabu@stoptime{\the\pdfelapsedtime}% - \tabu@message{(tabu)\tabu@spaces Time elapsed during measure: - \the\numexpr(\tabu@stoptime-\tabu@starttime-32767)/65536\relax sec - \the\numexpr\numexpr(\tabu@stoptime-\tabu@starttime) - -\numexpr(\tabu@stoptime-\tabu@starttime-32767)/65536\relax*65536\relax - *1000/65536\relax ms \tabu@spaces(\the\tabu@cnt\space - cycle\ifnum\tabu@cnt>\@ne s\fi)^^J^^J}} -\def\tabu@message@verticalsp {% - \ifdim \@tempdima>\tabu@ht - \ifdim \@tempdimb>\tabu@dp - \expandafter\expandafter\expandafter\string\tabu@ht = - \tabu@msgalign \@tempdima { }{ }{ }{ }{ }\@@ - \expandafter\expandafter\expandafter\string\tabu@dp = - \tabu@msgalign \@tempdimb { }{ }{ }{ }{ }\@@^^J% - \else - \expandafter\expandafter\expandafter\string\tabu@ht = - \tabu@msgalign \@tempdima { }{ }{ }{ }{ }\@@^^J% - \fi - \else\ifdim \@tempdimb>\tabu@dp - \tabu@spaces\tabu@spaces\tabu@spaces - \expandafter\expandafter\expandafter\string\tabu@dp = - \tabu@msgalign \@tempdimb { }{ }{ }{ }{ }\@@^^J\fi - \fi -}% \tabu@message@verticalsp -\edef\tabu@spaces{\@spaces} -\def\tabu@strippt{\expandafter\tabu@pt\the} -{\@makeother\P \@makeother\T\lowercase{\gdef\tabu@pt #1PT{#1}}} -\def\tabu@msgalign{\expandafter\tabu@msg@align\the\dimexpr} -\def\tabu@msgalign@PT{\expandafter\tabu@msg@align\romannumeral-`\0\tabu@strippt} -\def\do #1{% - \def\tabu@msg@align##1.##2##3##4##5##6##7##8##9\@@{% - \ifnum##1<10 #1 #1\else - \ifnum##1<100 #1 \else - \ifnum##1<\@m #1\fi\fi\fi - ##1.##2##3##4##5##6##7##8#1}% - \def\tabu@header{(tabu) \ifnum\tabu@cnt<10 #1\fi\the\tabu@cnt) }% - \def\tabu@titles{\ifnum \tabu@nested=\z@ - (tabu) Try#1 #1 tabu X #1 #1 #1tabu Width #1 #1 Target - #1 #1 #1 Coefs #1 #1 #1 Update^^J\fi}% - \def\tabu@spreadheader{% - (tabu) Try#1 #1 Spread #1 #1 tabu Width #1 #1 #1 Nat. X #1 #1 #1 #1Nat. Min. - #1 New Target^^J% - (tabu) sprd} - \def\tabu@message@save {\begingroup - \def\x ####1{\tabu@msg@align ####1{ }{ }{ }{ }{}\@@} - \def\z ####1{\expandafter\x\expandafter{\romannumeral-`\0\tabu@strippt - \dimexpr####1\p@{ }{ }}}% - \let\color \relax \def\tabu@rulesstyle ####1####2{\detokenize{####1}}% - \let\CT@arc@ \relax \let\@preamble \@gobble - \let\tabu@savedpream \@firstofone - \let\tabu@savedparams \@firstofone - \def\tabu@target ####1\relax {(tabu) target #1 #1 #1 #1 #1 = \x{####1}^^J}% - \def\tabucolX ####1\relax {(tabu) X columns width#1 = \x{####1}^^J}% - \def\tabu@nbcols ####1\relax {(tabu) Number of columns: \z{####1}^^J}% - \def\tabu@aligndefault ####1{(tabu) Default alignment: #1 #1 ####1^^J}% - \def\col@sep ####1\relax {(tabu) column sep #1 #1 #1 = \x{####1}^^J}% - \def\arrayrulewidth ####1\relax{(tabu) arrayrulewidth #1 = \x{####1}}% - \def\doublerulesep ####1\relax { doublerulesep = \x{####1}^^J}% - \def\extratabsurround####1\relax{(tabu) extratabsurround = \x{####1}^^J}% - \def\extrarowheight ####1\relax{(tabu) extrarowheight #1 = \x{####1}}% - \def\extrarowdepth ####1\relax {extrarowdepth = \x{####1}^^J}% - \def\abovetabulinesep####1\relax{(tabu) abovetabulinesep=\x{####1} }% - \def\belowtabulinesep####1\relax{ belowtabulinesep=\x{####1}^^J}% - \def\arraystretch ####1{(tabu) arraystretch #1 #1 = \z{####1}^^J}% - \def\minrowclearance####1\relax{(tabu) minrowclearance #1 = \x{####1}^^J}% - \def\tabu@arc@L ####1{(tabu) taburulecolor #1 #1 = ####1^^J}% - \def\tabu@drsc@L ####1{(tabu) tabudoublerulecolor= ####1^^J}% - \def\tabu@evr@L ####1{(tabu) everyrow #1 #1 #1 #1 = \detokenize{####1}^^J}% - \def\tabu@ls@L ####1{(tabu) line style = \detokenize{####1}^^J}% - \def\NC@find ####1\@nil{(tabu) tabu preamble#1 #1 = \detokenize{####1}^^J}% - \def\tabu@wddef####1####2{(tabu) Natural width ####1 = \x{####2}^^J}% - \let\edef \@gobbletwo \let\def \@empty \let\let \@gobbletwo - \tabu@message{% - (tabu) \string\savetabu{\tabu@temp}: \on@line^^J% - \tabu@usetabu \@nil^^J}% - \endgroup} -}\do{ } -%% Measuring the natural width (varwidth) - store the results ------- -\def\tabu@startpboxmeasure #1{\bgroup % entering \vtop - \edef\tabu@temp{\expandafter\@secondoftwo \ifx\tabu@hsize #1\else\relax\fi}% - \ifodd 1\ifx \tabu@temp\@empty 0 \else % starts with \tabu@hsize ? - \iftabu@spread \else % if spread -> measure - \ifdim \tabu@temp\p@>\z@ 0 \fi\fi\fi% if coef>0 -> do not measure - \let\@startpbox \tabu@startpboxORI % restore immediately (nesting) - \tabu@measuringtrue % for the quick option... - \tabu@Xcol =\expandafter\@firstoftwo\ifx\tabu@hsize #1\fi - \ifdim \tabu@temp\p@>\z@ \ifdim \tabu@temp\tabucolX<\tabu@target - \tabu@target=\tabu@temp\tabucolX \fi\fi - \setbox\tabu@box \hbox \bgroup - \begin{varwidth}\tabu@target - \let\FV@ListProcessLine \tabu@FV@ListProcessLine % \hbox to natural width... - \narrowragged \arraybackslash \parfillskip \@flushglue - \ifdefined\pdfadjustspacing \pdfadjustspacing\z@ \fi - \bgroup \aftergroup\tabu@endpboxmeasure - \ifdefined \cellspacetoplimit \tabu@cellspacepatch \fi - \else \expandafter\@gobble - \tabu@startpboxquick{#1}% \@gobble \bgroup - \fi -}% \tabu@startpboxmeasure -\def\tabu@cellspacepatch{\def\bcolumn##1\@nil{}\let\ecolumn\@empty - \bgroup\color@begingroup} -\def\tabu@endpboxmeasure {% - \@finalstrut \@arstrutbox - \end{varwidth}\egroup % - \ifdim \tabu@temp\p@ <\z@ % neg coef - \ifdim \tabu@wd\tabu@Xcol <\wd\tabu@box - \tabu@wddef\tabu@Xcol {\the\wd\tabu@box}% - \tabu@debug{\tabu@message@endpboxmeasure}% - \fi - \else % spread coef>0 - \global\advance \tabu@naturalX \wd\tabu@box - \@tempdima =\dimexpr \wd\tabu@box *\p@/\dimexpr \tabu@temp\p@\relax \relax - \ifdim \tabu@naturalXmax <\tabu@naturalX - \xdef\tabu@naturalXmax {\the\tabu@naturalX}\fi - \ifdim \tabu@naturalXmin <\@tempdima - \xdef\tabu@naturalXmin {\the\@tempdima}\fi - \fi - \box\tabu@box \egroup % end of \vtop (measure) restore \tabu@target -}% \tabu@endpboxmeasure -\def\tabu@wddef #1{\expandafter\xdef - \csname tabu@\the\tabu@nested.W\number#1\endcsname} -\def\tabu@wd #1{\csname tabu@\the\tabu@nested.W\number#1\endcsname} -\def\tabu@message@endpboxmeasure{\tabu@spaces\tabu@spaces<-> % <-> save natural wd - \the\tabu@Xcol. X[\tabu@temp]: - target = \the\tabucolX \space - \expandafter\expandafter\expandafter\string\tabu@wd\tabu@Xcol - =\tabu@wd\tabu@Xcol -}% \tabu@message@endpboxmeasure -\def\tabu@startpboxquick {\bgroup - \let\@startpbox \tabu@startpboxORI % restore immediately - \let\tabu \tabu@quick % \begin is expanded before... - \expandafter\@gobble \@startpbox % gobbles \bgroup -}% \tabu@startpboxquick -\def\tabu@quick {\begingroup \iffalse{\fi \ifnum0=`}\fi - \toks@{}\def\tabu@stack{b}\tabu@collectbody \tabu@endquick -}% \tabu@quick -\def\tabu@endquick {% - \ifodd 1\ifx\tabu@end@envir\tabu@endtabu \else - \ifx\tabu@end@envir\tabu@endtabus \else 0\fi\fi\relax - \endgroup - \else \let\endtabu \relax - \tabu@end@envir - \fi -}% \tabu@quick -\def\tabu@endtabu {\end{tabu}} -\def\tabu@endtabus {\end{tabu*}} -%% Measuring the heights and depths - store the results ------------- -\def\tabu@verticalmeasure{\everypar{}% - \ifnum \currentgrouptype>12 % 14=semi-simple, 15=math shift group - \setbox\tabu@box =\hbox\bgroup - \let\tabu@verticalspacing \tabu@verticalsp@lcr - \d@llarbegin % after \hbox ... - \else - \edef\tabu@temp{\ifnum\currentgrouptype=5\vtop - \else\ifnum\currentgrouptype=12\vcenter - \else\vbox\fi\fi}% - \setbox\tabu@box \hbox\bgroup$\tabu@temp \bgroup - \let\tabu@verticalspacing \tabu@verticalsp@pmb - \fi -}% \tabu@verticalmeasure -\def\tabu@verticalsp@lcr{% - \d@llarend \egroup % - \@tempdima \dimexpr \ht\tabu@box+\abovetabulinesep - \@tempdimb \dimexpr \dp\tabu@box+\belowtabulinesep \relax - \ifdim\tabustrutrule>\z@ \tabu@debug{\tabu@message@verticalsp}\fi - \ifdim \tabu@ht<\@tempdima \tabu@htdef{\the\@tempdima}\fi - \ifdim \tabu@dp<\@tempdimb \tabu@dpdef{\the\@tempdimb}\fi - \noindent\vrule height\@tempdima depth\@tempdimb -}% \tabu@verticalsp@lcr -\def\tabu@verticalsp@pmb{% inserts struts as needed - \par \expandafter\egroup - \expandafter$\expandafter - \egroup \expandafter - \@tempdimc \the\prevdepth - \@tempdima \dimexpr \ht\tabu@box+\abovetabulinesep - \@tempdimb \dimexpr \dp\tabu@box+\belowtabulinesep \relax - \ifdim\tabustrutrule>\z@ \tabu@debug{\tabu@message@verticalsp}\fi - \ifdim \tabu@ht<\@tempdima \tabu@htdef{\the\@tempdima}\fi - \ifdim \tabu@dp<\@tempdimb \tabu@dpdef{\the\@tempdimb}\fi - \let\@finalstrut \@gobble - \hrule height\@tempdima depth\@tempdimb width\hsize -%% \box\tabu@box -}% \tabu@verticalsp@pmb - -\def\tabu@verticalinit{% - \ifnum \c@taburow=\z@ \tabu@rearstrut \fi % after \tabu@reset ! - \advance\c@taburow \@ne - \tabu@htdef{\the\ht\@arstrutbox}\tabu@dpdef{\the\dp\@arstrutbox}% - \advance\c@taburow \m@ne -}% \tabu@verticalinit -\def\tabu@htdef {\expandafter\xdef \csname tabu@\the\tabu@nested.H\the\c@taburow\endcsname} -\def\tabu@ht {\csname tabu@\the\tabu@nested.H\the\c@taburow\endcsname} -\def\tabu@dpdef {\expandafter\xdef \csname tabu@\the\tabu@nested.D\the\c@taburow\endcsname} -\def\tabu@dp {\csname tabu@\the\tabu@nested.D\the\c@taburow\endcsname} -\def\tabu@verticaldynamicadjustment {% - \advance\c@taburow \@ne - \extrarowheight \dimexpr\tabu@ht - \ht\strutbox - \extrarowdepth \dimexpr\tabu@dp - \dp\strutbox - \let\arraystretch \@empty - \advance\c@taburow \m@ne -}% \tabu@verticaldynamicadjustment -\def\tabuphantomline{\crcr \noalign{% - {\globaldefs \@ne - \setbox\@arstrutbox \box\voidb@x - \let\tabu@@celllalign \tabu@celllalign - \let\tabu@@cellralign \tabu@cellralign - \let\tabu@@cellleft \tabu@cellleft - \let\tabu@@cellright \tabu@cellright - \let\tabu@@thevline \tabu@thevline - \let\tabu@celllalign \@empty - \let\tabu@cellralign \@empty - \let\tabu@cellright \@empty - \let\tabu@cellleft \@empty - \let\tabu@thevline \relax}% - \edef\tabu@temp{\tabu@multispan \tabu@nbcols{\noindent &}}% - \toks@\expandafter{\tabu@temp \noindent\tabu@everyrowfalse \cr - \noalign{\tabu@rearstrut - {\globaldefs\@ne - \let\tabu@celllalign \tabu@@celllalign - \let\tabu@cellralign \tabu@@cellralign - \let\tabu@cellleft \tabu@@cellleft - \let\tabu@cellright \tabu@@cellright - \let\tabu@thevline \tabu@@thevline}}}% - \expandafter}\the\toks@ -}% \tabuphantomline -%% \firsthline and \lasthline corrections --------------------------- -\def\tabu@firstline {\tabu@hlineAZ \tabu@firsthlinecorrection {}} -\def\tabu@firsthline{\tabu@hlineAZ \tabu@firsthlinecorrection \hline} -\def\tabu@lastline {\tabu@hlineAZ \tabu@lasthlinecorrection {}} -\def\tabu@lasthline {\tabu@hlineAZ \tabu@lasthlinecorrection \hline} -\def\tabu@hline {% replaces \hline if no colortbl (see \AtBeginDocument) - \noalign{\ifnum0=`}\fi - {\CT@arc@\hrule height\arrayrulewidth}% - \futurelet \tabu@temp \tabu@xhline -}% \tabu@hline -\def\tabu@xhline{% - \ifx \tabu@temp \hline - {\ifx \CT@drsc@\relax \vskip - \else\ifx \CT@drsc@\@empty \vskip - \else \CT@drsc@\hrule height - \fi\fi - \doublerulesep}% - \fi - \ifnum0=`{\fi}% -}% \tabu@xhline -\def\tabu@hlineAZ #1#2{\noalign{\ifnum0=`}\fi \dimen@ \z@ \count@ \z@ - \toks@{}\def\tabu@hlinecorrection{#1}\def\tabu@temp{#2}% - \tabu@hlineAZsurround -}% \tabu@hlineAZ -\newcommand*\tabu@hlineAZsurround[1][\extratabsurround]{% - \extratabsurround #1\let\tabucline \tabucline@scan - \let\hline \tabu@hlinescan \let\firsthline \hline - \let\cline \tabu@clinescan \let\lasthline \hline - \expandafter \futurelet \expandafter \tabu@temp - \expandafter \tabu@nexthlineAZ \tabu@temp -}% \tabu@hlineAZsurround -\def\tabu@hlinescan {\tabu@thick \arrayrulewidth \tabu@xhlineAZ \hline} -\def\tabu@clinescan #1{\tabu@thick \arrayrulewidth \tabu@xhlineAZ {\cline{#1}}} -\def\tabucline@scan{\@testopt \tabucline@sc@n {}} -\def\tabucline@sc@n #1[#2]{\tabu@xhlineAZ {\tabucline[{#1}]{#2}}} -\def\tabu@nexthlineAZ{% - \ifx \tabu@temp\hline \else - \ifx \tabu@temp\cline \else - \ifx \tabu@temp\tabucline \else - \tabu@hlinecorrection - \fi\fi\fi -}% \tabu@nexthlineAZ -\def\tabu@xhlineAZ #1{% - \toks@\expandafter{\the\toks@ #1}% - \@tempdimc \tabu@thick % The last line width - \ifcase\count@ \@tempdimb \tabu@thick % The first line width - \else \advance\dimen@ \dimexpr \tabu@thick+\doublerulesep \relax - \fi - \advance\count@ \@ne \futurelet \tabu@temp \tabu@nexthlineAZ -}% \tabu@xhlineAZ -\def\tabu@firsthlinecorrection{% \count@ = number of \hline -1 - \@tempdima \dimexpr \ht\@arstrutbox+\dimen@ - \edef\firsthline{% - \omit \hbox to\z@{\hss{\noexpand\tabu@DBG{yellow}\vrule - height \the\dimexpr\@tempdima+\extratabsurround - depth \dp\@arstrutbox - width \tabustrutrule}\hss}\cr - \noalign{\vskip -\the\dimexpr \@tempdima+\@tempdimb - +\dp\@arstrutbox \relax}% - \the\toks@ - }\ifnum0=`{\fi - \expandafter}\firsthline % we are then ! -}% \tabu@firsthlinecorrection -\def\tabu@lasthlinecorrection{% - \@tempdima \dimexpr \dp\@arstrutbox+\dimen@+\@tempdimb+\@tempdimc - \edef\lasthline{% - \the\toks@ - \noalign{\vskip -\the\dimexpr\dimen@+\@tempdimb+\dp\@arstrutbox}% - \omit \hbox to\z@{\hss{\noexpand\tabu@DBG{yellow}\vrule - depth \the\dimexpr \dp\@arstrutbox+\@tempdimb+\dimen@ - +\extratabsurround-\@tempdimc - height \z@ - width \tabustrutrule}\hss}\cr - }\ifnum0=`{\fi - \expandafter}\lasthline % we are then ! -}% \tabu@lasthlinecorrection -\def\tabu@LT@@hline{% - \ifx\LT@next\hline - \global\let\LT@next \@gobble - \ifx \CT@drsc@\relax - \gdef\CT@LT@sep{% - \noalign{\penalty-\@medpenalty\vskip\doublerulesep}}% - \else - \gdef\CT@LT@sep{% - \multispan\LT@cols{% - \CT@drsc@\leaders\hrule\@height\doublerulesep\hfill}\cr}% - \fi - \else - \global\let\LT@next\empty - \gdef\CT@LT@sep{% - \noalign{\penalty-\@lowpenalty\vskip-\arrayrulewidth}}% - \fi - \ifnum0=`{\fi}% - \multispan\LT@cols - {\CT@arc@\leaders\hrule\@height\arrayrulewidth\hfill}\cr - \CT@LT@sep - \multispan\LT@cols - {\CT@arc@\leaders\hrule\@height\arrayrulewidth\hfill}\cr - \noalign{\penalty\@M}% - \LT@next -}% \tabu@LT@@hline -%% Horizontal lines : \tabucline ------------------------------------ -\let\tabu@start \@tempcnta -\let\tabu@stop \@tempcntb -\newcommand*\tabucline{\noalign{\ifnum0=`}\fi \tabu@cline} -\newcommand*\tabu@cline[2][]{\tabu@startstop{#2}% - \ifnum \tabu@stop<\z@ \toks@{}% - \else \tabu@clinearg{#1}\tabu@thestyle - \edef\tabucline{\toks@{% - \ifnum \tabu@start>\z@ \omit - \tabu@multispan\tabu@start {\span\omit}&\fi - \omit \tabu@multispan\tabu@stop {\span\omit}% - \tabu@thehline\cr - }}\tabucline - \tabu@tracinglines{(tabu:tabucline) Style: #1^^J\the\toks@^^J^^J}% - \fi - \futurelet \tabu@temp \tabu@xcline -}% \tabu@cline -\def\tabu@clinearg #1{% - \ifx\\#1\\\let\tabu@thestyle \tabu@ls@ - \else \@defaultunits \expandafter\let\expandafter\@tempa - \romannumeral-`\0#1\relax \@nnil - \ifx \hbox\@tempa \tabu@clinebox{#1}% - \else\ifx \box\@tempa \tabu@clinebox{#1}% - \else\ifx \vbox\@tempa \tabu@clinebox{#1}% - \else\ifx \vtop\@tempa \tabu@clinebox{#1}% - \else\ifx \copy\@tempa \tabu@clinebox{#1}% - \else\ifx \leaders\@tempa \tabu@clineleads{#1}% - \else\ifx \cleaders\@tempa \tabu@clineleads{#1}% - \else\ifx \xleaders\@tempa \tabu@clineleads{#1}% - \else\tabu@getline {#1}% - \fi\fi\fi\fi\fi\fi\fi\fi - \fi -}% \tabu@clinearg -\def\tabu@clinebox #1{\tabu@clineleads{\xleaders#1\hss}} -\def\tabu@clineleads #1{% - \let\tabu@thestyle \relax \let\tabu@leaders \@undefined - \gdef\tabu@thehrule{#1}} -\def\tabu@thehline{\begingroup - \ifdefined\tabu@leaders - \noexpand\tabu@thehleaders - \else \noexpand\tabu@thehrule - \fi \endgroup -}% \tabu@thehline -\def\tabu@xcline{% - \ifx \tabu@temp\tabucline - \toks@\expandafter{\the\toks@ \noalign - {\ifx\CT@drsc@\relax \vskip - \else \CT@drsc@\hrule height - \fi - \doublerulesep}}% - \fi - \tabu@docline -}% \tabu@xcline -\def\tabu@docline {\ifnum0=`{\fi \expandafter}\the\toks@} -\def\tabu@docline@evr {\xdef\tabu@doclineafter{\the\toks@}% - \ifnum0=`{\fi}\aftergroup\tabu@doclineafter} -\def\tabu@multispan #1#2{% - \ifnum\numexpr#1>\@ne #2\expandafter\tabu@multispan - \else \expandafter\@gobbletwo - \fi {#1-1}{#2}% -}% \tabu@multispan -\def\tabu@startstop #1{\tabu@start@stop #1\relax 1-\tabu@nbcols \@nnil} -\def\tabu@start@stop #1-#2\@nnil{% - \@defaultunits \tabu@start\number 0#1\relax \@nnil - \@defaultunits \tabu@stop \number 0#2\relax \@nnil - \tabu@stop \ifnum \tabu@start>\tabu@nbcols \m@ne - \else\ifnum \tabu@stop=\z@ \tabu@nbcols - \else\ifnum \tabu@stop>\tabu@nbcols \tabu@nbcols - \else \tabu@stop - \fi\fi\fi - \advance\tabu@start \m@ne - \ifnum \tabu@start>\z@ \advance\tabu@stop -\tabu@start \fi -}% \tabu@start@stop -%% Numbers: siunitx S columns (and \tabudecimal) ------------------- -\def\tabu@tabudecimal #1{% - \def\tabu@decimal{#1}\@temptokena{}% - \let\tabu@getdecimal@ \tabu@getdecimal@ignorespaces - \tabu@scandecimal -}% \tabu@tabudecimal -\def\tabu@scandecimal{\futurelet \tabu@temp \tabu@getdecimal@} -\def\tabu@skipdecimal#1{#1\tabu@scandecimal} -\def\tabu@getdecimal@ignorespaces{% - \ifcase 0\ifx\tabu@temp\ignorespaces\else - \ifx\tabu@temp\@sptoken1\else - 2\fi\fi\relax - \let\tabu@getdecimal@ \tabu@getdecimal - \expandafter\tabu@skipdecimal - \or \expandafter\tabu@gobblespace\expandafter\tabu@scandecimal - \else \expandafter\tabu@skipdecimal - \fi -}% \tabu@getdecimal@ignorespaces -\def\tabu@get@decimal#1{\@temptokena\expandafter{\the\@temptokena #1}% - \tabu@scandecimal} -\def\do#1{% - \def\tabu@get@decimalspace#1{% - \@temptokena\expandafter{\the\@temptokena #1}\tabu@scandecimal}% -}\do{ } -\let\tabu@@tabudecimal \tabu@tabudecimal -\def\tabu@getdecimal{% - \ifcase 0\ifx 0\tabu@temp\else - \ifx 1\tabu@temp\else - \ifx 2\tabu@temp\else - \ifx 3\tabu@temp\else - \ifx 4\tabu@temp\else - \ifx 5\tabu@temp\else - \ifx 6\tabu@temp\else - \ifx 7\tabu@temp\else - \ifx 8\tabu@temp\else - \ifx 9\tabu@temp\else - \ifx .\tabu@temp\else - \ifx ,\tabu@temp\else - \ifx -\tabu@temp\else - \ifx +\tabu@temp\else - \ifx e\tabu@temp\else - \ifx E\tabu@temp\else - \ifx\tabu@cellleft\tabu@temp1\else - \ifx\ignorespaces\tabu@temp1\else - \ifx\@sptoken\tabu@temp2\else - 3\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\relax - \expandafter\tabu@get@decimal - \or \expandafter\tabu@skipdecimal - \or \expandafter\tabu@get@decimalspace - \else\expandafter\tabu@printdecimal - \fi -}% \tabu@getdecimal -\def\tabu@printdecimal{% - \edef\tabu@temp{\the\@temptokena}% - \ifx\tabu@temp\@empty\else - \ifx\tabu@temp\space\else - \expandafter\tabu@decimal\expandafter{\the\@temptokena}% - \fi\fi -}% \tabu@printdecimal -%% Verbatim inside X columns ---------------------------------------- -\def\tabu@verbatim{% - \let\verb \tabu@verb - \let\FV@DefineCheckEnd \tabu@FV@DefineCheckEnd -}% \tabu@verbatim -\let\tabu@ltx@verb \verb -\def\tabu@verb{\@ifstar {\tabu@ltx@verb*} \tabu@ltx@verb} -\def\tabu@fancyvrb {% - \def\tabu@FV@DefineCheckEnd ##1{% - \def\tabu@FV@DefineCheckEnd{% - ##1% - \let\FV@CheckEnd \tabu@FV@CheckEnd - \let\FV@@CheckEnd \tabu@FV@@CheckEnd - \let\FV@@@CheckEnd \tabu@FV@@@CheckEnd - \edef\FV@EndScanning{% - \def\noexpand\next{\noexpand\end{\FV@EnvironName}}% - \global\let\noexpand\FV@EnvironName\relax - \noexpand\next}% - \xdef\FV@EnvironName{\detokenize\expandafter{\FV@EnvironName}}}% - }\expandafter\tabu@FV@DefineCheckEnd\expandafter{\FV@DefineCheckEnd} -}% \tabu@fancyvrb -\def\tabu@FV@CheckEnd #1{\expandafter\FV@@CheckEnd \detokenize{#1\end{}}\@nil} -\edef\tabu@FV@@@CheckEnd {\detokenize{\end{}}} -\begingroup -\catcode`\[1 \catcode`\]2 -\@makeother\{ \@makeother\} - \edef\x[\endgroup - \def\noexpand\tabu@FV@@CheckEnd ##1\detokenize[\end{]##2\detokenize[}]##3% - ]\x \@nil{\def\@tempa{#2}\def\@tempb{#3}} -\def\tabu@FV@ListProcessLine #1{% - \hbox {%to \hsize{% - \kern\leftmargin - \hbox {%to \linewidth{% - \FV@LeftListNumber - \FV@LeftListFrame - \FancyVerbFormatLine{#1}\hss -%% DG/SR modification begin - Jan. 28, 1998 (for numbers=right add-on) -%% \FV@RightListFrame}% - \FV@RightListFrame - \FV@RightListNumber}% -%% DG/SR modification end - \hss}} -%% \savetabu -------------------------------------------------------- -\newcommand*\savetabu[1]{\noalign{% - \tabu@sanitizearg{#1}\tabu@temp - \ifx \tabu@temp\@empty \tabu@savewarn{}{The tabu will not be saved}\else - \@ifundefined{tabu@saved@\tabu@temp}{}{\tabu@savewarn{#1}{Overwriting}}% - \ifdefined\tabu@restored \expandafter\let - \csname tabu@saved@\tabu@temp \endcsname \tabu@restored - \else {\tabu@save}% - \fi - \fi}% -}% \savetabu -\def\tabu@save {% - \toks0\expandafter{\tabu@saved@}% - \iftabu@negcoef - \let\tabu@wddef \relax \let\tabu@ \tabu@savewd \edef\tabu@savewd{\tabu@Xcoefs}% - \toks0\expandafter{\the\toks\expandafter0\tabu@savewd}\fi - \toks1\expandafter{\tabu@savedpream}% - \toks2\expandafter{\tabu@savedpreamble}% - \let\@preamble \relax - \let\tabu@savedpream \relax \let\tabu@savedparams \relax - \edef\tabu@preamble{% - \def\noexpand\tabu@aligndefault{\tabu@align}% - \def\tabu@savedparams {\noexpand\the\toks0}% - \def\tabu@savedpream {\noexpand\the\toks1}}% - \edef\tabu@usetabu{% - \def\@preamble {\noexpand\the\toks2}% - \tabu@target \the\tabu@target \relax - \tabucolX \the\tabucolX \relax - \tabu@nbcols \the\tabu@nbcols \relax - \def\noexpand\tabu@aligndefault{\tabu@align}% - \def\tabu@savedparams {\noexpand\the\toks0}% - \def\tabu@savedpream {\noexpand\the\toks1}}% - \let\tabu@aligndefault \relax \let\@sharp \relax - \edef\@tempa{\noexpand\tabu@s@ved - {\tabu@usetabu} - {\tabu@preamble} - {\the\toks1}}\@tempa - \tabu@message@save -}% \tabu@save -\long\def\tabu@s@ved #1#2#3{% - \def\tabu@usetabu{#1}% - \expandafter\gdef\csname tabu@saved@\tabu@temp\endcsname ##1{% - \ifodd ##1% \usetabu - \tabu@measuringfalse \tabu@spreadfalse % Just in case... - \gdef\tabu@usetabu {% - \ifdim \tabu@target>\z@ \tabu@warn@usetabu \fi - \global\let\tabu@usetabu \@undefined - \def\@halignto {to\tabu@target}% - #1% - \ifx \tabu@align\tabu@aligndefault@text - \ifnum \tabu@nested=\z@ - \let\tabu@align \tabu@aligndefault \fi\fi}% - \else % \preamble - \gdef\tabu@preamble {% - \global\let\tabu@preamble \@undefined - #2% - \ifx \tabu@align\tabu@aligndefault@text - \ifnum \tabu@nested=\z@ - \let\tabu@align \tabu@aligndefault \fi\fi}% - \fi - #3}% -}% \tabu@s@ved -\def\tabu@aligndefault@text {\tabu@aligndefault}% -\def\tabu@warn@usetabu {\PackageWarning{tabu} - {Specifying a target with \string\usetabu\space is useless - \MessageBreak The target cannot be changed!}} -\def\tabu@savewd #1#2{\ifdim #2\p@<\z@ \tabu@wddef{#1}{\tabu@wd{#1}}\fi} -\def\tabu@savewarn#1#2{\PackageInfo{tabu} - {User-name `#1' already used for \string\savetabu - \MessageBreak #2}}% -\def\tabu@saveerr#1{\PackageError{tabu} - {User-name `#1' is unknown for \string\usetabu - \MessageBreak I cannot restore an unknown preamble!}\@ehd} -%% \rowfont --------------------------------------------------------- -\newskip \tabu@cellskip -\def\tabu@rowfont{\ifdim \baselineskip=\z@\noalign\fi - {\ifnum0=`}\fi \tabu@row@font} -\newcommand*\tabu@row@font[2][]{% - \ifnum7=\currentgrouptype - \global\let\tabu@@cellleft \tabu@cellleft - \global\let\tabu@@cellright \tabu@cellright - \global\let\tabu@@celllalign \tabu@celllalign - \global\let\tabu@@cellralign \tabu@cellralign - \global\let\tabu@@rowfontreset\tabu@rowfontreset - \fi - \global\let\tabu@rowfontreset \tabu@rowfont@reset - \expandafter\gdef\expandafter\tabu@cellleft\expandafter{\tabu@cellleft #2}% - \ifcsname tabu@cell@#1\endcsname % row alignment - \csname tabu@cell@#1\endcsname \fi - \ifnum0=`{\fi}% end of group / noalign group -}% \rowfont -\def\tabu@ifcolorleavevmode #1{\let\color \tabu@leavevmodecolor #1\let\color\tabu@color}% -\def\tabu@rowfont@reset{% - \global\let\tabu@rowfontreset \tabu@@rowfontreset - \global\let\tabu@cellleft \tabu@@cellleft - \global\let\tabu@cellright \tabu@@cellright - \global\let\tabu@cellfont \@empty - \global\let\tabu@celllalign \tabu@@celllalign - \global\let\tabu@cellralign \tabu@@cellralign -}% \tabu@@rowfontreset -\let\tabu@rowfontreset \@empty % overwritten \AtBeginDocument if colortbl -%% \tabu@prepnext@tok ----------------------------------------------- -\newif \iftabu@cellright -\def\tabu@prepnext@tok{% - \ifnum \count@<\z@ % - \@tempcnta \@M % - \tabu@nbcols\z@ - \let\tabu@fornoopORI \@fornoop - \tabu@cellrightfalse - \else - \ifcase \numexpr \count@-\@tempcnta \relax % (case 0): prev. token is left - \advance \tabu@nbcols \@ne - \iftabu@cellright % before-previous token is right and is finished - \tabu@cellrightfalse % - \tabu@righttok - \fi - \tabu@lefttok - \or % (case 1) previous token is right - \tabu@cellrighttrue \let\@fornoop \tabu@lastnoop - \else % special column: do not change the token - \iftabu@cellright % before-previous token is right - \tabu@cellrightfalse - \tabu@righttok - \fi - \fi % \ifcase - \fi - \tabu@prepnext@tokORI -}% \tabu@prepnext@tok -\long\def\tabu@lastnoop#1\@@#2#3{\tabu@lastn@@p #2\@nextchar \in@\in@@} -\def\tabu@lastn@@p #1\@nextchar #2#3\in@@{% - \ifx \in@#2\else - \let\@fornoop \tabu@fornoopORI - \xdef\tabu@mkpreambuffer{\tabu@nbcols\the\tabu@nbcols \tabu@mkpreambuffer}% - \toks0\expandafter{\expandafter\tabu@everyrowtrue \the\toks0}% - \expandafter\prepnext@tok - \fi -}% \tabu@lastnoop -\def\tabu@righttok{% - \advance \count@ \m@ne - \toks\count@\expandafter {\the\toks\count@ \tabu@cellright \tabu@cellralign}% - \advance \count@ \@ne -}% \tabu@righttok -\def\tabu@lefttok{\toks\count@\expandafter{\expandafter\tabu@celllalign - \the\toks\count@ \tabu@cellleft}% after because of $ -}% \tabu@lefttok -%% Neutralisation of glues ------------------------------------------ -\let\tabu@cellleft \@empty -\let\tabu@cellright \@empty -\tabu@celllalign@def{\tabu@cellleft}% -\let\tabu@cellralign \@empty -\def\tabu@cell@align #1#2#3{% - \let\tabu@maybesiunitx \toks@ \tabu@celllalign - \global \expandafter \tabu@celllalign@def \expandafter {\the\toks@ #1}% - \toks@\expandafter{\tabu@cellralign #2}% - \xdef\tabu@cellralign{\the\toks@}% - \toks@\expandafter{\tabu@cellleft #3}% - \xdef\tabu@cellleft{\the\toks@}% -}% \tabu@cell@align -\def\tabu@cell@l{% force alignment to left - \tabu@cell@align - {\tabu@removehfil \raggedright \tabu@cellleft}% left - {\tabu@flush1\tabu@ignorehfil}% right - \raggedright -}% \tabu@cell@l -\def\tabu@cell@c{% force alignment to center - \tabu@cell@align - {\tabu@removehfil \centering \tabu@flush{.5}\tabu@cellleft} - {\tabu@flush{.5}\tabu@ignorehfil} - \centering -}% \tabu@cell@c -\def\tabu@cell@r{% force alignment to right - \tabu@cell@align - {\tabu@removehfil \raggedleft \tabu@flush1\tabu@cellleft} - \tabu@ignorehfil - \raggedleft -}% \tabu@cell@r -\def\tabu@cell@j{% force justification (for p, m, b columns) - \tabu@cell@align - {\tabu@justify\tabu@cellleft} - {} - \tabu@justify -}% \tabu@cell@j -\def\tabu@justify{% - \leftskip\z@skip \@rightskip\leftskip \rightskip\@rightskip - \parfillskip\@flushglue -}% \tabu@justify -%% ragged2e settings -\def\tabu@cell@L{% force alignment to left (ragged2e) - \tabu@cell@align - {\tabu@removehfil \RaggedRight \tabu@cellleft} - {\tabu@flush 1\tabu@ignorehfil} - \RaggedRight -}% \tabu@cell@L -\def\tabu@cell@C{% force alignment to center (ragged2e) - \tabu@cell@align - {\tabu@removehfil \Centering \tabu@flush{.5}\tabu@cellleft} - {\tabu@flush{.5}\tabu@ignorehfil} - \Centering -}% \tabu@cell@C -\def\tabu@cell@R{% force alignment to right (ragged2e) - \tabu@cell@align - {\tabu@removehfil \RaggedLeft \tabu@flush 1\tabu@cellleft} - \tabu@ignorehfil - \RaggedLeft -}% \tabu@cell@R -\def\tabu@cell@J{% force justification (ragged2e) - \tabu@cell@align - {\justifying \tabu@cellleft} - {} - \justifying -}% \tabu@cell@J -\def\tabu@flush#1{% - \iftabu@colortbl % colortbl uses \hfill rather than \hfil - \hskip \ifnum13<\currentgrouptype \stretch{#1}% - \else \ifdim#1pt<\p@ \tabu@cellskip - \else \stretch{#1} - \fi\fi \relax - \else % array.sty - \ifnum 13<\currentgrouptype - \hfil \hskip1sp \relax \fi - \fi -}% \tabu@flush -\let\tabu@hfil \hfil -\let\tabu@hfill \hfill -\let\tabu@hskip \hskip -\def\tabu@removehfil{% - \iftabu@colortbl - \unkern \tabu@cellskip =\lastskip - \ifnum\gluestretchorder\tabu@cellskip =\tw@ \hskip-\tabu@cellskip - \else \tabu@cellskip \z@skip - \fi - \else - \ifdim\lastskip=1sp\unskip\fi - \ifnum\gluestretchorder\lastskip =\@ne - \hfilneg % \hfilneg for array.sty but not for colortbl... - \fi - \fi -}% \tabu@removehfil -\def\tabu@ignorehfil{\aftergroup \tabu@nohfil} -\def\tabu@nohfil{% \hfil -> do nothing + restore original \hfil - \def\hfil{\let\hfil \tabu@hfil}% local to (alignment template) group -}% \tabu@nohfil -\def\tabu@colortblalignments {% if colortbl - \def\tabu@nohfil{% - \def\hfil {\let\hfil \tabu@hfil}% local to (alignment template) group - \def\hfill {\let\hfill \tabu@hfill}% (colortbl uses \hfill) pfff... - \def\hskip ####1\relax{\let\hskip \tabu@hskip}}% local -}% \tabu@colortblalignments -%% Taking care of footnotes and hyperfootnotes ---------------------- -\long\def\tabu@footnotetext #1{% - \edef\@tempa{\the\tabu@footnotes - \noexpand\footnotetext [\the\csname c@\@mpfn\endcsname]}% - \global\tabu@footnotes\expandafter{\@tempa {#1}}}% -\long\def\tabu@xfootnotetext [#1]#2{% - \global\tabu@footnotes\expandafter{\the\tabu@footnotes - \footnotetext [{#1}]{#2}}} -\let\tabu@xfootnote \@xfootnote -\long\def\tabu@Hy@ftntext{\tabu@Hy@ftntxt {\the \c@footnote }} -\long\def\tabu@Hy@xfootnote [#1]{% - \begingroup - \value\@mpfn #1\relax - \protected@xdef \@thefnmark {\thempfn}% - \endgroup - \@footnotemark \tabu@Hy@ftntxt {#1}% -}% \tabu@Hy@xfootnote -\long\def\tabu@Hy@ftntxt #1#2{% - \edef\@tempa{% - \the\tabu@footnotes - \begingroup - \value\@mpfn #1\relax - \noexpand\protected@xdef\noexpand\@thefnmark {\noexpand\thempfn}% - \expandafter \noexpand \expandafter - \tabu@Hy@footnotetext \expandafter{\Hy@footnote@currentHref}% - }% - \global\tabu@footnotes\expandafter{\@tempa {#2}% - \endgroup}% -}% \tabu@Hy@ftntxt -\long\def\tabu@Hy@footnotetext #1#2{% - \H@@footnotetext{% - \ifHy@nesting - \hyper@@anchor {#1}{#2}% - \else - \Hy@raisedlink{% - \hyper@@anchor {#1}{\relax}% - }% - \def\@currentHref {#1}% - \let\@currentlabelname \@empty - #2% - \fi - }% -}% \tabu@Hy@footnotetext -%% No need for \arraybackslash ! ------------------------------------ -\def\tabu@latextwoe {% -\def\tabu@temp##1##2##3{{\toks@\expandafter{##2##3}\xdef##1{\the\toks@}}} -\tabu@temp \tabu@centering \centering \arraybackslash -\tabu@temp \tabu@raggedleft \raggedleft \arraybackslash -\tabu@temp \tabu@raggedright \raggedright \arraybackslash -}% \tabu@latextwoe -\def\tabu@raggedtwoe {% -\def\tabu@temp ##1##2##3{{\toks@\expandafter{##2##3}\xdef##1{\the\toks@}}} -\tabu@temp \tabu@Centering \Centering \arraybackslash -\tabu@temp \tabu@RaggedLeft \RaggedLeft \arraybackslash -\tabu@temp \tabu@RaggedRight \RaggedRight \arraybackslash -\tabu@temp \tabu@justifying \justifying \arraybackslash -}% \tabu@raggedtwoe -\def\tabu@normalcrbackslash{\let\\\@normalcr} -\def\tabu@trivlist{\expandafter\def\expandafter\@trivlist\expandafter{% - \expandafter\tabu@normalcrbackslash \@trivlist}} -%% Utilities: \fbox \fcolorbox and \tabudecimal ------------------- -\def\tabu@fbox {\leavevmode\afterassignment\tabu@beginfbox \setbox\@tempboxa\hbox} -\def\tabu@beginfbox {\bgroup \kern\fboxsep - \bgroup\aftergroup\tabu@endfbox} -\def\tabu@endfbox {\kern\fboxsep\egroup\egroup - \@frameb@x\relax} -\def\tabu@color@b@x #1#2{\leavevmode \bgroup - \def\tabu@docolor@b@x{#1{#2\color@block{\wd\z@}{\ht\z@}{\dp\z@}\box\z@}}% - \afterassignment\tabu@begincolor@b@x \setbox\z@ \hbox -}% \tabu@color@b@x -\def\tabu@begincolor@b@x {\kern\fboxsep \bgroup - \aftergroup\tabu@endcolor@b@x \set@color} -\def\tabu@endcolor@b@x {\kern\fboxsep \egroup - \dimen@\ht\z@ \advance\dimen@ \fboxsep \ht\z@ \dimen@ - \dimen@\dp\z@ \advance\dimen@ \fboxsep \dp\z@ \dimen@ - \tabu@docolor@b@x \egroup -}% \tabu@endcolor@b@x -%% Corrections (arydshln, delarray, colortbl) ----------------------- -\def\tabu@fix@arrayright {%% \@arrayright is missing from \endarray - \iftabu@colortbl - \ifdefined\adl@array % - \def\tabu@endarray{% - \adl@endarray \egroup \adl@arrayrestore \CT@end \egroup % - \@arrayright % - \gdef\@preamble{}}% - \else % - \def\tabu@endarray{% - \crcr \egroup \egroup % - \@arrayright % - \gdef\@preamble{}\CT@end}% - \fi - \else - \ifdefined\adl@array % - \def\tabu@endarray{% - \adl@endarray \egroup \adl@arrayrestore \egroup % - \@arrayright % - \gdef\@preamble{}}% - \else % - \PackageWarning{tabu} - {\string\@arrayright\space is missing from the - \MessageBreak definition of \string\endarray. - \MessageBreak Compatibility with delarray.sty is broken.}% - \fi\fi -}% \tabu@fix@arrayright -\def\tabu@adl@xarraydashrule #1#2#3{% - \ifnum\@lastchclass=\adl@class@start\else - \ifnum\@lastchclass=\@ne\else - \ifnum\@lastchclass=5 \else % @-arg (class 5) and !-arg (class 1) - \adl@leftrulefalse \fi\fi % must be treated the same - \fi - \ifadl@zwvrule\else \ifadl@inactive\else - \@addtopreamble{\vrule\@width\arrayrulewidth - \@height\z@ \@depth\z@}\fi \fi - \ifadl@leftrule - \@addtopreamble{\adl@vlineL{\CT@arc@}{\adl@dashgapcolor}% - {\number#1}#3}% - \else \@addtopreamble{\adl@vlineR{\CT@arc@}{\adl@dashgapcolor}% - {\number#2}#3} - \fi -}% \tabu@adl@xarraydashrule -\def\tabu@adl@act@endpbox {% - \unskip \ifhmode \nobreak \fi \@finalstrut \@arstrutbox - \egroup \egroup - \adl@colhtdp \box\adl@box \hfil -}% \tabu@adl@act@endpbox -\def\tabu@adl@fix {% - \let\adl@xarraydashrule \tabu@adl@xarraydashrule % arydshln - \let\adl@act@endpbox \tabu@adl@act@endpbox % arydshln - \let\adl@act@@endpbox \tabu@adl@act@endpbox % arydshln - \let\@preamerror \@preamerr % arydshln -}% \tabu@adl@fix -%% Correction for longtable' \@startbox definition ------------------ -%% => \everypar is ``missing'' : TeX should be in vertical mode -\def\tabu@LT@startpbox #1{% - \bgroup - \let\@footnotetext\LT@p@ftntext - \setlength\hsize{#1}% - \@arrayparboxrestore - \everypar{% - \vrule \@height \ht\@arstrutbox \@width \z@ - \everypar{}}% -}% \tabu@LT@startpbox -%% \tracingtabu and the package options ------------------ -\DeclareOption{delarray}{\AtEndOfPackage{\RequirePackage{delarray}}} -\DeclareOption{linegoal}{% - \AtEndOfPackage{% - \RequirePackage{linegoal}[2010/12/07]% - \let\tabudefaulttarget \linegoal% \linegoal is \linewidth if not pdfTeX -}} -\DeclareOption{scantokens}{\tabuscantokenstrue} -\DeclareOption{debugshow}{\AtEndOfPackage{\tracingtabu=\tw@}} -\def\tracingtabu {\begingroup\@ifnextchar=% - {\afterassignment\tabu@tracing\count@} - {\afterassignment\tabu@tracing\count@1\relax}} -\def\tabu@tracing{\expandafter\endgroup - \expandafter\tabu@tr@cing \the\count@ \relax -}% \tabu@tracing -\def\tabu@tr@cing #1\relax {% - \ifnum#1>\thr@@ \let\tabu@tracinglines\message - \else \let\tabu@tracinglines\@gobble - \fi - \ifnum#1>\tw@ \let\tabu@DBG \tabu@@DBG - \def\tabu@mkarstrut {\tabu@DBG@arstrut}% - \tabustrutrule 1.5\p@ - \else \let\tabu@DBG \@gobble - \def\tabu@mkarstrut {\tabu@arstrut}% - \tabustrutrule \z@ - \fi - \ifnum#1>\@ne \let\tabu@debug \message - \else \let\tabu@debug \@gobble - \fi - \ifnum#1>\z@ - \let\tabu@message \message - \let\tabu@tracing@save \tabu@message@save - \let\tabu@starttimer \tabu@pdftimer - \else - \let\tabu@message \@gobble - \let\tabu@tracing@save \@gobble - \let\tabu@starttimer \relax - \fi -}% \tabu@tr@cing -%% Setup \AtBeginDocument -\AtBeginDocument{\tabu@AtBeginDocument} -\def\tabu@AtBeginDocument{\let\tabu@AtBeginDocument \@undefined - \ifdefined\arrayrulecolor \tabu@colortbltrue % - \tabu@colortblalignments % different glues are used - \else \tabu@colortblfalse \fi - \ifdefined\CT@arc@ \else \let\CT@arc@ \relax \fi - \ifdefined\CT@drsc@\else \let\CT@drsc@ \relax \fi - \let\tabu@arc@L \CT@arc@ \let\tabu@drsc@L \CT@drsc@ - \ifodd 1\ifcsname siunitx_table_collect_begin:Nn\endcsname % - \expandafter\ifx - \csname siunitx_table_collect_begin:Nn\endcsname\relax 0\fi\fi\relax - \tabu@siunitxtrue - \else \let\tabu@maybesiunitx \@firstofone % - \let\tabu@siunitx \tabu@nosiunitx - \tabu@siunitxfalse - \fi - \ifdefined\adl@array % - \else \let\tabu@adl@fix \relax - \let\tabu@adl@endtrial \@empty \fi - \ifdefined\longtable % - \else \let\longtabu \tabu@nolongtabu \fi - \ifdefined\cellspacetoplimit \tabu@warn@cellspace\fi - \csname\ifcsname ifHy@hyperfootnotes\endcsname % - ifHy@hyperfootnotes\else iffalse\fi\endcsname - \let\tabu@footnotetext \tabu@Hy@ftntext - \let\tabu@xfootnote \tabu@Hy@xfootnote \fi - \ifdefined\FV@DefineCheckEnd% - \tabu@fancyvrb \fi - \ifdefined\color % - \let\tabu@color \color - \def\tabu@leavevmodecolor ##1{% - \def\tabu@leavevmodecolor {\leavevmode ##1}% - }\expandafter\tabu@leavevmodecolor\expandafter{\color}% - \else - \let\tabu@color \tabu@nocolor - \let\tabu@leavevmodecolor \@firstofone \fi - \tabu@latextwoe - \ifdefined\@raggedtwoe@everyselectfont % - \tabu@raggedtwoe - \else - \let\tabu@cell@L \tabu@cell@l - \let\tabu@cell@R \tabu@cell@r - \let\tabu@cell@C \tabu@cell@c - \let\tabu@cell@J \tabu@cell@j \fi - \expandafter\in@ \expandafter\@arrayright \expandafter{\endarray}% - \ifin@ \let\tabu@endarray \endarray - \else \tabu@fix@arrayright \fi% - \everyrow{}% -}% \tabu@AtBeginDocument -\def\tabu@warn@cellspace{% - \PackageWarning{tabu}{% - Package cellspace has some limitations - \MessageBreak And redefines some macros of array.sty. - \MessageBreak Please use \string\tabulinesep\space to control - \MessageBreak vertical spacing of lines inside tabu environment}% -}% \tabu@warn@cellspace -%% tabu Package initialisation -\tabuscantokensfalse -\let\tabu@arc@G \relax -\let\tabu@drsc@G \relax -\let\tabu@evr@G \@empty -\let\tabu@rc@G \@empty -\def\tabu@ls@G {\tabu@linestyle@}% -\let\tabu@@rowfontreset \@empty % -\let\tabu@@celllalign \@empty -\let\tabu@@cellralign \@empty -\let\tabu@@cellleft \@empty -\let\tabu@@cellright \@empty -\def\tabu@naturalXmin {\z@} -\def\tabu@naturalXmax {\z@} -\let\tabu@rowfontreset \@empty -\def\tabulineon {4pt}\let\tabulineoff \tabulineon -\tabu@everyrowtrue -\ifdefined\pdfelapsedtime % - \def\tabu@pdftimer {\xdef\tabu@starttime{\the\pdfelapsedtime}}% -\else \let\tabu@pdftimer \relax \let\tabu@message@etime \relax -\fi -\tracingtabu=\z@ -\newtabulinestyle {=\maxdimen}% creates the 'factory' settings \tabu@linestyle@ -\tabulinestyle{} -\taburowcolors{} -\let\tabudefaulttarget \linewidth -\ProcessOptions* % \ProcessOptions* is quicker ! -\endinput -%% -%% End of file `tabu.sty'. diff --git a/include/BNO08x.hpp b/include/BNO08x.hpp index c0b05ac..fb8ac35 100644 --- a/include/BNO08x.hpp +++ b/include/BNO08x.hpp @@ -11,6 +11,11 @@ #include #include +// hill-crest labs includes (apache 2.0 license, compatible with MIT) +#include "sh2.h" +#include "sh2_SensorValue.h" +#include "sh2_err.h" + // esp-idf includes #include #include @@ -38,205 +43,10 @@ class BNO08x bool initialize(); bool hard_reset(); - bool soft_reset(); - BNO08xResetReason get_reset_reason(); - bool mode_sleep(); - bool mode_on(); - float q_to_float(int16_t fixed_point_value, uint8_t q_point); - - bool run_full_calibration_routine(); - void calibrate_all(); - void calibrate_accelerometer(); - void calibrate_gyro(); - void calibrate_magnetometer(); - void calibrate_planar_accelerometer(); - void request_calibration_status(); - bool calibration_complete(); - void end_calibration(); - void save_calibration(); - - void enable_rotation_vector(uint32_t time_between_reports); - void enable_game_rotation_vector(uint32_t time_between_reports); - void enable_ARVR_stabilized_rotation_vector(uint32_t time_between_reports); - void enable_ARVR_stabilized_game_rotation_vector(uint32_t time_between_reports); - void enable_gyro_integrated_rotation_vector(uint32_t time_between_reports); - void enable_uncalibrated_gyro(uint32_t time_between_reports); - void enable_calibrated_gyro(uint32_t time_between_reports); - void enable_accelerometer(uint32_t time_between_reports); - void enable_linear_accelerometer(uint32_t time_between_reports); - void enable_gravity(uint32_t time_between_reports); - void enable_magnetometer(uint32_t time_between_reports); - void enable_tap_detector(uint32_t time_between_reports); - void enable_step_counter(uint32_t time_between_reports); - void enable_stability_classifier(uint32_t time_between_reports); - void enable_activity_classifier( - uint32_t time_between_reports, BNO08xActivityEnable activities_to_enable, uint8_t (&activity_confidence_vals)[9]); - void enable_raw_mems_gyro(uint32_t time_between_reports); - void enable_raw_mems_accelerometer(uint32_t time_between_reports); - void enable_raw_mems_magnetometer(uint32_t time_between_reports); - - void disable_rotation_vector(); - void disable_game_rotation_vector(); - void disable_ARVR_stabilized_rotation_vector(); - void disable_ARVR_stabilized_game_rotation_vector(); - void disable_gyro_integrated_rotation_vector(); - void disable_accelerometer(); - void disable_linear_accelerometer(); - void disable_gravity(); - void disable_calibrated_gyro(); - void disable_uncalibrated_gyro(); - void disable_magnetometer(); - void disable_step_counter(); - void disable_stability_classifier(); - void disable_activity_classifier(); - void disable_tap_detector(); - void disable_raw_mems_accelerometer(); - void disable_raw_mems_gyro(); - void disable_raw_mems_magnetometer(); - - void tare_now(uint8_t axis_sel = TARE_AXIS_ALL, uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR); - void save_tare(); - void clear_tare(); - - bool data_available(bool ignore_no_reports_enabled = false); void register_cb(std::function cb_fxn); - void reset_all_data_to_defaults(); - - uint32_t get_time_stamp(); - - void get_magf(float& x, float& y, float& z, BNO08xAccuracy& accuracy); - float get_magf_X(); - float get_magf_Y(); - float get_magf_Z(); - BNO08xAccuracy get_magf_accuracy(); - - void get_gravity(float& x, float& y, float& z, BNO08xAccuracy& accuracy); - float get_gravity_X(); - float get_gravity_Y(); - float get_gravity_Z(); - BNO08xAccuracy get_gravity_accuracy(); - - float get_roll(); - float get_pitch(); - float get_yaw(); - - float get_roll_deg(); - float get_pitch_deg(); - float get_yaw_deg(); - - void get_quat(float& i, float& j, float& k, float& real, float& rad_accuracy, BNO08xAccuracy& accuracy); - float get_quat_I(); - float get_quat_J(); - float get_quat_K(); - float get_quat_real(); - float get_quat_radian_accuracy(); - BNO08xAccuracy get_quat_accuracy(); - - void get_accel(float& x, float& y, float& z, BNO08xAccuracy& accuracy); - float get_accel_X(); - float get_accel_Y(); - float get_accel_Z(); - BNO08xAccuracy get_accel_accuracy(); - - void get_linear_accel(float& x, float& y, float& z, BNO08xAccuracy& accuracy); - float get_linear_accel_X(); - float get_linear_accel_Y(); - float get_linear_accel_Z(); - BNO08xAccuracy get_linear_accel_accuracy(); - - void get_raw_mems_accel(uint16_t& x, uint16_t& y, uint16_t& z); - uint16_t get_raw_mems_accel_X(); - uint16_t get_raw_mems_accel_Y(); - uint16_t get_raw_mems_accel_Z(); - - void get_raw_mems_gyro(uint16_t& x, uint16_t& y, uint16_t& z); - uint16_t get_raw_mems_gyro_X(); - uint16_t get_raw_mems_gyro_Y(); - uint16_t get_raw_mems_gyro_Z(); - - void get_raw_mems_magf(uint16_t& x, uint16_t& y, uint16_t& z); - uint16_t get_raw_mems_magf_X(); - uint16_t get_raw_mems_magf_Y(); - uint16_t get_raw_mems_magf_Z(); - - void get_calibrated_gyro_velocity(float& x, float& y, float& z); - float get_calibrated_gyro_velocity_X(); - float get_calibrated_gyro_velocity_Y(); - float get_calibrated_gyro_velocity_Z(); - - void get_uncalibrated_gyro_velocity(float& x, float& y, float& z, float& bx, float& by, float& bz); - float get_uncalibrated_gyro_velocity_X(); - float get_uncalibrated_gyro_velocity_Y(); - float get_uncalibrated_gyro_velocity_Z(); - float get_uncalibrated_gyro_bias_X(); - float get_uncalibrated_gyro_bias_Y(); - float get_uncalibrated_gyro_bias_Z(); - - void get_integrated_gyro_velocity(float& x, float& y, float& z); - float get_integrated_gyro_velocity_X(); - float get_integrated_gyro_velocity_Y(); - float get_integrated_gyro_velocity_Z(); - - uint8_t get_tap_detector(); - uint16_t get_step_count(); - BNO08xStability get_stability_classifier(); - BNO08xActivity get_activity_classifier(); - - // Metadata functions - int16_t get_Q1(uint16_t record_ID); - int16_t get_Q2(uint16_t record_ID); - int16_t get_Q3(uint16_t record_ID); - float get_resolution(uint16_t record_ID); - float get_range(uint16_t record_ID); - uint32_t FRS_read_word(uint16_t record_ID, uint8_t word_number); - bool FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size); - bool FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read); - - // Record IDs from figure 29, page 29 reference manual - // These are used to read the metadata for each sensor type - static const constexpr uint16_t FRS_RECORD_ID_ACCELEROMETER = - 0xE302U; ///< Accelerometer record ID, to be passed in metadata functions like get_Q1() - static const constexpr uint16_t FRS_RECORD_ID_GYROSCOPE_CALIBRATED = - 0xE306U; ///< Calirated gyroscope record ID, to be passed in metadata functions like get_Q1() - static const constexpr uint16_t FRS_RECORD_ID_MAGNETIC_FIELD_CALIBRATED = - 0xE309U; ///< Calibrated magnetometer record ID, to be passed in metadata functions like get_Q1() - static const constexpr uint16_t FRS_RECORD_ID_ROTATION_VECTOR = - 0xE30BU; ///< Rotation vector record ID, to be passed in metadata functions like get_Q1() - - static const constexpr uint8_t TARE_AXIS_ALL = 0x07U; ///< Tare all axes (used with tare now command) - static const constexpr uint8_t TARE_AXIS_Z = 0x04U; ///< Tar yaw axis only (used with tare now command) - - // Which rotation vector to tare, BNO08x saves them seperately - static const constexpr uint8_t TARE_ROTATION_VECTOR = 0U; ///> cb_list; // Vector for storing any call-back functions added with register_cb() - uint32_t meta_data[9]; ///init_config_args(); - } - - /** - * @brief Used to call private BNO08x::init_gpio() member for tests. - * - * @return ESP_OK if init succeeded. - */ - static esp_err_t call_init_gpio() - { - if (test_imu == nullptr) - return ESP_FAIL; - - return test_imu->init_gpio(); - } - - /** - * @brief Used to call private BNO08x::init_hint_isr() member for tests. - * - * @return ESP_OK if init succeeded. - */ - static esp_err_t call_init_hint_isr() - { - if (test_imu == nullptr) - return ESP_FAIL; - - return test_imu->init_hint_isr(); - } - - /** - * @brief Used to call private BNO08x::init_spi() member for tests. - * - * @return ESP_OK if init succeeded. - */ - static esp_err_t call_init_spi() - { - if (test_imu == nullptr) - return ESP_FAIL; - - return test_imu->init_spi(); - } - - /** - * @brief Used to call private BNO08x::launch_tasks() member for tests. - * - * @return ESP_OK if init succeeded. - */ - static esp_err_t call_launch_tasks() - { - if (test_imu == nullptr) - return ESP_FAIL; - - return test_imu->launch_tasks(); - } - - /** - * @brief Checks if report_data matches the default states stored within default_report_data data for respective report. - * - * @param report_data Current report data. - * @param default_report_data Default report data to compare (should always contain default values) - * - * @return True if new data was received for respective report. - */ - static bool rotation_vector_data_is_new(imu_report_data_t* report_data, imu_report_data_t* default_report_data) - { - bool new_data = false; - - // prev report should always contain the default test values as per test structure - if (report_data->quat_I != default_report_data->quat_I) - new_data = true; - - if (report_data->quat_J != default_report_data->quat_J) - new_data = true; - - if (report_data->quat_K != default_report_data->quat_K) - new_data = true; - - if (report_data->quat_real != default_report_data->quat_real) - new_data = true; - - if (report_data->quat_accuracy != default_report_data->quat_accuracy) - new_data = true; - - if (report_data->quat_radian_accuracy != default_report_data->quat_radian_accuracy) - new_data = true; - - return new_data; - } - - /** - * @brief Checks if report_data matches the default states stored within default_report_data data for respective report. - * - * @param report_data Current report data. - * @param default_report_data Default report data to compare (should always contain default values) - * - * @return True if new data was received for respective report. - */ - static bool gyro_integrated_rotation_vector_data_is_new(imu_report_data_t* report_data, imu_report_data_t* default_report_data) - { - bool new_data = false; - - if (report_data->quat_I != default_report_data->quat_I) - new_data = true; - - if (report_data->quat_J != default_report_data->quat_J) - new_data = true; - - if (report_data->quat_K != default_report_data->quat_K) - new_data = true; - - if (report_data->quat_real != default_report_data->quat_real) - new_data = true; - - if (report_data->integrated_gyro_vel_x != default_report_data->integrated_gyro_vel_x) - new_data = true; - - if (report_data->integrated_gyro_vel_y != default_report_data->integrated_gyro_vel_y) - new_data = true; - - if (report_data->integrated_gyro_vel_z != default_report_data->integrated_gyro_vel_z) - new_data = true; - - return new_data; - } - - /** - * @brief Checks if report_data matches the default states stored within default_report_data data for respective report. - * - * @param report_data Current report data. - * @param default_report_data Default report data to compare (should always contain default values) - * - * @return True if new data was received for respective report. - */ - static bool uncalibrated_gyro_data_is_new(imu_report_data_t* report_data, imu_report_data_t* default_report_data) - { - bool new_data = false; - - if (report_data->uncalib_gyro_vel_x != default_report_data->uncalib_gyro_vel_x) - new_data = true; - - if (report_data->uncalib_gyro_vel_y != default_report_data->uncalib_gyro_vel_y) - new_data = true; - - if (report_data->uncalib_gyro_vel_z != default_report_data->uncalib_gyro_vel_z) - new_data = true; - - if (report_data->uncalib_gyro_drift_x != default_report_data->uncalib_gyro_drift_x) - new_data = true; - - if (report_data->uncalib_gyro_drift_y != default_report_data->uncalib_gyro_drift_y) - new_data = true; - - if (report_data->uncalib_gyro_drift_z != default_report_data->uncalib_gyro_drift_z) - new_data = true; - - return new_data; - } - - /** - * @brief Checks if report_data matches the default states stored within default_report_data data for respective report. - * - * @param report_data Current report data. - * @param default_report_data Default report data to compare (should always contain default values) - * - * @return True if new data was received for respective report. - */ - static bool calibrated_gyro_data_is_new(imu_report_data_t* report_data, imu_report_data_t* default_report_data) - { - bool new_data = false; - - if (report_data->calib_gyro_vel_x != default_report_data->calib_gyro_vel_x) - new_data = true; - - if (report_data->calib_gyro_vel_y != default_report_data->calib_gyro_vel_y) - new_data = true; - - if (report_data->calib_gyro_vel_z != default_report_data->calib_gyro_vel_z) - new_data = true; - - return new_data; - } - - /** - * @brief Checks if report_data matches the default states stored within default_report_data data for respective report. - * - * @param report_data Current report data. - * @param default_report_data Default report data to compare (should always contain default values) - * - * @return True if new data was received for respective report. - */ - static bool accelerometer_data_is_new(imu_report_data_t* report_data, imu_report_data_t* default_report_data) - { - bool new_data = false; - - if (report_data->accel_x != default_report_data->accel_x) - new_data = true; - - if (report_data->accel_y != default_report_data->accel_y) - new_data = true; - - if (report_data->accel_z != default_report_data->accel_z) - new_data = true; - - if (report_data->accel_accuracy != default_report_data->accel_accuracy) - new_data = true; - - return new_data; - } - - /** - * @brief Checks if report_data matches the default states stored within default_report_data data for respective report. - * - * @param report_data Current report data. - * @param default_report_data Default report data to compare (should always contain default values) - * - * @return True if new data was received for respective report. - */ - static bool linear_accelerometer_data_is_new(imu_report_data_t* report_data, imu_report_data_t* default_report_data) - { - bool new_data = false; - - if (report_data->lin_accel_x != default_report_data->lin_accel_x) - new_data = true; - - if (report_data->lin_accel_y != default_report_data->lin_accel_y) - new_data = true; - - if (report_data->lin_accel_z != default_report_data->lin_accel_z) - new_data = true; - - if (report_data->lin_accel_accuracy != default_report_data->lin_accel_accuracy) - new_data = true; - - return new_data; - } - - /** - * @brief Checks if report_data matches the default states stored within default_report_data data for respective report. - * - * @param report_data Current report data. - * @param default_report_data Default report data to compare (should always contain default values) - * - * @return True if new data was received for respective report. - */ - static bool gravity_data_is_new(imu_report_data_t* report_data, imu_report_data_t* default_report_data) - { - bool new_data = false; - - if (report_data->grav_x != default_report_data->grav_x) - new_data = true; - - if (report_data->grav_y != default_report_data->grav_y) - new_data = true; - - if (report_data->grav_z != default_report_data->grav_z) - new_data = true; - - if (report_data->grav_accuracy != default_report_data->grav_accuracy) - new_data = true; - - return new_data; - } - - /** - * @brief Checks if report_data matches the default states stored within default_report_data data for respective report. - * - * @param report_data Current report data. - * @param default_report_data Default report data to compare (should always contain default values) - * - * @return True if new data was received for respective report. - */ - static bool magnetometer_data_is_new(imu_report_data_t* report_data, imu_report_data_t* default_report_data) - { - bool new_data = false; - - if (report_data->magf_x != default_report_data->magf_x) - new_data = true; - - if (report_data->magf_y != default_report_data->magf_y) - new_data = true; - - if (report_data->magf_z != default_report_data->magf_z) - new_data = true; - - if (report_data->magf_accuracy != default_report_data->magf_accuracy) - new_data = true; - - return new_data; - } - - /** - * @brief Checks if report_data matches the default states stored within default_report_data data for respective report. - * - * @param report_data Current report data. - * @param default_report_data Default report data to compare (should always contain default values) - * - * @return True if new data was received for respective report. - */ - static bool step_counter_data_is_new(imu_report_data_t* report_data, imu_report_data_t* default_report_data) - { - bool new_data = false; - - if (report_data->step_count != default_report_data->step_count) - new_data = true; - - return new_data; - } - - /** - * @brief Checks if report_data matches the default states stored within default_report_data data for respective report. - * - * @param report_data Current report data. - * @param default_report_data Default report data to compare (should always contain default values) - * - * @return True if new data was received for respective report. - */ - static bool stability_classifier_data_is_new(imu_report_data_t* report_data, imu_report_data_t* default_report_data) - { - bool new_data = false; - - if (report_data->stability_classifier != default_report_data->stability_classifier) - new_data = true; - - return new_data; - } - - /** - * @brief Checks if report_data matches the default states stored within default_report_data data for respective report. - * - * @param report_data Current report data. - * @param default_report_data Default report data to compare (should always contain default values) - * - * @return True if new data was received for respective report. - */ - static bool activity_classifier_data_is_new(imu_report_data_t* report_data, imu_report_data_t* default_report_data) - { - bool new_data = false; - - if (report_data->activity_classifier != default_report_data->activity_classifier) - new_data = true; - - return new_data; - } - - /** - * @brief Updates report data with calls relevant test_imu methods. - * - * @param report_data Pointer to imu_report_data_t struct to save report data. - * - * @return void, noting to return. - */ - static void update_report_data(imu_report_data_t* report_data) - { - - test_imu->get_quat(report_data->quat_I, report_data->quat_J, report_data->quat_K, report_data->quat_real, - report_data->quat_radian_accuracy, report_data->quat_accuracy); - test_imu->get_integrated_gyro_velocity( - report_data->integrated_gyro_vel_x, report_data->integrated_gyro_vel_y, report_data->integrated_gyro_vel_z); - test_imu->get_accel(report_data->accel_x, report_data->accel_y, report_data->accel_z, report_data->accel_accuracy); - test_imu->get_linear_accel(report_data->lin_accel_x, report_data->lin_accel_y, report_data->lin_accel_z, report_data->lin_accel_accuracy); - test_imu->get_gravity(report_data->grav_x, report_data->grav_y, report_data->grav_z, report_data->grav_accuracy); - test_imu->get_calibrated_gyro_velocity(report_data->calib_gyro_vel_x, report_data->calib_gyro_vel_y, report_data->calib_gyro_vel_z); - test_imu->get_uncalibrated_gyro_velocity(report_data->uncalib_gyro_vel_x, report_data->uncalib_gyro_vel_y, - report_data->uncalib_gyro_vel_z, report_data->uncalib_gyro_drift_x, report_data->uncalib_gyro_drift_y, - report_data->uncalib_gyro_drift_z); - test_imu->get_magf(report_data->magf_x, report_data->magf_y, report_data->magf_z, report_data->magf_accuracy); - test_imu->get_raw_mems_gyro(report_data->raw_mems_gyro_x, report_data->raw_mems_gyro_y, report_data->raw_mems_gyro_z); - report_data->step_count = test_imu->get_step_count(); - report_data->stability_classifier = test_imu->get_stability_classifier(); - report_data->activity_classifier = test_imu->get_activity_classifier(); - } - - /** - * @brief Resets internal test imu data with test defaults via accessing its private members directly. - * - * @return void, nothing to return. - */ - static void reset_all_imu_data_to_test_defaults() - { - static const constexpr uint16_t TEST_VAL_UINT16 = 65535U; - static const constexpr uint16_t TEST_VAL_UINT8 = 255; - test_imu->time_stamp = 0UL; - - test_imu->raw_accel_X = TEST_VAL_UINT16; - test_imu->raw_accel_Y = TEST_VAL_UINT16; - test_imu->raw_accel_Z = TEST_VAL_UINT16; - test_imu->accel_accuracy = static_cast(BNO08xAccuracy::UNDEFINED); - - test_imu->raw_lin_accel_X = TEST_VAL_UINT16; - test_imu->raw_lin_accel_Y = TEST_VAL_UINT16; - test_imu->raw_lin_accel_Z = TEST_VAL_UINT16; - test_imu->accel_lin_accuracy = static_cast(BNO08xAccuracy::UNDEFINED); - - test_imu->raw_calib_gyro_X = TEST_VAL_UINT16; - test_imu->raw_calib_gyro_Y = TEST_VAL_UINT16; - test_imu->raw_calib_gyro_Z = TEST_VAL_UINT16; - - // reset quaternion to nan - test_imu->raw_quat_I = 0U; - test_imu->raw_quat_J = 0U; - test_imu->raw_quat_K = 0U; - test_imu->raw_quat_real = 0U; - test_imu->raw_quat_radian_accuracy = static_cast(BNO08xAccuracy::UNDEFINED); - test_imu->quat_accuracy = static_cast(BNO08xAccuracy::UNDEFINED); - - test_imu->integrated_gyro_velocity_X = TEST_VAL_UINT16; - test_imu->integrated_gyro_velocity_Y = TEST_VAL_UINT16; - test_imu->integrated_gyro_velocity_Z = TEST_VAL_UINT16; - - test_imu->gravity_X = TEST_VAL_UINT16; - test_imu->gravity_Y = TEST_VAL_UINT16; - test_imu->gravity_Z = TEST_VAL_UINT16; - test_imu->gravity_accuracy = static_cast(BNO08xAccuracy::UNDEFINED); - - test_imu->raw_uncalib_gyro_X = TEST_VAL_UINT16; - test_imu->raw_uncalib_gyro_Y = TEST_VAL_UINT16; - test_imu->raw_uncalib_gyro_Z = TEST_VAL_UINT16; - test_imu->raw_bias_X = TEST_VAL_UINT16; - test_imu->raw_bias_Y = TEST_VAL_UINT16; - test_imu->raw_bias_Z = TEST_VAL_UINT16; - - test_imu->raw_magf_X = TEST_VAL_UINT16; - test_imu->raw_magf_Y = TEST_VAL_UINT16; - test_imu->raw_magf_Z = TEST_VAL_UINT16; - test_imu->magf_accuracy = static_cast(BNO08xAccuracy::UNDEFINED); - - test_imu->tap_detector = TEST_VAL_UINT8; - test_imu->step_count = TEST_VAL_UINT16; - test_imu->stability_classifier = static_cast(BNO08xStability::UNDEFINED); - test_imu->activity_classifier = static_cast(BNO08xActivity::UNDEFINED); - - test_imu->mems_raw_accel_X = TEST_VAL_UINT16; - test_imu->mems_raw_accel_Y = TEST_VAL_UINT16; - test_imu->mems_raw_accel_Z = TEST_VAL_UINT16; - - test_imu->mems_raw_gyro_X = TEST_VAL_UINT16; - test_imu->mems_raw_gyro_Y = TEST_VAL_UINT16; - test_imu->mems_raw_gyro_Z = TEST_VAL_UINT16; - - test_imu->mems_raw_magf_X = TEST_VAL_UINT16; - test_imu->mems_raw_magf_Y = TEST_VAL_UINT16; - test_imu->mems_raw_magf_Z = TEST_VAL_UINT16; - } - - /** - * @brief Converts BNO08xAccuracy enum class object to string. - * - * @param report_data BNO08xAccuracy object to convert to string. - * - * @return The resulting string conversion. - */ - static const char* BNO08xAccuracy_to_str(BNO08xAccuracy accuracy) - { - switch (accuracy) - { - case BNO08xAccuracy::LOW: - return "LOW"; - case BNO08xAccuracy::MED: - return "MED"; - case BNO08xAccuracy::HIGH: - return "HIGH"; - case BNO08xAccuracy::UNDEFINED: - return "UNDEFINED"; - default: - return "INVALID"; - } - }; - - /** - * @brief Converts BNO08xStability enum class object to string. - * - * @param stability BNO08xStability object to convert to string. - * - * @return The resulting string conversion. - */ - static const char* BNO08xStability_to_str(BNO08xStability stability) - { - switch (stability) - { - case BNO08xStability::UNKNOWN: - return "UNKNOWN"; - case BNO08xStability::ON_TABLE: - return "ON TABLE"; - case BNO08xStability::STATIONARY: - return "STATIONARY"; - case BNO08xStability::UNDEFINED: - return "UNDEFINED"; - default: - return "INVALID"; - } - } - - /** - * @brief Converts BNO08xActivity enum class object to string. - * - * @param activity BNO08xActivity object to convert to string. - * - * @return The resulting string conversion. - */ - static const char* BNO08xActivity_to_str(BNO08xActivity activity) - { - switch (activity) - { - case BNO08xActivity::UNKNOWN: - return "UNKNOWN"; - case BNO08xActivity::IN_VEHICLE: - return "IN VEHICLE"; - case BNO08xActivity::ON_BICYCLE: - return "ON BICYCLE"; - case BNO08xActivity::ON_FOOT: - return "ON FOOT"; - case BNO08xActivity::STILL: - return "STILL"; - case BNO08xActivity::TILTING: - return "TILTING"; - case BNO08xActivity::WALKING: - return "WALKING"; - case BNO08xActivity::RUNNING: - return "RUNNING"; - case BNO08xActivity::ON_STAIRS: - return "ON STAIRS"; - case BNO08xActivity::UNDEFINED: - return "UNDEFINED"; - default: - return "INVALID"; - } - } -}; \ No newline at end of file diff --git a/include/BNO08xTestSuite.hpp b/include/BNO08xTestSuite.hpp deleted file mode 100644 index 98e0aac..0000000 --- a/include/BNO08xTestSuite.hpp +++ /dev/null @@ -1,105 +0,0 @@ -/** - * @file BNO08xTestSuite.hpp - * @author Myles Parfeniuk - * - * - * @warning YOU MUST ADD THE FOLLOWING LINE TO YOUR MAIN PROJECTS CMakeLists.txt IN ORDER FOR THIS TEST SUITE TO BE BUILT WITH PROJECT: - * set(TEST_COMPONENTS "esp32_BNO08x" CACHE STRING "Components to test.") - */ -#pragma once - -#include -#include -#include "unity.h" -#include "BNO08xTestHelper.hpp" - -/** - * @class BNO08xTestSuite - * - * @brief BNO08x unit test launch point class. - * */ -class BNO08xTestSuite -{ - private: - static void print_begin_tests_banner(const char* test_set_name) - { - printf("####################### BEGIN TESTS: %s #######################\n\r", test_set_name); - } - - static void print_end_tests_banner(const char* test_set_name) - { - printf("####################### END TESTS: %s #######################\n\r", test_set_name); - } - - public: - static void run_all_tests() - { - UNITY_BEGIN(); - run_init_deinit_tests(false); - run_single_report_tests(false); - run_multi_report_tests(false); - run_callback_tests(false); - UNITY_END(); - } - - static void run_init_deinit_tests(bool call_unity_end_begin = true) - { - print_begin_tests_banner("init_denit_tests"); - - if (call_unity_end_begin) - UNITY_BEGIN(); - - unity_run_tests_by_tag("[InitComprehensive]", false); - unity_run_tests_by_tag("[InitDenit]", false); - - if (call_unity_end_begin) - UNITY_END(); - - print_end_tests_banner("init_denit_tests"); - } - - static void run_single_report_tests(bool call_unity_end_begin = true) - { - print_begin_tests_banner("single_report_tests"); - - if (call_unity_end_begin) - UNITY_BEGIN(); - - unity_run_tests_by_tag("[SingleReportEnableDisable]", false); - - if (call_unity_end_begin) - UNITY_END(); - - print_end_tests_banner("single_report_tests"); - } - - static void run_multi_report_tests(bool call_unity_end_begin = true) - { - print_begin_tests_banner("multi_report_tests"); - - if (call_unity_end_begin) - UNITY_BEGIN(); - - unity_run_tests_by_tag("[MultiReportEnableDisable]", false); - - if (call_unity_end_begin) - UNITY_END(); - - print_end_tests_banner("multi_report_tests"); - } - - static void run_callback_tests(bool call_unity_end_begin = true) - { - print_begin_tests_banner("run_callback_tests"); - - if (call_unity_end_begin) - UNITY_BEGIN(); - - unity_run_tests_by_tag("[CallbackTests]", false); - - if (call_unity_end_begin) - UNITY_END(); - - print_end_tests_banner("run_callback_tests"); - } -}; \ No newline at end of file diff --git a/include/BNO08x_macros.hpp b/include/BNO08x_macros.hpp index d5a94d0..0cda336 100644 --- a/include/BNO08x_macros.hpp +++ b/include/BNO08x_macros.hpp @@ -68,256 +68,3 @@ #define PARSE_PACKET_LENGTH(packet_ptr) \ (UINT16_CLR_LSB(static_cast(packet_ptr->header[1]) << 8U) | UINT16_CLR_MSB(static_cast(packet_ptr->header[0]))) -/** - * @brief Parse timestamp from SHTP packet. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return Packet timestamp. - */ -#define PARSE_PACKET_TIMESTAMP(packet_ptr) \ - (UINT32_MSK_BYTE(static_cast(packet->body[4]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast(packet->body[3]) << 16UL, 2UL) | \ - UINT32_MSK_BYTE(static_cast(packet->body[2]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast(packet->body[1]), 0UL)) - -// product id report parsing - -/** - * @brief Parse reset reason from SHTP packet containing product ID report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return Reset reason. - */ -#define PARSE_PRODUCT_ID_REPORT_RESET_REASON(packet_ptr) UINT32_MSK_BYTE(static_cast(packet_ptr->body[1]), 0UL) - -/** - * @brief Parse sw part number from SHTP packet containing product ID report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return sw part number. - */ -#define PARSE_PRODUCT_ID_REPORT_SW_PART_NO(packet_ptr) \ - (UINT32_MSK_BYTE(static_cast(packet_ptr->body[7]) << 24UL, 3UL) | \ - UINT32_MSK_BYTE(static_cast(packet_ptr->body[6]) << 16UL, 2UL) | \ - UINT32_MSK_BYTE(static_cast(packet_ptr->body[5]) << 8UL, 1UL) | \ - UINT32_MSK_BYTE(static_cast(packet_ptr->body[4]), 0UL)) - -/** - * @brief Parse sw build number from SHTP packet containing product ID report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return sw build number. - */ -#define PARSE_PRODUCT_ID_REPORT_SW_BUILD_NO(packet_ptr) \ - UINT32_MSK_BYTE(static_cast(packet->body[11]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast(packet->body[10]) << 16UL, 2UL) | \ - UINT32_MSK_BYTE(static_cast(packet->body[9]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast(packet->body[8]), 0UL) - -/** - * @brief Parse sw version patch from SHTP packet containing product ID report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return sw version patch. - */ -#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_PATCH(packet_ptr) \ - (UINT32_MSK_BYTE(static_cast(packet->body[13]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast(packet->body[12]), 0UL)) - -/** - * @brief Parse product ID SHTP packet containing product ID report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return Product ID. - */ -#define PARSE_PRODUCT_ID_REPORT_PRODUCT_ID(packet_ptr) UINT32_MSK_BYTE(static_cast(packet->body[0]), 0UL) - -/** - * @brief Parse product sw version major containing product ID report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return sw version major. - */ -#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_MAJOR(packet_ptr) UINT32_MSK_BYTE(static_cast(packet->body[2]), 0UL) - -/** - * @brief Parse product sw version minor containing product ID report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return sw version minor. - */ -#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_MINOR(packet_ptr) UINT32_MSK_BYTE(static_cast(packet->body[3]), 0UL) - -// gyro report parsing - -/** - * @brief Parse quat I data from integrated gyro rotation vector report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return Quat I data. - */ -#define PARSE_GYRO_REPORT_RAW_QUAT_I(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[1]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[0]))) - -/** - * @brief Parse quat J data from integrated gyro rotation vector report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return Quat J data. - */ -#define PARSE_GYRO_REPORT_RAW_QUAT_J(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[3]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[2]))) - -/** - * @brief Parse quat K data from integrated gyro rotation vector report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return Quat K data. - */ -#define PARSE_GYRO_REPORT_RAW_QUAT_K(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[5]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[4]))) - -/** - * @brief Parse quat real data from integrated gyro rotation vector report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return Quat real data. - */ -#define PARSE_GYRO_REPORT_RAW_QUAT_REAL(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[7]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[6]))) - -/** - * @brief Parse x axis velocity data from integrated gyro rotation vector report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return x velocity data. - */ -#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_X(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[9]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[8]))) - -/** - * @brief Parse y axis velocity data from integrated gyro rotation vector report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return y velocity data. - */ -#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_Y(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[11]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[10]))) - -/** - * @brief Parse z axis velocity data from integrated gyro rotation vector report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return z velocity data. - */ -#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_Z(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[13]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[12]))) - -// input report parsing - -/** - * @brief Parse status bits from input report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return Input report status bits. - */ -#define PARSE_INPUT_REPORT_STATUS_BITS(packet) (packet->body[5 + 2] & 0x03U) - -/** - * @brief Parse report ID from input report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return Report ID. - */ -#define PARSE_INPUT_REPORT_REPORT_ID(packet) UINT16_CLR_MSB(static_cast(packet->body[5])) - -/** - * @brief Parse first data block from input report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return First data block of input report. - */ -#define PARSE_INPUT_REPORT_DATA_1(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[5 + 5]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[5 + 4]))) - -/** - * @brief Parse second data block from input report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return Second data block of input report. - */ -#define PARSE_INPUT_REPORT_DATA_2(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[5 + 7]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[5 + 6]))) - -/** - * @brief Parse third data block from input report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return third data block of input report. - */ -#define PARSE_INPUT_REPORT_DATA_3(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[5 + 9]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[5 + 8]))) - -/** - * @brief Parse fourth data block from input report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return fourth data block of input report. - */ -#define PARSE_INPUT_REPORT_DATA_4(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[5 + 11]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[5 + 10]))) - -/** - * @brief Parse fifth data block from input report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return fifth data block of input report. - */ -#define PARSE_INPUT_REPORT_DATA_5(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[5 + 13]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[5 + 12]))) - -/** - * @brief Parse sixth data block from input report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return sixth data block of input report. - */ -#define PARSE_INPUT_REPORT_DATA_6(packet) \ - (UINT16_CLR_LSB(static_cast(packet->body[5 + 15]) << 8U) | UINT16_CLR_MSB(static_cast(packet->body[5 + 14]))) - -/** - * @brief Checks if packet containing input report is a rotation vector report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return True if contained input report is rotation vector report. - */ -#define IS_ROTATION_VECTOR_REPORT(packet) \ - ((packet)->body[5] == SENSOR_REPORT_ID_ROTATION_VECTOR || (packet)->body[5] == SENSOR_REPORT_ID_GAME_ROTATION_VECTOR || \ - (packet)->body[5] == SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR || \ - (packet)->body[5] == SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR) - -// frs read response report parsing - -/** - * @brief Parse FRS record ID from FRS read response report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return FRS record ID. - */ -#define PARSE_FRS_READ_RESPONSE_REPORT_RECORD_ID(packet_body) \ - (UINT16_CLR_LSB(static_cast(packet_body[13]) << 8U) | UINT16_CLR_MSB(static_cast(packet_body[12]))) - -/** - * @brief Parse data block 1 from FRS read response report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return FRS read response data block 1. - */ -#define PARSE_FRS_READ_RESPONSE_REPORT_DATA_1(packet_body) \ - (UINT32_MSK_BYTE(static_cast(packet_body[7]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast(packet_body[6]) << 16UL, 2UL) | \ - UINT32_MSK_BYTE(static_cast(packet_body[5]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast(packet_body[4]), 0UL)) - -/** - * @brief Parse data block 2 from FRS read response report. - * - * @param packet Pointer to bno08x_rx_packet_t containing data. - * @return FRS read response data block 2. - */ -#define PARSE_FRS_READ_RESPONSE_REPORT_DATA_2(packet_body) \ - (UINT32_MSK_BYTE(static_cast(packet_body[11]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast(packet_body[10]) << 16UL, 2UL) | \ - UINT32_MSK_BYTE(static_cast(packet_body[9]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast(packet_body[8]), 0UL)) diff --git a/source/BNO08x.cpp b/source/BNO08x.cpp index 0fd6701..4ba614f 100644 --- a/source/BNO08x.cpp +++ b/source/BNO08x.cpp @@ -17,10 +17,7 @@ BNO08x::BNO08x(bno08x_config_t imu_config) , evt_grp_task_flow(xEventGroupCreate()) , queue_rx_data(xQueueCreate(1, sizeof(sh2_packet_t))) , queue_tx_data(xQueueCreate(1, sizeof(sh2_packet_t))) - , queue_frs_read_data(xQueueCreate(1, RX_DATA_LENGTH * sizeof(uint8_t))) - , queue_reset_reason(xQueueCreate(1, sizeof(uint32_t))) , imu_config(imu_config) - , calibration_status(1) { } @@ -51,8 +48,6 @@ BNO08x::~BNO08x() // delete queues vQueueDelete(queue_rx_data); vQueueDelete(queue_tx_data); - vQueueDelete(queue_frs_read_data); - vQueueDelete(queue_reset_reason); // delete event groups vEventGroupDelete(evt_grp_spi); @@ -97,16 +92,6 @@ bool BNO08x::initialize() if (!hard_reset()) return false; - if (get_reset_reason() == BNO08xResetReason::UNDEFINED) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGE(TAG, "Initialization failed, undefined reset reason returned after reset."); - #endif - // clang-format on - return false; - } - // clang-format off #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS ESP_LOGI(TAG, "Successfully initialized...."); @@ -178,8 +163,6 @@ esp_err_t BNO08x::init_config_args() return ESP_ERR_INVALID_ARG; } - reset_all_data_to_defaults(); // reset data members that are returned by public getter APIs (for ex. get_roll_deg()) - // SPI bus config bus_config.mosi_io_num = imu_config.io_mosi; // assign mosi gpio pin bus_config.miso_io_num = imu_config.io_miso; // assign miso gpio pin @@ -596,147 +579,14 @@ esp_err_t BNO08x::deinit_spi() return ret; } -/** - * @brief Waits for data to be received over SPI, or host_int_timeout_ms to elapse. - * - * If no reports are currently enabled the hint pin interrupt will be re-enabled by this function. - * This function is for when the validity of packets is not a concern, it is for flushing packets - * we do not care about. - * - * @return True if data has been received over SPI within host_int_timeout_ms. - */ -bool BNO08x::wait_for_rx_done() -{ - bool success = false; - - // if no reports are enabled we can assume interrupts are disabled (see spi_task()) - if (xEventGroupGetBits(evt_grp_report_en) == 0) - gpio_intr_enable(imu_config.io_int); // re-enable interrupts - - // wait until an interrupt has been asserted and data received or timeout has occured - if (xEventGroupWaitBits(evt_grp_spi, EVT_GRP_SPI_RX_DONE_BIT, pdTRUE, pdTRUE, host_int_timeout_ms)) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_DEBUG_STATEMENTS - ESP_LOGI(TAG, "int asserted"); - #endif - // clang-format on - - success = true; - } - else - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGE(TAG, "Interrupt to host device never asserted."); - #endif - // clang-format on - - success = false; - } - - return success; -} - -/** - * @brief Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse. - * - * If no reports are currently enabled the hint pin interrupt will be re-enabled by this function. - * - * @return True if valid packet has been received within host_int_timeout_ms, false if otherwise. - */ -bool BNO08x::wait_for_data() -{ - bool success = false; - - // if no reports are enabled we can assume interrupts are disabled (see spi_task()) - if (xEventGroupGetBits(evt_grp_report_en) == 0) - gpio_intr_enable(imu_config.io_int); // re-enable interrupts - - // check to see receive operation has finished - if (xEventGroupWaitBits(evt_grp_spi, EVT_GRP_SPI_RX_DONE_BIT, pdTRUE, pdTRUE, host_int_timeout_ms)) - { - // wait until processing is done, this should never go to timeout; however, it will be set slightly after EVT_GRP_SPI_RX_DONE_BIT - if (xEventGroupWaitBits( - evt_grp_spi, EVT_GRP_SPI_RX_VALID_PACKET_BIT | EVT_GRP_SPI_RX_INVALID_PACKET_BIT, pdFALSE, pdFALSE, host_int_timeout_ms)) - { - // only return true if packet is valid - if (xEventGroupGetBits(evt_grp_spi) & EVT_GRP_SPI_RX_VALID_PACKET_BIT) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_DEBUG_STATEMENTS - ESP_LOGI(TAG, "Valid packet received."); - #endif - // clang-format on - - success = true; - } - else - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGE(TAG, "Invalid packet received."); - #endif - // clang-format on - } - } - } - else - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGE(TAG, "Interrupt to host device never asserted."); - #endif - // clang-format on - } - - xEventGroupClearBits(evt_grp_spi, EVT_GRP_SPI_RX_VALID_PACKET_BIT | EVT_GRP_SPI_RX_INVALID_PACKET_BIT); - return success; -} - -/** - * @brief Waits for a queued packet to be sent or host_int_timeout_ms to elapse. - * - * If no reports are currently enabled the hint pin interrupt will be re-enabled by this function. - * - * @return True if packet was sent within host_int_timeout_ms, false if otherwise. - */ -bool BNO08x::wait_for_tx_done() -{ - /* if no reports are enabled we can assume interrupts are disabled (see spi_task()) */ - if (xEventGroupGetBits(evt_grp_report_en) == 0) - gpio_intr_enable(imu_config.io_int); // re-enable interrupts - - if (xEventGroupWaitBits(evt_grp_spi, EVT_GRP_SPI_TX_DONE_BIT, pdTRUE, pdTRUE, host_int_timeout_ms)) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_DEBUG_STATEMENTS - ESP_LOGI(TAG, "Packet sent successfully."); - #endif - // clang-format on - - return true; - } - else - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGE(TAG, "Packet failed to send."); - #endif - // clang-format on - } - - return false; -} - /** * @brief Hard resets BNO08x sensor. * - * @return void, nothing to return + * @return True if reset succeeded. */ bool BNO08x::hard_reset() { - bool success = false; + bool reset_success = false; // resetting disables all reports xEventGroupClearBits(evt_grp_report_en, EVT_GRP_RPT_ALL_BITS); @@ -751,162 +601,10 @@ bool BNO08x::hard_reset() gpio_set_level(imu_config.io_rst, 1); // bring out of reset // Receive advertisement message on boot (see SH2 Ref. Manual 5.2 & 5.3) - if (!wait_for_rx_done()) // wait for receive operation to complete - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGE(TAG, "Reset Failed, interrupt to host device never asserted."); - #endif - // clang-format on - } - else - { - if (first_boot) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGI(TAG, "Received advertisement message."); - #endif - // clang-format on - } - // The BNO080 will then transmit an unsolicited Initialize Response (see SH2 Ref. Manual 6.4.5.2) - if (!wait_for_rx_done()) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGE(TAG, "Failed to receive initialize response on boot."); - #endif - // clang-format on - } - else if (first_boot) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGI(TAG, "Received initialize response."); - #endif - // clang-format on - - success = true; - } - } - - return success; + return reset_success; } -/** - * @brief Soft resets BNO08x sensor using executable channel. - * - * @return True if reset was success. - */ -bool BNO08x::soft_reset() -{ - bool success = false; - uint8_t commands[20] = {0}; - - // reseting resets all reports - xEventGroupClearBits(evt_grp_report_en, EVT_GRP_RPT_ALL_BITS); - - commands[0] = 1; - queue_packet(CHANNEL_EXECUTABLE, 1, commands); - success = wait_for_tx_done(); - - // flush any packets received - flush_rx_packets(3); - - return success; -} - -/** - * @brief Requests product ID, prints the returned info over serial, and returns the reason for the most resent reset. - * - * @return The reason for the most recent recent reset ( 1 = POR (power on reset), 2 = internal reset, 3 = watchdog - * timer, 4 = external reset 5 = other) - */ -BNO08xResetReason BNO08x::get_reset_reason() -{ - uint32_t reset_reason = 0; - bool reason_received = false; - - // queue request for product ID command - queue_request_product_id_command(); - // wait for transmit to finish - if (!wait_for_tx_done()) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGE(TAG, "Failed to send product ID report request"); - #endif - // clang-format on - } - else - { - // receive product ID report - for (int i = 0; i < 3; i++) - { - if(wait_for_data()) - if (xQueueReceive(queue_reset_reason, &reset_reason, 10UL / portTICK_PERIOD_MS)) - { - reason_received = true; - break; - } - } - - if (xEventGroupGetBits(evt_grp_report_en) == 0) - gpio_intr_disable(imu_config.io_int); // disable interrupts - - if (!reason_received) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGE(TAG, "Failed to receive product ID report."); - #endif - // clang-format on - } - } - - return static_cast(reset_reason); -} - -/** - * @brief Turns on/ brings BNO08x sensor out of sleep mode using executable channel. - * - * @return True if exiting sleep mode was success. - */ -bool BNO08x::mode_on() -{ - bool success = false; - uint8_t commands[20] = {0}; - - commands[0] = 2; - queue_packet(CHANNEL_EXECUTABLE, 1, commands); - success = wait_for_tx_done(); - - // flush any packets received - flush_rx_packets(3); - - return success; -} - -/** - * @brief Puts BNO08x sensor into sleep/low power mode using executable channel. - * - * @return True if entering sleep mode was success. - */ -bool BNO08x::mode_sleep() -{ - bool success = false; - uint8_t commands[20] = {0}; - - commands[0] = 3; - queue_packet(CHANNEL_EXECUTABLE, 1, commands); - success = wait_for_tx_done(); - - // flush any packets received - flush_rx_packets(3); - - return success; -} /** * @brief Receives/sends a SHTP packet via SPI. Sends any received packets to data_proc_task(). @@ -1024,465 +722,6 @@ esp_err_t BNO08x::transmit_packet_body(sh2_packet_t* rx_packet, sh2_packet_t* tx return ret; } -/** - * @brief Enables a sensor report for a given ID. - * - * @param report_ID The report ID of the sensor, i.e. SENSOR_REPORT_ID_X - * @param time_between_reports The desired time in microseconds between each report. The BNO08x will send reports according to this interval. - * @param report_evt_grp_bit The event group bit for the respective report, to indicate to spi_task() it's enabled, i.e. EVT_GRP_RPT_X - * - * If no reports were enabled prior to call, this function will re-enable interrupts on hint pin. - * - * @return void, nothing to return - */ -void BNO08x::enable_report(uint8_t report_ID, uint32_t time_between_reports, const EventBits_t report_evt_grp_bit, uint32_t special_config) -{ - // if no reports have been enabled before this one, we can assume the IMU has gone to sleep, wake it up with a reset - if ((xEventGroupGetBits(evt_grp_report_en) & ~report_evt_grp_bit) == 0) - hard_reset(); - - update_report_period_trackers(report_ID, time_between_reports); - - queue_feature_command(report_ID, time_between_reports, special_config); - if (wait_for_tx_done()) // wait for transmit operation to complete - { - xEventGroupSetBits(evt_grp_report_en, report_evt_grp_bit); - - // if no reports were enabled before this one, we can assume hint interrupt was disabled, re-enable to read reports - if ((xEventGroupGetBits(evt_grp_report_en) & ~report_evt_grp_bit) == 0) - { - gpio_intr_enable(imu_config.io_int); - } - } - - // flush the first few reports returned to ensure new data - flush_rx_packets(3); -} - -/** - * @brief Disables a sensor report for a given ID by setting its time interval to 0. - * - * @param report_ID The report ID of the sensor, i.e. SENSOR_REPORT_ID_X - * @param report_evt_grp_bit The event group bit for the respective report, to indicate to spi_task() it's disabled, i.e. EVT_GRP_RPT_X - * - * If no reports are enabled after disabling, this function will disable interrupts on hint pin. - * - * @return void, nothing to return - */ -void BNO08x::disable_report(uint8_t report_ID, const EventBits_t report_evt_grp_bit) -{ - update_report_period_trackers(report_ID, 0); - queue_feature_command(report_ID, 0); - if (wait_for_tx_done()) // wait for transmit operation to complete - { - xEventGroupClearBits(evt_grp_report_en, report_evt_grp_bit); - - /* - 6.5.5 of SH-2 Ref manual: "Note that SH-2 protocol version 1.0.1 and higher will send Get Feature Response messages - unsolicited if a sensor’s rate changes (e.g. due to change in the rate of a related sensor." - - For ex. after calling disable_rotation_vector(), the following response packet will be sent: - - I (3497) BNO08x: SHTP Header: - Raw 32 bit word: 0x15000205 - Packet Length: 21 - Channel Number: 2 - Sequence Number: 5 - Channel Type: Control - Body: - 0xFC 0x05 0x00 0x00 0x00 0x00 - 0x00 0x00 0x00 0x00 0x00 0x00 - 0x00 0x00 0x00 0x00 0x00 - - The 0xFC indicates it is a get feature response, the 0x05 indicates it is for the rotation vector, the rest of the body will be 0. - It might be wise to detect the response for the respective report being disabled, but is probably not necessary. For now, all get feature - responses are detected as valid packets. - */ - - // no reports enabled, disable hint to avoid wasting processing time - if ((xEventGroupGetBits(evt_grp_report_en)) == 0) - { - host_int_timeout_ms = HOST_INT_TIMEOUT_DEFAULT_MS; - gpio_intr_disable(imu_config.io_int); - } - - flush_rx_packets(2); - } -} - -/** - * @brief Queues an SHTP packet to be sent via SPI. - * - * @param SHTP channel number - * @param data_length data length in bytes - * @param commands array containing data to be sent - * - * @return void, nothing to return - */ -void BNO08x::queue_packet(uint8_t channel_number, uint8_t data_length, uint8_t* commands) -{ - - static uint8_t sequence_number[6] = {0}; // Sequence num of each com channel, 6 in total - sh2_packet_t tx_packet; - - tx_packet.length = data_length + 4; // add 4 bytes for header length - - tx_packet.header[0] = tx_packet.length & 0xFF; // packet length LSB - tx_packet.header[1] = tx_packet.length >> 8; // packet length MSB - tx_packet.header[2] = channel_number; // channel number to write to - tx_packet.header[3] = sequence_number[channel_number]++; // increment and send sequence number (packet counter) - - // save commands to send to tx_buffer - for (int i = 0; i < data_length; i++) - { - tx_packet.body[i] = commands[i]; - } - - xQueueSend(queue_tx_data, &tx_packet, 0); -} - -void BNO08x::flush_rx_packets(uint8_t flush_count) -{ - for (int i = 0; i < flush_count; i++) - wait_for_rx_done(); -} - -/** - * @brief Queues a packet containing a command. - * - * @param command The command to be sent. - * @param commands Command data array, pre-packed with exception of first 3 elements (command info) - * - * @return void, nothing to return - */ -void BNO08x::queue_command(uint8_t command, uint8_t* commands) -{ - static uint8_t command_sequence_number = 0; // Sequence num of command, sent within command packet. - - commands[0] = SHTP_REPORT_COMMAND_REQUEST; // Command Request - commands[1] = command_sequence_number++; // Increments automatically each function call - commands[2] = command; // Command - - queue_packet(CHANNEL_CONTROL, 12, commands); -} - -/** - * @brief Queues a packet containing the request product ID command. - * - * @return void, nothing to return - */ -void BNO08x::queue_request_product_id_command() -{ - uint8_t commands[20] = {0}; - - commands[0] = SHTP_REPORT_PRODUCT_ID_REQUEST; // request product ID and reset info - commands[1] = 0; // reserved - queue_packet(CHANNEL_CONTROL, 2, commands); -} - -/** - * @brief Sends command to calibrate accelerometer, gyro, and magnetometer. - * - * @return void, nothing to return - */ -void BNO08x::calibrate_all() -{ - queue_calibrate_command(CALIBRATE_ACCEL_GYRO_MAG); - wait_for_tx_done(); // wait for transmit operation to complete - vTaskDelay(CMD_EXECUTION_DELAY_MS); // allow some time for command to be executed -} - -/** - * @brief Sends command to calibrate accelerometer. - * - * @return void, nothing to return - */ -void BNO08x::calibrate_accelerometer() -{ - queue_calibrate_command(CALIBRATE_ACCEL); - wait_for_tx_done(); // wait for transmit operation to complete - vTaskDelay(CMD_EXECUTION_DELAY_MS); // allow some time for command to be executed -} - -/** - * @brief Sends command to calibrate gyro. - * - * @return void, nothing to return - */ -void BNO08x::calibrate_gyro() -{ - queue_calibrate_command(CALIBRATE_GYRO); - wait_for_tx_done(); // wait for transmit operation to complete - vTaskDelay(CMD_EXECUTION_DELAY_MS); // allow some time for command to be executed -} - -/** - * @brief Sends command to calibrate magnetometer. - * - * @return void, nothing to return - */ -void BNO08x::calibrate_magnetometer() -{ - queue_calibrate_command(CALIBRATE_MAG); - wait_for_tx_done(); // wait for transmit operation to complete - vTaskDelay(CMD_EXECUTION_DELAY_MS); // allow some time for command to be executed -} - -/** - * @brief Sends command to calibrate planar accelerometer - * - * @return void, nothing to return - */ -void BNO08x::calibrate_planar_accelerometer() -{ - queue_calibrate_command(CALIBRATE_PLANAR_ACCEL); - wait_for_tx_done(); // wait for transmit operation to complete - vTaskDelay(CMD_EXECUTION_DELAY_MS); // allow some time for command to be executed -} - -/** - * @brief Queues a packet containing a command to calibrate the specified sensor. - * - * @param sensor_to_calibrate The sensor to calibrate. - * - * @return void, nothing to return - */ -void BNO08x::queue_calibrate_command(uint8_t sensor_to_calibrate) -{ - uint8_t commands[20] = {0}; - - switch (sensor_to_calibrate) - { - case CALIBRATE_ACCEL: - commands[3] = 1; - break; - - case CALIBRATE_GYRO: - commands[4] = 1; - break; - - case CALIBRATE_MAG: - commands[5] = 1; - break; - - case CALIBRATE_PLANAR_ACCEL: - commands[7] = 1; - break; - - case CALIBRATE_ACCEL_GYRO_MAG: - commands[3] = 1; - commands[4] = 1; - commands[5] = 1; - break; - - case CALIBRATE_STOP: - // do nothing, send packet of all 0s - break; - - default: - - break; - } - - calibration_status = 1; - - queue_command(COMMAND_ME_CALIBRATE, commands); -} - -/** - * @brief Requests ME calibration status from BNO08x (see Ref. Manual 6.4.7.2) - * - * @return void, nothing to return - */ -void BNO08x::request_calibration_status() -{ - uint8_t commands[20] = {0}; - - commands[6] = 0x01; // P3 - 0x01 - Subcommand: Get ME Calibration - - // Using this commands packet, send a command - queue_command(COMMAND_ME_CALIBRATE, commands); - wait_for_tx_done(); // wait for transmit operation to complete - vTaskDelay(CMD_EXECUTION_DELAY_MS); // allow some time for command to be executed -} - -/** - * @brief Returns true if calibration has completed. - * - * @return True if calibration complete, false if otherwise. - */ -bool BNO08x::calibration_complete() -{ - if (calibration_status == 0) - return true; - - return false; -} - -/** - * @brief Sends command to end calibration procedure. - * - * @return void, nothing to return - */ -void BNO08x::end_calibration() -{ - queue_calibrate_command(CALIBRATE_STOP); // Disables all calibrations - wait_for_tx_done(); // wait for transmit operation to complete - vTaskDelay(CMD_EXECUTION_DELAY_MS); // allow some time for command to be executed -} - -/** - * @brief Sends command to save internal calibration data (See Ref. Manual 6.4.7). - * - * @return void, nothing to return - */ -void BNO08x::save_calibration() -{ - uint8_t commands[20] = {0}; - - // Using this shtpData packet, send a command - queue_command(COMMAND_DCD, commands); // Save DCD command - wait_for_tx_done(); // wait for transmit operation to complete - vTaskDelay(CMD_EXECUTION_DELAY_MS); // allow some time for command to be executed -} - -/** - * @brief Runs full calibration routine. - * - * Enables game rotation vector and magnetometer, starts ME calibration process. - * Waits for accuracy of returned quaternions and magnetic field vectors to be high, then saves calibration data and - * returns. - * - * @return True if calibration succeeded, false if otherwise. - */ -bool BNO08x::run_full_calibration_routine() -{ - float magf_x = 0; - float magf_y = 0; - float magf_z = 0; - BNO08xAccuracy magnetometer_accuracy = BNO08xAccuracy::LOW; - - float quat_I = 0; - float quat_J = 0; - float quat_K = 0; - float quat_real = 0; - BNO08xAccuracy quat_accuracy = BNO08xAccuracy::LOW; - - uint16_t high_accuracy = 0; - uint16_t save_calibration_attempt = 0; - - // Enable dynamic calibration for accel, gyro, and mag - calibrate_all(); // Turn on cal for Accel, Gyro, and Mag - - // Enable Game Rotation Vector output - enable_game_rotation_vector(100000UL); // Send data update every 100ms - - // Enable Magnetic Field output - enable_magnetometer(100000UL); // Send data update every 100ms - - while (1) - { - if (data_available()) - { - magf_x = get_magf_X(); - magf_y = get_magf_Y(); - magf_z = get_magf_Z(); - magnetometer_accuracy = get_magf_accuracy(); - - quat_I = get_quat_I(); - quat_J = get_quat_J(); - quat_K = get_quat_K(); - quat_real = get_quat_real(); - quat_accuracy = get_quat_accuracy(); - - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGI(TAG, "Magnetometer: x: %.3f y: %.3f z: %.3f, accuracy: %d", magf_x, magf_y, magf_z, static_cast(magnetometer_accuracy)); - ESP_LOGI(TAG, "Quaternion Rotation Vector: i: %.3f j: %.3f k: %.3f, real: %.3f, accuracy: %d", quat_I, quat_J, quat_K, quat_real, - static_cast(quat_accuracy)); - #endif - // clang-format on - - vTaskDelay(5UL / portTICK_PERIOD_MS); - - if ((magnetometer_accuracy >= BNO08xAccuracy::MED) && (quat_accuracy == BNO08xAccuracy::HIGH)) - high_accuracy++; - else - high_accuracy = 0; - - if (high_accuracy > 10) - { - save_calibration(); - request_calibration_status(); - - save_calibration_attempt = 0; - - while (save_calibration_attempt < 20) - { - if (data_available()) - { - if (calibration_complete()) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGW(TAG, "Calibration data successfully stored."); - #endif - // clang-format on - - return true; - } - else - { - save_calibration(); - request_calibration_status(); - save_calibration_attempt++; - } - } - } - - vTaskDelay(1 / portTICK_PERIOD_MS); - - if (save_calibration_attempt >= 20) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGE(TAG, "Calibration data failed to store."); - #endif - // clang-format on - } - - return false; - } - } - - vTaskDelay(5 / portTICK_PERIOD_MS); - } -} - -/** - * @brief Checks if BNO08x has asserted interrupt and sent data. - * - * @param ignore_no_reports_enabled Forces a wait for data even if no reports are enabled (default is false), used for unit tests. - * - * @return True if new data has been parsed and saved, false if otherwise. - */ -bool BNO08x::data_available(bool ignore_no_reports_enabled) -{ - if (!ignore_no_reports_enabled) - if (xEventGroupGetBits(evt_grp_report_en) == 0) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - ESP_LOGE(TAG, "No reports enabled."); - #endif - // clang-format on - - return false; - } - - return wait_for_data(); -} - /** * @brief Registers a callback to execute when new data from a report is received. * @@ -1495,2041 +734,6 @@ void BNO08x::register_cb(std::function cb_fxn) cb_list.push_back(cb_fxn); } -/** - * @brief Parses a packet received from bno08x, updating any data according to received reports. - * - * @param packet The packet to be parsed. - * @param notify_users Bool reference that is set to true if users should be notified of new data through callbacks/polling, false if packet is valid - * but users don't need to be notified. - * - * @return 0 if invalid packet, non-zero if otherwise. - */ -uint16_t BNO08x::parse_packet(sh2_packet_t* packet, bool& notify_users) -{ - notify_users = true; - - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_DEBUG_STATEMENTS - ESP_LOGW(TAG, "SHTP Header RX'd: 0x%X 0x%X 0x%X 0x%X", packet->header[0], packet->header[1], packet->header[2], packet->header[3]); - #endif - // clang-format on - - switch (packet->body[0]) - { - case SHTP_REPORT_PRODUCT_ID_RESPONSE: - return parse_product_id_report(packet); - break; - - case SHTP_REPORT_GET_FEATURE_RESPONSE: - notify_users = false; - return parse_feature_get_response_report(packet); - break; - - case SHTP_REPORT_FRS_READ_RESPONSE: - return parse_frs_read_response_report(packet); - break; - - default: - - break; - } - - switch (packet->header[2]) - { - case CHANNEL_REPORTS: - if (packet->body[0] == SHTP_REPORT_BASE_TIMESTAMP) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_DEBUG_STATEMENTS - ESP_LOGI(TAG, "RX'd packet, channel report"); - #endif - // clang-format on - - // this will update the rawAccelX, etc variables depending on which feature report is found - return parse_input_report(packet); - } - break; - - case CHANNEL_CONTROL: - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_DEBUG_STATEMENTS - ESP_LOGI(TAG, "RX'd packet, channel control"); - #endif - // clang-format on - - // this will update responses to commands, calibrationStatus, etc. - return parse_command_report(packet); - - break; - - case CHANNEL_GYRO: - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_DEBUG_STATEMENTS - ESP_LOGI(TAG, "Rx packet, channel gyro"); - #endif - // clang-format on - - // this will update the rawAccelX, etc variables depending on which feature report is found - return parse_gyro_integrated_rotation_vector_report(packet); - - break; - - case CHANNEL_COMMAND: - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_DEBUG_STATEMENTS - ESP_LOGI(TAG, "Rx packet, channel command"); - #endif - // clang-format on - - // todo add proper handling - notify_users = false; - return 1; - break; - - case CHANNEL_WAKE_REPORTS: - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_DEBUG_STATEMENTS - ESP_LOGI(TAG, "Rx packet, wake reports"); - #endif - // clang-format on - - // todo add proper handling - notify_users = false; - return 1; - break; - - default: - - break; - } - - return 0; -} - -/** - * @brief Parses product id report and prints device info. - * - * @param packet The packet containing product id report. - * - * @return 1, always valid. - */ -uint16_t BNO08x::parse_product_id_report(sh2_packet_t* packet) -{ - - const uint32_t reset_reason = PARSE_PRODUCT_ID_REPORT_RESET_REASON(packet); - - if (first_boot) - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_LOG_STATEMENTS - - const uint32_t product_id = PARSE_PRODUCT_ID_REPORT_PRODUCT_ID(packet); - const uint32_t sw_part_number = PARSE_PRODUCT_ID_REPORT_SW_PART_NO(packet); - const uint32_t sw_version_major = PARSE_PRODUCT_ID_REPORT_SW_VERSION_MAJOR(packet); - const uint32_t sw_version_minor = PARSE_PRODUCT_ID_REPORT_SW_VERSION_MINOR(packet); - const uint32_t sw_build_number = PARSE_PRODUCT_ID_REPORT_SW_BUILD_NO(packet); - const uint32_t sw_version_patch = PARSE_PRODUCT_ID_REPORT_SW_VERSION_PATCH(packet); - - // print product ID info packet - ESP_LOGI(TAG, - "Product ID Info: \n\r" - " ---------------------------\n\r" - " Product ID: 0x%" PRIx32 "\n\r" - " SW Version Major: 0x%" PRIx32 "\n\r" - " SW Version Minor: 0x%" PRIx32 "\n\r" - " SW Part Number: 0x%" PRIx32 "\n\r" - " SW Build Number: 0x%" PRIx32 "\n\r" - " SW Version Patch: 0x%" PRIx32 "\n\r" - " ---------------------------\n\r", - product_id, sw_version_major, sw_version_minor, sw_part_number, sw_build_number, sw_version_patch); - #endif - // clang-format on - - first_boot = false; - } - - xQueueSend(queue_reset_reason, &reset_reason, 0); - - return 1; -} - -/** - * @brief Sends packet to be parsed to meta data function call (FRS_read_data()) through queue. - * - * @param packet The packet containing the frs read report. - * - * @return 1, always valid, parsing for this happens in frs_read_word() - */ -uint16_t BNO08x::parse_frs_read_response_report(sh2_packet_t* packet) -{ - xQueueSend(queue_frs_read_data, &packet->body, 0); - return 1; -} - -/** - * @brief Parses get feature request report received from BNO08x. - * - * Note there is no means in this library currently to request feature reports, this is simply to handle the - * unsolicited get feature request reports that come with report rate changes (ie when a report is disabled by setting it 0) - * such that they aren't detected as invalid packets. - * - * "6.5.5 of SH-2 Ref manual: "Note that SH-2 protocol version 1.0.1 and higher will send Get Feature Response messages - * unsolicited if a sensor’s rate changes (e.g. due to change in the rate of a related sensor." - * - * @param packet bno8x_rx_packet_t containing the get feature request report to parse. - * - * @return The report ID of the respective sensor, for ex. SENSOR_REPORT_ID_ACCELEROMETER, 0 if invalid. - */ -uint16_t BNO08x::parse_feature_get_response_report(sh2_packet_t* packet) -{ - uint16_t report_ID = 0; - - // TODO: add get feature requests and handle this properly, this is just to handle the unsolcited get feature responses due to report rate changes - switch (packet->body[1]) - { - case SENSOR_REPORT_ID_ACCELEROMETER: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_GYROSCOPE: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_MAGNETIC_FIELD: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_LINEAR_ACCELERATION: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_ROTATION_VECTOR: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_GRAVITY: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_UNCALIBRATED_GYRO: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_GAME_ROTATION_VECTOR: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_GEOMAGNETIC_ROTATION_VECTOR: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_TAP_DETECTOR: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_STEP_COUNTER: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_STABILITY_CLASSIFIER: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_RAW_ACCELEROMETER: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_RAW_GYROSCOPE: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_RAW_MAGNETOMETER: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR: - report_ID = packet->body[0]; - break; - - case SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR: - report_ID = packet->body[0]; - break; - - default: - break; - } - - return report_ID; -} - -/** - * @brief Parses received input report sent by BNO08x. - * - * Unit responds with packet that contains the following: - * - * packet->header[0:3]: First, a 4 byte header - * packet->body[0:4]: Then a 5 byte timestamp of microsecond ticks since reading was taken - * packet->body[5 + 0]: Then a feature report ID (0x01 for Accel, 0x05 for Rotation Vector, etc...) - * packet->body[5 + 1]: Sequence number (See Ref.Manual 6.5.8.2) - * packet->body[5 + 2]: Status - * packet->body[3]: Delay - * packet->body[4:5]: i/accel x/gyro x/etc - * packet->body[6:7]: j/accel y/gyro y/etc - * packet->body[8:9]: k/accel z/gyro z/etc - * packet->body[10:11]: real/gyro temp/etc - * packet->body[12:13]: Accuracy estimate - * - * @param packet bno8x_rx_packet_t containing the input report to parse - * - * @return The report ID of the respective sensor, for ex. SENSOR_REPORT_ID_ACCELEROMETER, 0 if invalid. - */ -uint16_t BNO08x::parse_input_report(sh2_packet_t* packet) -{ - uint8_t status = PARSE_INPUT_REPORT_STATUS_BITS(packet); - uint16_t data_length = PARSE_PACKET_LENGTH(packet); - uint16_t report_ID = PARSE_INPUT_REPORT_REPORT_ID(packet); - uint16_t data[6] = {0}; - - data_length &= ~(1U << 15U); // Clear the MSbit. This bit indicates if this package is a continuation of the last. - // ignore it for now. TODO catch this as an error and exit - - data_length -= 4; // Remove the header bytes from the data count - time_stamp = PARSE_PACKET_TIMESTAMP(packet); - - parse_input_report_data(packet, data, data_length); - - // store these generic values to their proper global variable - switch (report_ID) - { - case SENSOR_REPORT_ID_ACCELEROMETER: - update_accelerometer_data(data, status); - break; - - case SENSOR_REPORT_ID_LINEAR_ACCELERATION: - update_lin_accelerometer_data(data, status); - break; - - case SENSOR_REPORT_ID_GYROSCOPE: - update_calibrated_gyro_data(data, status); - break; - - case SENSOR_REPORT_ID_UNCALIBRATED_GYRO: - update_uncalibrated_gyro_data(data, status); - break; - - case SENSOR_REPORT_ID_MAGNETIC_FIELD: - update_magf_data(data, status); - break; - - case SENSOR_REPORT_ID_TAP_DETECTOR: - update_tap_detector_data(packet); - break; - - case SENSOR_REPORT_ID_STEP_COUNTER: - update_step_counter_data(data); - break; - - case SENSOR_REPORT_ID_STABILITY_CLASSIFIER: - update_stability_classifier_data(packet); - break; - - case SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER: - update_personal_activity_classifier_data(packet); - break; - - case SENSOR_REPORT_ID_RAW_ACCELEROMETER: - update_raw_accelerometer_data(data); - break; - - case SENSOR_REPORT_ID_RAW_GYROSCOPE: - update_raw_gyro_data(data); - break; - - case SENSOR_REPORT_ID_RAW_MAGNETOMETER: - update_raw_magf_data(data); - break; - - case SHTP_REPORT_COMMAND_RESPONSE: - update_command_data(packet); - break; - - case SENSOR_REPORT_ID_GRAVITY: - update_gravity_data(data, status); - break; - - default: - if (IS_ROTATION_VECTOR_REPORT(packet)) - { - update_rotation_vector_data(data, status); - } - - break; - } - - // TODO additional feature reports may be strung together. Parse them all. - - return report_ID; -} - -/** - * @brief Parses data from received input report. - * - * @param packet bno8x_rx_packet_t containing the input report to parse - * @param data uint16_t array to store parsed data in - * @param data_length length of data in bytes parsed from packet header - * - * @return void, nothing to return - */ -void BNO08x::parse_input_report_data(sh2_packet_t* packet, uint16_t* data, uint16_t data_length) -{ - - data[0] = PARSE_INPUT_REPORT_DATA_1(packet); - data[1] = PARSE_INPUT_REPORT_DATA_2(packet); - data[2] = PARSE_INPUT_REPORT_DATA_3(packet); - - if (data_length - 5 > 9) - { - data[3] = PARSE_INPUT_REPORT_DATA_4(packet); - } - if (data_length - 5 > 11) - { - data[4] = PARSE_INPUT_REPORT_DATA_5(packet); - } - if (data_length - 5 > 13) - { - data[5] = PARSE_INPUT_REPORT_DATA_6(packet); - } -} - -/** - * @brief Parses received gyro integrated rotation vector report sent by BNO08x. - * - * Unit responds with packet that contains the following: - * - * packet->header[0:3]: First, a 4 byte header - * packet->body[0:1]: Raw quaternion component I - * packet->body[2:3]: Raw quaternion component J - * packet->body[4:5]: Raw quaternion component K - * packet->body[6:7]: Raw quaternion real component - * packet->body[8:9]: Raw gyroscope angular velocity in X axis - * packet->body[10:11]: Raw gyroscope angular velocity in Y axis - * packet->body[12:13]: Raw gyroscope angular velocity in Z axis - * - * @param packet bno8x_rx_packet_t containing the gyro integrated rotation vector report report to parse - * - * @return Integrated rotation vector report ID (always valid) - */ -uint16_t BNO08x::parse_gyro_integrated_rotation_vector_report(sh2_packet_t* packet) -{ - // the gyro-integrated input reports are sent via the special gyro channel and do not include the usual ID, sequence, and status fields - update_integrated_gyro_rotation_vector_data(packet); - - return SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR; -} - -/** - * @brief Parses received command report sent by BNO08x (See Ref. Manual 6.3.9) - * - * @return The command report ID, 0 if invalid. - */ -uint16_t BNO08x::parse_command_report(sh2_packet_t* packet) -{ - uint8_t command = 0; - - if (packet->body[0] == SHTP_REPORT_COMMAND_RESPONSE) - { - // The BNO080 responds with this report to command requests. It's up to use to remember which command we issued. - command = packet->body[2]; // This is the Command byte of the response - - if (command == COMMAND_ME_CALIBRATE) - { - calibration_status = packet->body[5 + 0]; // R0 - Status (0 = success, non-zero = fail) - } - return packet->body[0]; - } - else - { - // This sensor report ID is unhandled. - // See SH2 Ref. Manual to add additional feature reports as needed - } - - return 0; -} - -/** - * @brief Updates accelerometer data from parsed input report. - * - * @param data uint16_t array containing parsed input report data. - * @param status uint8_t containing parsed status bits (represents accuracy) - * - * @return void, nothing to return - */ -void BNO08x::update_accelerometer_data(uint16_t* data, uint8_t status) -{ - accel_accuracy = status; - raw_accel_X = data[0]; - raw_accel_Y = data[1]; - raw_accel_Z = data[2]; -} - -/** - * @brief Updates linear accelerometer data from parsed input report. - * - * @param data uint16_t array containing parsed input report data. - * @param status uint8_t containing parsed status bits (represents accuracy) - * - * @return void, nothing to return - */ -void BNO08x::update_lin_accelerometer_data(uint16_t* data, uint8_t status) -{ - accel_lin_accuracy = status; - raw_lin_accel_X = data[0]; - raw_lin_accel_Y = data[1]; - raw_lin_accel_Z = data[2]; -} - -/** - * @brief Updates linear gyro data from parsed input report. - * - * @param data uint16_t array containing parsed input report data. - * @param status uint8_t containing parsed status bits (represents accuracy) - * - * @return void, nothing to return - */ -void BNO08x::update_calibrated_gyro_data(uint16_t* data, uint8_t status) -{ - raw_calib_gyro_X = data[0]; - raw_calib_gyro_Y = data[1]; - raw_calib_gyro_Z = data[2]; -} - -/** - * @brief Updates uncalibrated gyro data from parsed input report. - * - * @param data uint16_t array containing parsed input report data. - * @param status uint8_t containing parsed status bits (represents accuracy) - * - * @return void, nothing to return - */ -void BNO08x::update_uncalibrated_gyro_data(uint16_t* data, uint8_t status) -{ - raw_uncalib_gyro_X = data[0]; - raw_uncalib_gyro_Y = data[1]; - raw_uncalib_gyro_Z = data[2]; - raw_bias_X = data[3]; - raw_bias_Y = data[4]; - raw_bias_Z = data[5]; -} - -/** - * @brief Updates magnetic field data from parsed input report. - * - * @param data uint16_t array containing parsed input report data. - * @param status uint8_t containing parsed status bits (represents accuracy) - * - * @return void, nothing to return - */ -void BNO08x::update_magf_data(uint16_t* data, uint8_t status) -{ - magf_accuracy = status; - raw_magf_X = data[0]; - raw_magf_Y = data[1]; - raw_magf_Z = data[2]; -} - -/** - * @brief Updates gravity data from parsed input report. - * - * @param data uint16_t array containing parsed input report data. - * @param status uint8_t containing parsed status bits (represents accuracy) - * - * @return void, nothing to return - */ -void BNO08x::update_gravity_data(uint16_t* data, uint8_t status) -{ - gravity_accuracy = status; - gravity_X = data[0]; - gravity_Y = data[1]; - gravity_Z = data[2]; -} - -/** - * @brief Updates roation vector data from parsed input report. - * - * @param data uint16_t array containing parsed input report data. - * @param status uint8_t containing parsed status bits (represents accuracy) - * - * @return void, nothing to return - */ -void BNO08x::update_rotation_vector_data(uint16_t* data, uint8_t status) -{ - quat_accuracy = status; - raw_quat_I = data[0]; - raw_quat_J = data[1]; - raw_quat_K = data[2]; - raw_quat_real = data[3]; - - // Only available on rotation vector and ar/vr stabilized rotation vector, - // not game rot vector and not ar/vr stabilized rotation vector - raw_quat_radian_accuracy = data[4]; -} - -/** - * @brief Updates step counter data from parsed input report. - * - * @param data uint16_t array containing parsed input report data. - * - * @return void, nothing to return - */ -void BNO08x::update_step_counter_data(uint16_t* data) -{ - step_count = data[2]; // bytes 8/9 -} - -/** - * @brief Updates raw accelerometer data from parsed input report. - * - * @param data uint16_t array containing parsed input report data. - * - * @return void, nothing to return - */ -void BNO08x::update_raw_accelerometer_data(uint16_t* data) -{ - mems_raw_accel_X = data[0]; - mems_raw_accel_Y = data[1]; - mems_raw_accel_Z = data[2]; -} - -/** - * @brief Updates raw gyro data from parsed input report. - * - * @param data uint16_t array containing parsed input report data. - * - * @return void, nothing to return - */ -void BNO08x::update_raw_gyro_data(uint16_t* data) -{ - mems_raw_gyro_X = data[0]; - mems_raw_gyro_Y = data[1]; - mems_raw_gyro_Z = data[2]; -} - -/** - * @brief Updates raw magnetic field data from parsed input report. - * - * @param data uint16_t array containing parsed input report data. - * - * @return void, nothing to return - */ -void BNO08x::update_raw_magf_data(uint16_t* data) -{ - mems_raw_magf_X = data[0]; - mems_raw_magf_Y = data[1]; - mems_raw_magf_Z = data[2]; -} - -/** - * @brief Updates tap detector data from parsed input report. - * - * @param packet sh2_packet_t containing the packet with tap detector report. - * - * @return void, nothing to return - */ -void BNO08x::update_tap_detector_data(sh2_packet_t* packet) -{ - tap_detector = packet->body[5 + 4]; // Byte 4 only -} - -/** - * @brief Updates stability classifier data from parsed input report. - * - * @param packet sh2_packet_t containing the packet with stability classifier report. - * - * @return void, nothing to return - */ -void BNO08x::update_stability_classifier_data(sh2_packet_t* packet) -{ - stability_classifier = packet->body[5 + 4]; // Byte 4 only -} - -/** - * @brief Updates activity classifier data from parsed input report. - * - * @param packet sh2_packet_t containing the packet with activity classifier report. - * - * @return void, nothing to return - */ -void BNO08x::update_personal_activity_classifier_data(sh2_packet_t* packet) -{ - activity_classifier = packet->body[5 + 5]; // Most likely state - - // Load activity classification confidences into the array - if (activity_confidences != nullptr) - for (int i = 0; i < 9; i++) // Hardcoded to max of 9. TODO - bring in array size - activity_confidences[i] = packet->body[5 + 6 + i]; // 5 bytes of timestamp, byte 6 is first confidence - // byte -} - -/** - * @brief Updates command data from parsed input report. - * - * @param packet sh2_packet_t containing the packet with command response report. - * - * @return void, nothing to return - */ -void BNO08x::update_command_data(sh2_packet_t* packet) -{ - uint8_t command = 0; - - // the BNO080 responds with this report to command requests. It's up to use to remember which command we issued. - command = packet->body[5 + 2]; // This is the Command byte of the response - - if (command == COMMAND_ME_CALIBRATE) - calibration_status = packet->body[5 + 5]; // R0 - Status (0 = success, non-zero = fail) -} - -/** - * @brief Updates integrated gyro rotation vector data from SHTP channel 5 (CHANNEL_GYRO) special report data. - * - * @param packet sh2_packet_t containing the packet with command response report. - * - * @return void, nothing to return - */ -void BNO08x::update_integrated_gyro_rotation_vector_data(sh2_packet_t* packet) -{ - raw_quat_I = PARSE_GYRO_REPORT_RAW_QUAT_I(packet); - raw_quat_J = PARSE_GYRO_REPORT_RAW_QUAT_J(packet); - raw_quat_K = PARSE_GYRO_REPORT_RAW_QUAT_K(packet); - raw_quat_real = PARSE_GYRO_REPORT_RAW_QUAT_REAL(packet); - integrated_gyro_velocity_X = PARSE_GYRO_REPORT_RAW_GYRO_VEL_X(packet); - integrated_gyro_velocity_Y = PARSE_GYRO_REPORT_RAW_GYRO_VEL_Y(packet); - integrated_gyro_velocity_Z = PARSE_GYRO_REPORT_RAW_GYRO_VEL_Z(packet); -} - -/** - * @brief Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_game_rotation_vector(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_GAME_ROTATION_VECTOR, time_between_reports, EVT_GRP_RPT_GAME_ROTATION_VECTOR_BIT); -} - -/** - * @brief Sends command to enable rotation vector reports (See Ref. Manual 6.5.18) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_rotation_vector(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_ROTATION_VECTOR, time_between_reports, EVT_GRP_RPT_ROTATION_VECTOR_BIT); -} - -/** - * @brief Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6.5.42) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_ARVR_stabilized_rotation_vector(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR, time_between_reports, EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BIT); -} - -/** - * @brief Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6.5.43) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_ARVR_stabilized_game_rotation_vector(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR, time_between_reports, EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BIT); -} - -/** - * @brief Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6.5.44) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_gyro_integrated_rotation_vector(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR, time_between_reports, EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BIT); -} - -/** - * @brief Sends command to enable accelerometer reports (See Ref. Manual 6.5.9) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_accelerometer(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_ACCELEROMETER, time_between_reports, EVT_GRP_RPT_ACCELEROMETER_BIT); -} - -/** - * @brief Sends command to enable linear accelerometer reports (See Ref. Manual 6.5.10) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_linear_accelerometer(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_LINEAR_ACCELERATION, time_between_reports, EVT_GRP_RPT_LINEAR_ACCELEROMETER_BIT); -} - -/** - * @brief Sends command to enable gravity reading reports (See Ref. Manual 6.5.11) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_gravity(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_GRAVITY, time_between_reports, EVT_GRP_RPT_GRAVITY_BIT); -} - -/** - * @brief Sends command to enable calibrated gyro reports (See Ref. Manual 6.5.13) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_calibrated_gyro(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_GYROSCOPE, time_between_reports, EVT_GRP_RPT_GYRO_BIT); -} - -/** - * @brief Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.5.14) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_uncalibrated_gyro(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_UNCALIBRATED_GYRO, time_between_reports, EVT_GRP_RPT_GYRO_UNCALIBRATED_BIT); -} - -/** - * @brief Sends command to enable magnetometer reports (See Ref. Manual 6.5.16) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_magnetometer(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_MAGNETIC_FIELD, time_between_reports, EVT_GRP_RPT_MAGNETOMETER_BIT); -} - -/** - * @brief Sends command to enable tap detector reports (See Ref. Manual 6.5.27) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_tap_detector(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_TAP_DETECTOR, time_between_reports, EVT_GRP_RPT_TAP_DETECTOR_BIT); -} - -/** - * @brief Sends command to enable step counter reports (See Ref. Manual 6.5.29) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_step_counter(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_STEP_COUNTER, time_between_reports, EVT_GRP_RPT_STEP_COUNTER_BIT); -} - -/** - * @brief Sends command to enable activity stability classifier reports (See Ref. Manual 6.5.31) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_stability_classifier(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_STABILITY_CLASSIFIER, time_between_reports, EVT_GRP_RPT_STABILITY_CLASSIFIER_BIT); -} - -/** - * @brief Sends command to enable activity classifier reports (See Ref. Manual 6.5.36) - * - * @param time_between_reports Desired time between reports in microseconds. - * @param activities_to_enable Desired activities to enable (0x1F enables all). - * @param activity_confidence_vals Returned activity level confidences. - * @return void, nothing to return - */ -void BNO08x::enable_activity_classifier( - uint32_t time_between_reports, BNO08xActivityEnable activities_to_enable, uint8_t (&activity_confidence_vals)[9]) -{ - activity_confidences = activity_confidence_vals; // Store pointer to array - enable_report(SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER, time_between_reports, EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BIT, - static_cast(activities_to_enable)); -} - -/** - * @brief Sends command to enable raw MEMs accelerometer reports (See Ref. Manual 6.5.8) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_raw_mems_accelerometer(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_RAW_ACCELEROMETER, time_between_reports, EVT_GRP_RPT_RAW_ACCELEROMETER_BIT); -} - -/** - * @brief Sends command to enable raw MEMs gyro reports (See Ref. Manual 6.5.12) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_raw_mems_gyro(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_RAW_GYROSCOPE, time_between_reports, EVT_GRP_RPT_RAW_GYRO_BIT); -} - -/** - * @brief Sends command to enable raw MEMs magnetometer reports (See Ref. Manual 6.5.15) - * - * @param time_between_reports Desired time between reports in microseconds. - * @return void, nothing to return - */ -void BNO08x::enable_raw_mems_magnetometer(uint32_t time_between_reports) -{ - enable_report(SENSOR_REPORT_ID_RAW_MAGNETOMETER, time_between_reports, EVT_GRP_RPT_RAW_MAGNETOMETER_BIT); -} - -/** - * @brief Sends command to disable rotation vector reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_rotation_vector() -{ - disable_report(SENSOR_REPORT_ID_ROTATION_VECTOR, EVT_GRP_RPT_ROTATION_VECTOR_BIT); -} - -/** - * @brief Sends command to disable game rotation vector reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_game_rotation_vector() -{ - disable_report(SENSOR_REPORT_ID_GAME_ROTATION_VECTOR, EVT_GRP_RPT_GAME_ROTATION_VECTOR_BIT); -} - -/** - * @brief Sends command to disable ARVR stabilized rotation vector reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_ARVR_stabilized_rotation_vector() -{ - disable_report(SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR, EVT_GRP_RPT_ARVR_S_ROTATION_VECTOR_BIT); -} - -/** - * @brief Sends command to disable ARVR stabilized game rotation vector reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_ARVR_stabilized_game_rotation_vector() -{ - disable_report(SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR, EVT_GRP_RPT_ARVR_S_GAME_ROTATION_VECTOR_BIT); -} - -/** - * @brief Sends command to disable gyro integrated rotation vector reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_gyro_integrated_rotation_vector() -{ - disable_report(SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR, EVT_GRP_RPT_GYRO_ROTATION_VECTOR_BIT); -} - -/** - * @brief Sends command to disable accelerometer reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_accelerometer() -{ - disable_report(SENSOR_REPORT_ID_ACCELEROMETER, EVT_GRP_RPT_ACCELEROMETER_BIT); -} - -/** - * @brief Sends command to disable linear accelerometer reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_linear_accelerometer() -{ - disable_report(SENSOR_REPORT_ID_LINEAR_ACCELERATION, EVT_GRP_RPT_LINEAR_ACCELEROMETER_BIT); -} - -/** - * @brief Sends command to disable gravity reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_gravity() -{ - disable_report(SENSOR_REPORT_ID_GRAVITY, EVT_GRP_RPT_GRAVITY_BIT); -} - -/** - * @brief Sends command to disable calibrated gyro reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_calibrated_gyro() -{ - disable_report(SENSOR_REPORT_ID_GYROSCOPE, EVT_GRP_RPT_GYRO_BIT); -} - -/** - * @brief Sends command to disable uncalibrated gyro reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_uncalibrated_gyro() -{ - disable_report(SENSOR_REPORT_ID_UNCALIBRATED_GYRO, EVT_GRP_RPT_GYRO_UNCALIBRATED_BIT); -} - -/** - * @brief Sends command to disable magnetometer reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_magnetometer() -{ - disable_report(SENSOR_REPORT_ID_MAGNETIC_FIELD, EVT_GRP_RPT_MAGNETOMETER_BIT); -} - -/** - * @brief Sends command to disable tap detector reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_tap_detector() -{ - disable_report(SENSOR_REPORT_ID_TAP_DETECTOR, EVT_GRP_RPT_TAP_DETECTOR_BIT); -} - -/** - * @brief Sends command to disable step counter reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_step_counter() -{ - disable_report(SENSOR_REPORT_ID_STEP_COUNTER, EVT_GRP_RPT_STEP_COUNTER_BIT); -} - -/** - * @brief Sends command to disable stability reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_stability_classifier() -{ - disable_report(SENSOR_REPORT_ID_STABILITY_CLASSIFIER, EVT_GRP_RPT_STABILITY_CLASSIFIER_BIT); -} - -/** - * @brief Sends command to disable activity classifier reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_activity_classifier() -{ - activity_confidences = nullptr; - disable_report(SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER, EVT_GRP_RPT_ACTIVITY_CLASSIFIER_BIT); -} - -/** - * @brief Sends command to disable raw accelerometer reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_raw_mems_accelerometer() -{ - disable_report(SENSOR_REPORT_ID_RAW_ACCELEROMETER, EVT_GRP_RPT_RAW_ACCELEROMETER_BIT); -} - -/** - * @brief Sends command to disable raw gyro reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_raw_mems_gyro() -{ - disable_report(SENSOR_REPORT_ID_RAW_GYROSCOPE, EVT_GRP_RPT_RAW_GYRO_BIT); -} - -/** - * @brief Sends command to disable raw magnetometer reports by setting report interval to 0. - * - * @return void, nothing to return - */ -void BNO08x::disable_raw_mems_magnetometer() -{ - disable_report(SENSOR_REPORT_ID_RAW_MAGNETOMETER, EVT_GRP_RPT_RAW_MAGNETOMETER_BIT); -} - -/** - * @brief Sends command to tare an axis (See Ref. Manual 6.4.4.1) - * - * @param axis_sel Which axes to zero, can be TARE_AXIS_ALL (all axes) or TARE_AXIS_Z (only yaw) - * @param rotation_vector_basis Which rotation vector type to zero axes can be TARE_ROTATION_VECTOR, - * TARE_GAME_ROTATION_VECTOR, TARE_GEOMAGNETIC_ROTATION_VECTOR, etc.. - * @return void, nothing to return - */ -void BNO08x::tare_now(uint8_t axis_sel, uint8_t rotation_vector_basis) -{ - queue_tare_command(TARE_NOW, axis_sel, rotation_vector_basis); - wait_for_tx_done(); // wait for transmit operation to complete - vTaskDelay(CMD_EXECUTION_DELAY_MS); // allow some time for command to be executed -} - -/** - * @brief Sends command to save tare into non-volatile memory of BNO08x (See Ref. Manual 6.4.4.2) - * - * @return void, nothing to return - */ -void BNO08x::save_tare() -{ - queue_tare_command(TARE_PERSIST); - wait_for_tx_done(); // wait for transmit operation to complete - vTaskDelay(CMD_EXECUTION_DELAY_MS); // allow some time for command to be executed -} - -/** - * @brief Sends command to clear persistent tare settings in non-volatile memory of BNO08x (See Ref. Manual 6.4.4.3) - * - * @return void, nothing to return - */ -void BNO08x::clear_tare() -{ - queue_tare_command(TARE_SET_REORIENTATION); - wait_for_tx_done(); // wait for transmit operation to complete - vTaskDelay(CMD_EXECUTION_DELAY_MS); // allow some time for command to be executed -} - -/** - * @brief Converts a register value to a float using its associated Q point. (See - * https://en.wikipedia.org/wiki/Q_(number_format)) - * - * @param q_point Q point value associated with register. - * @param fixed_point_value The fixed point value to convert. - * - * @return void, nothing to return - */ -float BNO08x::q_to_float(int16_t fixed_point_value, uint8_t q_point) -{ - float q_float = fixed_point_value; - q_float *= pow(2, q_point * -1); - return (q_float); -} - -/** - * @brief Return timestamp of most recent report. - * - * @return uint32_t containing the timestamp of the most recent report in microseconds. - */ -uint32_t BNO08x::get_time_stamp() -{ - return time_stamp; -} - -/** - * @brief Resets all data returned by public getter APIs to initial values of 0 and low accuracy. - * - * @return void, nothing to return - */ -void BNO08x::reset_all_data_to_defaults() -{ - time_stamp = 0UL; - - raw_accel_X = 0U; - raw_accel_Y = 0U; - raw_accel_Z = 0U; - accel_accuracy = static_cast(BNO08xAccuracy::UNDEFINED); - - raw_lin_accel_X = 0U; - raw_lin_accel_Y = 0U; - raw_lin_accel_Z = 0U; - accel_lin_accuracy = static_cast(BNO08xAccuracy::UNDEFINED); - - raw_calib_gyro_X = 0U; - raw_calib_gyro_Y = 0U; - raw_calib_gyro_Z = 0U; - - // reset quaternion to nan - raw_quat_I = 0U; - raw_quat_J = 0U; - raw_quat_K = 0U; - raw_quat_real = 0U; - raw_quat_radian_accuracy = static_cast(BNO08xAccuracy::UNDEFINED); - quat_accuracy = static_cast(BNO08xAccuracy::UNDEFINED); - - integrated_gyro_velocity_X = 0U; - integrated_gyro_velocity_Y = 0U; - integrated_gyro_velocity_Z = 0U; - - gravity_X = 0U; - gravity_Y = 0U; - gravity_Z = 0U; - gravity_accuracy = static_cast(BNO08xAccuracy::UNDEFINED); - - raw_uncalib_gyro_X = 0U; - raw_uncalib_gyro_Y = 0U; - raw_uncalib_gyro_Z = 0U; - raw_bias_X = 0U; - raw_bias_Y = 0U; - raw_bias_Z = 0U; - - raw_magf_X = 0U; - raw_magf_Y = 0U; - raw_magf_Z = 0U; - magf_accuracy = static_cast(BNO08xAccuracy::UNDEFINED); - - tap_detector = 0U; - step_count = 0U; - stability_classifier = 0U; - activity_classifier = 0U; - - mems_raw_accel_X = 0U; - mems_raw_accel_Y = 0U; - mems_raw_accel_Z = 0U; - - mems_raw_gyro_X = 0U; - mems_raw_gyro_Y = 0U; - mems_raw_gyro_Z = 0U; - - mems_raw_magf_X = 0U; - mems_raw_magf_Y = 0U; - mems_raw_magf_Z = 0U; -} - -/** - * @brief Get the full magnetic field vector. - * - * @param x Reference variable to save reported x magnitude. - * @param y Reference variable to save reported y magnitude. - * @param x Reference variable to save reported z magnitude. - * @param accuracy Reference variable to save reported accuracy. - * - * @return void, nothing to return - */ -void BNO08x::get_magf(float& x, float& y, float& z, BNO08xAccuracy& accuracy) -{ - x = q_to_float(raw_magf_X, MAGNETOMETER_Q1); - y = q_to_float(raw_magf_Y, MAGNETOMETER_Q1); - z = q_to_float(raw_magf_Z, MAGNETOMETER_Q1); - accuracy = static_cast(magf_accuracy); -} - -/** - * @brief Get X component of magnetic field vector. - * - * @return The reported X component of magnetic field vector. - */ -float BNO08x::get_magf_X() -{ - float mag = q_to_float(raw_magf_X, MAGNETOMETER_Q1); - return mag; -} - -/** - * @brief Get Y component of magnetic field vector. - * - * @return The reported Y component of magnetic field vector. - */ -float BNO08x::get_magf_Y() -{ - float mag = q_to_float(raw_magf_Y, MAGNETOMETER_Q1); - return mag; -} - -/** - * @brief Get Z component of magnetic field vector. - * - * @return The reported Z component of magnetic field vector. - */ -float BNO08x::get_magf_Z() -{ - float mag = q_to_float(raw_magf_Z, MAGNETOMETER_Q1); - return mag; -} - -/** - * @brief Get accuracy of reported magnetic field vector. - * - * @return The accuracy of reported magnetic field vector. - */ -BNO08xAccuracy BNO08x::get_magf_accuracy() -{ - return static_cast(magf_accuracy); -} - -/** - * @brief Get full reported gravity vector, units in m/s^2 - * - * @param x Reference variable to save X axis gravity. - * @param y Reference variable to save Y axis axis gravity. - * @param z Reference variable to save Z axis axis gravity. - * @param accuracy Reference variable to save reported gravity accuracy. - * - * @return void, nothing to return - */ -void BNO08x::get_gravity(float& x, float& y, float& z, BNO08xAccuracy& accuracy) -{ - x = q_to_float(gravity_X, GRAVITY_Q1); - y = q_to_float(gravity_Y, GRAVITY_Q1); - z = q_to_float(gravity_Z, GRAVITY_Q1); - accuracy = static_cast(gravity_accuracy); -} - -/** - * @brief Get the reported x axis gravity. - * - * @return x axis gravity in m/s^2 - */ -float BNO08x::get_gravity_X() -{ - return q_to_float(gravity_X, GRAVITY_Q1); -} - -/** - * @brief Get the reported y axis gravity. - * - * @return y axis gravity in m/s^2 - */ -float BNO08x::get_gravity_Y() -{ - return q_to_float(gravity_Y, GRAVITY_Q1); -} - -/** - * @brief Get the reported z axis gravity. - * - * @return z axis gravity in m/s^2 - */ -float BNO08x::get_gravity_Z() -{ - return q_to_float(gravity_Z, GRAVITY_Q1); -} - -/** - * @brief Get the reported gravity accuracy. - * - * @return Accuracy of reported gravity. - */ -BNO08xAccuracy BNO08x::get_gravity_accuracy() -{ - return static_cast(gravity_accuracy); -} - -/** - * @brief Get the reported rotation about x axis. - * - * @return Rotation about the x axis in radians. - */ -float BNO08x::get_roll() -{ - float t_0 = 0.0; - float t_1 = 0.0; - float dq_w = get_quat_real(); - float dq_x = get_quat_I(); - float dq_y = get_quat_J(); - float dq_z = get_quat_K(); - - float norm = sqrt(dq_w * dq_w + dq_x * dq_x + dq_y * dq_y + dq_z * dq_z); - dq_w = dq_w / norm; - dq_x = dq_x / norm; - dq_y = dq_y / norm; - dq_z = dq_z / norm; - - // roll (x-axis rotation) - t_0 = 2.0 * (dq_w * dq_x + dq_y * dq_z); - t_1 = 1.0 - (2.0 * ((dq_x * dq_x) + (dq_y * dq_y))); - - return atan2(t_0, t_1); -} - -/** - * @brief Get the reported rotation about y axis. - * - * @return Rotation about the y axis in radians. - */ -float BNO08x::get_pitch() -{ - float t_2 = 0.0; - float dq_w = get_quat_real(); - float dq_x = get_quat_I(); - float dq_y = get_quat_J(); - float dq_z = get_quat_K(); - float norm = sqrt(dq_w * dq_w + dq_x * dq_x + dq_y * dq_y + dq_z * dq_z); - - dq_w = dq_w / norm; - dq_x = dq_x / norm; - dq_y = dq_y / norm; - dq_z = dq_z / norm; - - // float ysqr = dqy * dqy; - - // pitch (y-axis rotation) - t_2 = 2.0 * ((dq_w * dq_y) - (dq_z * dq_x)); - t_2 = t_2 > 1.0 ? 1.0 : t_2; - t_2 = t_2 < -1.0 ? -1.0 : t_2; - - return asin(t_2); -} - -/** - * @brief Get the reported rotation about z axis. - * - * @return Rotation about the z axis in radians. - */ -float BNO08x::get_yaw() -{ - float t_3 = 0.0; - float t_4 = 0.0; - float dq_w = get_quat_real(); - float dq_x = get_quat_I(); - float dq_y = get_quat_J(); - float dq_z = get_quat_K(); - float norm = sqrt(dq_w * dq_w + dq_x * dq_x + dq_y * dq_y + dq_z * dq_z); - - dq_w = dq_w / norm; - dq_x = dq_x / norm; - dq_y = dq_y / norm; - dq_z = dq_z / norm; - - // yaw (z-axis rotation) - t_3 = 2.0 * ((dq_w * dq_z) + (dq_x * dq_y)); - t_4 = 1.0 - (2.0 * ((dq_y * dq_y) + (dq_z * dq_z))); - - return atan2(t_3, t_4); -} - -/** - * @brief Get the reported rotation about x axis. - * - * @return Rotation about the x axis in degrees. - */ -float BNO08x::get_roll_deg() -{ - return get_roll() * (180.0 / M_PI); -} - -/** - * @brief Get the reported rotation about y axis. - * - * @return Rotation about the y axis in degrees. - */ -float BNO08x::get_pitch_deg() -{ - return get_pitch() * (180.0 / M_PI); -} - -/** - * @brief Get the reported rotation about z axis. - * - * @return Rotation about the z axis in degrees. - */ -float BNO08x::get_yaw_deg() -{ - return get_yaw() * (180.0 / M_PI); -} - -/** - * @brief Get the full quaternion reading. - * - * @param i Reference variable to save reported i component of quaternion. - * @param j Reference variable to save reported j component of quaternion. - * @param k Reference variable to save reported k component of quaternion. - * @param real Reference variable to save reported real component of quaternion. - * @param rad_accuracy Reference variable to save reported raw quaternion radian accuracy. - * @param accuracy Reference variable to save reported quaternion accuracy. - * - * @return void, nothing to return - */ -void BNO08x::get_quat(float& i, float& j, float& k, float& real, float& rad_accuracy, BNO08xAccuracy& accuracy) -{ - i = q_to_float(raw_quat_I, ROTATION_VECTOR_Q1); - j = q_to_float(raw_quat_J, ROTATION_VECTOR_Q1); - k = q_to_float(raw_quat_K, ROTATION_VECTOR_Q1); - real = q_to_float(raw_quat_real, ROTATION_VECTOR_Q1); - rad_accuracy = q_to_float(raw_quat_radian_accuracy, ROTATION_VECTOR_Q1); - accuracy = static_cast(quat_accuracy); -} - -/** - * @brief Get I component of reported quaternion. - * - * @return The I component of reported quaternion. - */ -float BNO08x::get_quat_I() -{ - float quat = q_to_float(raw_quat_I, ROTATION_VECTOR_Q1); - return quat; -} - -/** - * @brief Get J component of reported quaternion. - * - * @return The J component of reported quaternion. - */ -float BNO08x::get_quat_J() -{ - float quat = q_to_float(raw_quat_J, ROTATION_VECTOR_Q1); - return quat; -} - -/** - * @brief Get K component of reported quaternion. - * - * @return The K component of reported quaternion. - */ -float BNO08x::get_quat_K() -{ - float quat = q_to_float(raw_quat_K, ROTATION_VECTOR_Q1); - return quat; -} - -/** - * @brief Get real component of reported quaternion. - * - * @return The real component of reported quaternion. - */ -float BNO08x::get_quat_real() -{ - float quat = q_to_float(raw_quat_real, ROTATION_VECTOR_Q1); - return quat; -} - -/** - * @brief Get radian accuracy of reported quaternion. - * - * @return The radian accuracy of reported quaternion. - */ -float BNO08x::get_quat_radian_accuracy() -{ - float quat = q_to_float(raw_quat_radian_accuracy, ROTATION_VECTOR_Q1); - return quat; -} - -/** - * @brief Get accuracy of reported quaternion. - * - * @return The accuracy of reported quaternion. - */ -BNO08xAccuracy BNO08x::get_quat_accuracy() -{ - return static_cast(quat_accuracy); -} - -/** - * @brief Get full acceleration (total acceleration of device, units in m/s^2). - * - * @param x Reference variable to save X axis acceleration. - * @param y Reference variable to save Y axis acceleration. - * @param z Reference variable to save Z axis acceleration. - * @param accuracy Reference variable to save reported acceleration accuracy. - * - * @return void, nothing to return - */ -void BNO08x::get_accel(float& x, float& y, float& z, BNO08xAccuracy& accuracy) -{ - x = q_to_float(raw_accel_X, ACCELEROMETER_Q1); - y = q_to_float(raw_accel_Y, ACCELEROMETER_Q1); - z = q_to_float(raw_accel_Z, ACCELEROMETER_Q1); - accuracy = static_cast(accel_accuracy); -} - -/** - * @brief Get x axis acceleration (total acceleration of device, units in m/s^2). - * - * @return The angular reported x axis acceleration. - */ -float BNO08x::get_accel_X() -{ - return q_to_float(raw_accel_X, ACCELEROMETER_Q1); -} - -/** - * @brief Get y axis acceleration (total acceleration of device, units in m/s^2). - * - * @return The angular reported y axis acceleration. - */ -float BNO08x::get_accel_Y() -{ - return q_to_float(raw_accel_Y, ACCELEROMETER_Q1); -} - -/** - * @brief Get z axis acceleration (total acceleration of device, units in m/s^2). - * - * @return The angular reported z axis acceleration. - */ -float BNO08x::get_accel_Z() -{ - return q_to_float(raw_accel_Z, ACCELEROMETER_Q1); -} - -/** - * @brief Get accuracy of linear acceleration. - * - * @return Accuracy of linear acceleration. - */ -BNO08xAccuracy BNO08x::get_accel_accuracy() -{ - return static_cast(accel_accuracy); -} - -/** - * @brief Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2). - * - * @param x Reference variable to save X axis acceleration. - * @param y Reference variable to save Y axis acceleration. - * @param z Reference variable to save Z axis acceleration. - * @param accuracy Reference variable to save reported linear acceleration accuracy. - * - * @return void, nothing to return - */ -void BNO08x::get_linear_accel(float& x, float& y, float& z, BNO08xAccuracy& accuracy) -{ - x = q_to_float(raw_lin_accel_X, LINEAR_ACCELEROMETER_Q1); - y = q_to_float(raw_lin_accel_Y, LINEAR_ACCELEROMETER_Q1); - z = q_to_float(raw_lin_accel_Z, LINEAR_ACCELEROMETER_Q1); - accuracy = static_cast(accel_lin_accuracy); -} - -/** - * @brief Get x axis linear acceleration (acceleration of device minus gravity, units in m/s^2) - * - * @return The angular reported x axis linear acceleration. - */ -float BNO08x::get_linear_accel_X() -{ - return q_to_float(raw_lin_accel_X, LINEAR_ACCELEROMETER_Q1); -} - -/** - * @brief Get y axis linear acceleration (acceleration of device minus gravity, units in m/s^2) - * - * @return The angular reported y axis linear acceleration. - */ -float BNO08x::get_linear_accel_Y() -{ - return q_to_float(raw_lin_accel_Y, LINEAR_ACCELEROMETER_Q1); -} - -/** - * @brief Get z axis linear acceleration (acceleration of device minus gravity, units in m/s^2) - * - * @return The angular reported z axis linear acceleration. - */ -float BNO08x::get_linear_accel_Z() -{ - return q_to_float(raw_lin_accel_Z, LINEAR_ACCELEROMETER_Q1); -} - -/** - * @brief Get accuracy of linear acceleration. - * - * @return Accuracy of linear acceleration. - */ -BNO08xAccuracy BNO08x::get_linear_accel_accuracy() -{ - return static_cast(accel_lin_accuracy); -} - -/** - * @brief Get full raw acceleration from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8). - * - * @param x Reference variable to save raw X axis acceleration. - * @param y Reference variable to save raw Y axis acceleration. - * @param z Reference variable to save raw Z axis acceleration. - * - * @return void, nothing to return - */ -void BNO08x::get_raw_mems_accel(uint16_t& x, uint16_t& y, uint16_t& z) -{ - x = mems_raw_accel_X; - y = mems_raw_accel_X; - z = mems_raw_accel_X; -} - -/** - * @brief Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8) - * - * @return Reported raw accelerometer x axis reading from physical MEMs sensor. - */ -uint16_t BNO08x::get_raw_mems_accel_X() -{ - return mems_raw_accel_X; -} - -/** - * @brief Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8) - * - * @return Reported raw accelerometer y axis reading from physical MEMs sensor. - */ -uint16_t BNO08x::get_raw_mems_accel_Y() -{ - return mems_raw_accel_Y; -} - -/** - * @brief Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8) - * - * @return Reported raw accelerometer z axis reading from physical MEMs sensor. - */ -uint16_t BNO08x::get_raw_mems_accel_Z() -{ - return mems_raw_accel_Z; -} - -/** - * @brief Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12) - * - * @param x Reference variable to save raw X axis data. - * @param y Reference variable to save raw Y axis data. - * @param z Reference variable to save raw Z axis data. - * - * @return void, nothing to return - */ -void BNO08x::get_raw_mems_gyro(uint16_t& x, uint16_t& y, uint16_t& z) -{ - x = mems_raw_gyro_X; - y = mems_raw_gyro_Y; - z = mems_raw_gyro_Z; -} - -/** - * @brief Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12) - * - * @return Reported raw gyroscope x axis reading from physical MEMs sensor. - */ -uint16_t BNO08x::get_raw_mems_gyro_X() -{ - return mems_raw_gyro_X; -} - -/** - * @brief Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12) - * - * @return Reported raw gyroscope y axis reading from physical MEMs sensor. - */ -uint16_t BNO08x::get_raw_mems_gyro_Y() -{ - return mems_raw_gyro_Y; -} - -/** - * @brief Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12) - * - * @return Reported raw gyroscope z axis reading from physical MEMs sensor. - */ -uint16_t BNO08x::get_raw_mems_gyro_Z() -{ - return mems_raw_gyro_Z; -} - -/** - * @brief Get raw magnetometer full reading from physical magnetometer sensor (See Ref. Manual 6.5.15) - * - * @param x Reference variable to save raw X axis data. - * @param y Reference variable to save raw Y axis data. - * @param z Reference variable to save raw Z axis data. - * - * @return void, nothing to return - */ -void BNO08x::get_raw_mems_magf(uint16_t& x, uint16_t& y, uint16_t& z) -{ - x = mems_raw_magf_X; - y = mems_raw_magf_Y; - z = mems_raw_magf_Z; -} - -/** - * @brief Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15) - * - * @return Reported raw magnetometer x axis reading from physical magnetometer sensor. - */ -uint16_t BNO08x::get_raw_mems_magf_X() -{ - return mems_raw_magf_X; -} - -/** - * @brief Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15) - * - * @return Reported raw magnetometer y axis reading from physical magnetometer sensor. - */ -uint16_t BNO08x::get_raw_mems_magf_Y() -{ - return mems_raw_magf_Y; -} - -/** - * @brief Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15) - * - * @return Reported raw magnetometer z axis reading from physical magnetometer sensor. - */ -uint16_t BNO08x::get_raw_mems_magf_Z() -{ - return mems_raw_magf_Z; -} - -/** - * @brief Get full rotational velocity with drift compensation (units in Rad/s). - * - * @param x Reference variable to save X axis angular velocity - * @param y Reference variable to save Y axis angular velocity - * @param z Reference variable to save Z axis angular velocity - * - * @return void, nothing to return - */ -void BNO08x::get_calibrated_gyro_velocity(float& x, float& y, float& z) -{ - x = q_to_float(raw_calib_gyro_X, GYRO_Q1); - y = q_to_float(raw_calib_gyro_Y, GYRO_Q1); - z = q_to_float(raw_calib_gyro_Z, GYRO_Q1); -} - -/** - * @brief Get calibrated gyro x axis angular velocity measurement. - * - * @return The angular reported x axis angular velocity from calibrated gyro (drift compensation applied). - */ -float BNO08x::get_calibrated_gyro_velocity_X() -{ - return q_to_float(raw_calib_gyro_X, GYRO_Q1); -} - -/** - * @brief Get calibrated gyro y axis angular velocity measurement. - * - * @return The angular reported y axis angular velocity from calibrated gyro (drift compensation applied). - */ -float BNO08x::get_calibrated_gyro_velocity_Y() -{ - return q_to_float(raw_calib_gyro_Y, GYRO_Q1); -} - -/** - * @brief Get calibrated gyro z axis angular velocity measurement. - * - * @return The angular reported z axis angular velocity from calibrated gyro (drift compensation applied). - */ -float BNO08x::get_calibrated_gyro_velocity_Z() -{ - return q_to_float(raw_calib_gyro_Z, GYRO_Q1); -} - -/** - * @brief Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is given but - * not applied. - * - * @param x Reference variable to save X axis angular velocity - * @param y Reference variable to save Y axis angular velocity - * @param z Reference variable to save Z axis angular velocity - * @param b_x Reference variable to save X axis drift estimate - * @param b_y Reference variable to save Y axis drift estimate - * @param b_z Reference variable to save Z axis drift estimate - * - * @return void, nothing to return - */ -void BNO08x::get_uncalibrated_gyro_velocity(float& x, float& y, float& z, float& b_x, float& b_y, float& b_z) -{ - x = q_to_float(raw_uncalib_gyro_X, GYRO_Q1); - y = q_to_float(raw_uncalib_gyro_Y, GYRO_Q1); - z = q_to_float(raw_uncalib_gyro_Z, GYRO_Q1); - b_x = q_to_float(raw_bias_X, GYRO_Q1); - b_y = q_to_float(raw_bias_Y, GYRO_Q1); - b_z = q_to_float(raw_bias_Z, GYRO_Q1); -} - -/** - * @brief Get uncalibrated gyro x axis angular velocity measurement. - * - * @return The angular reported x axis angular velocity from uncalibrated gyro. - */ -float BNO08x::get_uncalibrated_gyro_velocity_X() -{ - return q_to_float(raw_uncalib_gyro_X, GYRO_Q1); -} - -/** - * @brief Get uncalibrated gyro Y axis angular velocity measurement. - * - * @return The angular reported Y axis angular velocity from uncalibrated gyro. - */ -float BNO08x::get_uncalibrated_gyro_velocity_Y() -{ - return q_to_float(raw_uncalib_gyro_Y, GYRO_Q1); -} - -/** - * @brief Get uncalibrated gyro Z axis angular velocity measurement. - * - * @return The angular reported Z axis angular velocity from uncalibrated gyro. - */ -float BNO08x::get_uncalibrated_gyro_velocity_Z() -{ - return q_to_float(raw_uncalib_gyro_Z, GYRO_Q1); -} - -/** - * @brief Get uncalibrated gyro x axis drift estimate. - * - * @return The angular reported x axis drift estimate. - */ -float BNO08x::get_uncalibrated_gyro_bias_X() -{ - return q_to_float(raw_bias_X, GYRO_Q1); -} - -/** - * @brief Get uncalibrated gyro Y axis drift estimate. - * - * @return The angular reported Y axis drift estimate. - */ -float BNO08x::get_uncalibrated_gyro_bias_Y() -{ - return q_to_float(raw_bias_Y, GYRO_Q1); -} - -/** - * @brief Get uncalibrated gyro Z axis drift estimate. - * - * @return The angular reported Z axis drift estimate. - */ -float BNO08x::get_uncalibrated_gyro_bias_Z() -{ - return q_to_float(raw_bias_Z, GYRO_Q1); -} - -/** - * @brief Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5.44) - * - * @param x Reference variable to save X axis angular velocity - * @param y Reference variable to save Y axis angular velocity - * @param z Reference variable to save Z axis angular velocity - * - * @return void, nothing to return - */ -void BNO08x::get_integrated_gyro_velocity(float& x, float& y, float& z) -{ - x = q_to_float(integrated_gyro_velocity_X, ANGULAR_VELOCITY_Q1); - y = q_to_float(integrated_gyro_velocity_Y, ANGULAR_VELOCITY_Q1); - z = q_to_float(integrated_gyro_velocity_Z, ANGULAR_VELOCITY_Q1); -} - -/** - * @brief Get x axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44) - * - * @return The reported x axis angular velocity. - */ -float BNO08x::get_integrated_gyro_velocity_X() -{ - return q_to_float(integrated_gyro_velocity_X, ANGULAR_VELOCITY_Q1); -} - -/** - * @brief Get y axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44) - * - * @return The reported y axis angular velocity. - */ -float BNO08x::get_integrated_gyro_velocity_Y() -{ - return q_to_float(integrated_gyro_velocity_Y, ANGULAR_VELOCITY_Q1); -} - -/** - * @brief Get z axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44) - * - * @return The reported Z axis angular velocity. - */ -float BNO08x::get_integrated_gyro_velocity_Z() -{ - return q_to_float(integrated_gyro_velocity_Z, ANGULAR_VELOCITY_Q1); -} - -/** - * @brief Get if tap has occured. - * - * @return 7 bit tap code indicated which axis taps have occurred. (See Ref. Manual 6.5.27) - */ -uint8_t BNO08x::get_tap_detector() -{ - return tap_detector; -} - -/** - * @brief Get the counted amount of steps. - * - * @return The current amount of counted steps. - */ -uint16_t BNO08x::get_step_count() -{ - return step_count; -} - -/** - * @brief Get the current stability classifier (Seee Ref. Manual 6.5.31) - * - * @return The current stability (0 = unknown, 1 = on table, 2 = stationary) - */ -BNO08xStability BNO08x::get_stability_classifier() -{ - return static_cast(stability_classifier); -} - -/** - * @brief Get the current activity classifier (Seee Ref. Manual 6.5.36) - * - * @return The current activity: - * 0 = unknown - * 1 = in vehicle - * 2 = on bicycle - * 3 = on foot - * 4 = still - * 5 = tilting - * 6 = walking - * 7 = runnning - * 8 = on stairs - */ -BNO08xActivity BNO08x::get_activity_classifier() -{ - return static_cast(activity_classifier); -} - /** * @brief Prints the header of the passed SHTP packet to serial console with ESP_LOG statement. * @@ -3605,265 +809,6 @@ void BNO08x::print_packet(sh2_packet_t* packet) packet_string); } -/** - * @brief Gets Q1 point from BNO08x FRS (flash record system). - * - * Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. - * - * @param record_ID Which record ID/ sensor to get Q1 value for. - * - * @return Q1 value for requested sensor. - */ -int16_t BNO08x::get_Q1(uint16_t record_ID) -{ - // Q1 is lower 16 bits of word 7 - return static_cast((FRS_read_word(record_ID, 7) & 0xFFFFUL)); -} - -/** - * @brief Gets Q2 point from BNO08x FRS (flash record system). - * - * Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. - * - * @param record_ID Which record ID/ sensor to get Q2 value for. - * - * @return Q2 value for requested sensor. - */ -int16_t BNO08x::get_Q2(uint16_t record_ID) -{ - // Q2 is upper 16 bits of word 7 - return static_cast((FRS_read_word(record_ID, 7) >> 16U)); -} - -/** - * @brief Gets Q3 point from BNO08x FRS (flash record system). - * - * Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. - * - * @param record_ID Which record ID/ sensor to get Q3 value for. - * - * @return Q3 value for requested sensor. - */ -int16_t BNO08x::get_Q3(uint16_t record_ID) -{ - // Q3 is upper 16 bits of word 8 - return static_cast((FRS_read_word(record_ID, 8) >> 16U)); -} - -/** - * @brief Gets resolution from BNO08x FRS (flash record system). - * - * @param record_ID Which record ID/ sensor to get resolution value for. - * - * @return The resolution value for the requested sensor. - */ -float BNO08x::get_resolution(uint16_t record_ID) -{ - int16_t Q = get_Q1(record_ID); // use same q as sensor's input report for range calc - - // resolution is word 2 - uint32_t value = FRS_read_word(record_ID, 2); - - return q_to_float(value, Q); // return resolution -} - -/** - * @brief Gets range from BNO08x FRS (flash record system). - * - * @param record_ID Which record ID/ sensor to get range value for. - * - * @return The range value for the requested sensor. - */ -float BNO08x::get_range(uint16_t record_ID) -{ - int16_t Q = get_Q1(record_ID); // use same q as sensor's input report for range calc - - // resolution is word 1 - uint32_t value = FRS_read_word(record_ID, 1); - - return q_to_float(value, Q); // return range -} - -/** - * @brief Reads meta data word from BNO08x FRS (flash record system) given the record ID and word number. (See Ref. - * Manual 5.1 & 6.3.7) - * - * Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. - * - * @param record_ID Which record ID/ sensor to request meta data from. - * @param word_number Desired word to read. - * - * @return Requested meta data word, 0 if failed. - */ -uint32_t BNO08x::FRS_read_word(uint16_t record_ID, uint8_t word_number) -{ - uint32_t frs_read = 0; - - if (FRS_read_data(record_ID, word_number, 1)) // start at desired word and only read one 1 word - frs_read = meta_data[0]; - - return frs_read; -} - -/** - * @brief Requests meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other - * info. (See Ref. Manual 5.1 & 6.3.6) - * - * Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. - * - * @param record_ID Which record ID/ sensor to request meta data from. - * @param start_location Start byte location. - * @param words_to_read Length of words to read. - * - * @return True if read request acknowledged (HINT was asserted) - */ -bool BNO08x::FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size) -{ - uint8_t commands[20] = {0}; - - commands[0] = SHTP_REPORT_FRS_READ_REQUEST; // FRS Read Request - commands[1] = 0; // Reserved - commands[2] = (read_offset >> 0) & 0xFF; // Read Offset LSB - commands[3] = (read_offset >> 8) & 0xFF; // Read Offset MSB - commands[4] = (record_ID >> 0) & 0xFF; // FRS Type LSB - commands[5] = (record_ID >> 8) & 0xFF; // FRS Type MSB - commands[6] = (block_size >> 0) & 0xFF; // Block size LSB - commands[7] = (block_size >> 8) & 0xFF; // Block size MSB - - // Transmit packet on channel 2, 8 bytes - queue_packet(CHANNEL_CONTROL, 8, commands); - return wait_for_tx_done(); -} - -/** - * @brief Read meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other info. - * (See Ref. Manual 5.1 & 6.3.7) - * - * Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. - * - * @param record_ID Which record ID/ sensor to request meta data from. - * @param start_location Start byte location. - * @param words_to_read Length of words to read. - * - * @return True if meta data read successfully. - */ -bool BNO08x::FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read) -{ - uint8_t counter; - uint8_t packet_body[RX_DATA_LENGTH]; - uint8_t data_length; - uint8_t frs_status; - uint32_t data_1; - uint32_t data_2; - uint8_t spot = 0; - - if (FRS_read_request(record_ID, start_location, words_to_read)) - { - while (1) - { - while (1) - { - counter = 0; - - while (!wait_for_rx_done()) - { - counter++; - - if (counter > 100) - return false; - } - - if (xQueueReceive(queue_frs_read_data, &packet_body, host_int_timeout_ms)) - { - if (PARSE_FRS_READ_RESPONSE_REPORT_RECORD_ID(packet_body) == record_ID) - break; - } - } - - data_length = packet_body[1] >> 4; - frs_status = packet_body[1] & 0x0F; - - data_1 = PARSE_FRS_READ_RESPONSE_REPORT_DATA_1(packet_body); - data_2 = PARSE_FRS_READ_RESPONSE_REPORT_DATA_2(packet_body); - - if (data_length > 0) - meta_data[spot++] = data_1; - - if (data_length > 1) - meta_data[spot++] = data_2; - - if (spot >= MAX_METADATA_LENGTH) - return true; - - if (frs_status == 3 || frs_status == 6 || frs_status == 7) - return true; - } - } - - return false; -} - -/** - * @brief Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. - * Manual 6.5.4) - * - * @param report_ID ID of sensor report to be enabled. - * @param time_between_reports Desired time between reports in microseconds. - * @param specific_config Specific config word (used with personal activity classifier) - * - * @return void, nothing to return - */ -void BNO08x::queue_feature_command(uint8_t report_ID, uint32_t time_between_reports, uint32_t specific_config) -{ - uint8_t commands[20] = {0}; - - commands[0] = SHTP_REPORT_SET_FEATURE_COMMAND; // Set feature command (See Ref. Manual 6.5.4) - commands[1] = report_ID; // Feature Report ID. 0x01 = Accelerometer, 0x05 = Rotation vector - commands[2] = 0; // Feature flags - commands[3] = 0; // Change sensitivity (LSB) - commands[4] = 0; // Change sensitivity (MSB) - commands[5] = (time_between_reports >> 0) & 0xFF; // Report interval (LSB) in microseconds. 0x7A120 = 500ms - commands[6] = (time_between_reports >> 8) & 0xFF; // Report interval - commands[7] = (time_between_reports >> 16) & 0xFF; // Report interval - commands[8] = (time_between_reports >> 24) & 0xFF; // Report interval (MSB) - commands[9] = 0; // Batch Interval (LSB) - commands[10] = 0; // Batch Interval - commands[11] = 0; // Batch Interval - commands[12] = 0; // Batch Interval (MSB) - commands[13] = (specific_config >> 0) & 0xFF; // Sensor-specific config (LSB) - commands[14] = (specific_config >> 8) & 0xFF; // Sensor-specific config - commands[15] = (specific_config >> 16) & 0xFF; // Sensor-specific config - commands[16] = (specific_config >> 24) & 0xFF; // Sensor-specific config (MSB) - - // Transmit packet on channel 2, 17 bytes - queue_packet(CHANNEL_CONTROL, 17, commands); -} - -/** - * @brief Queues a packet containing a command related to zeroing sensor's axes. (See Ref. Manual 6.4.4.1) - * - * @param command Tare command to be sent. - * @param axis Specified axis (can be z or all at once) - * @param rotation_vector_basis Which rotation vector type to zero axes of, BNO08x saves seperate data for Rotation - * Vector, Gaming Rotation Vector, etc..) - * - * @return void, nothing to return - */ -void BNO08x::queue_tare_command(uint8_t command, uint8_t axis, uint8_t rotation_vector_basis) -{ - uint8_t commands[20] = {0}; - - commands[3] = command; - - if (command == TARE_NOW) - { - commands[4] = axis; - commands[5] = rotation_vector_basis; - } - - queue_command(COMMAND_TARE, commands); -} - /** * @brief Static function used to launch spi task. * @@ -3894,11 +839,6 @@ void BNO08x::spi_task() while (1) { - /*only re-enable interrupts if there are reports enabled, if no reports are enabled - interrupts will be re-enabled upon the next user call to wait_for_tx_done(), wait_for_rx_done(), or wait_for_data()*/ - if (xEventGroupGetBits(evt_grp_report_en) != 0) - gpio_intr_enable(imu_config.io_int); - ulTaskNotifyTake(pdTRUE, portMAX_DELAY); // block until notified by ISR (hint_handler) if (CHECK_TASKS_RUNNING(evt_grp_task_flow, EVT_GRP_TSK_FLW_RUNNING_BIT)) // ensure deconstructor has not requested that task be deleted @@ -3947,7 +887,6 @@ void BNO08x::data_proc_task_trampoline(void* arg) void BNO08x::data_proc_task() { sh2_packet_t packet; - bool notify_users = false; while (1) // receive packet from spi_task() { @@ -3955,28 +894,7 @@ void BNO08x::data_proc_task() { if (CHECK_TASKS_RUNNING(evt_grp_task_flow, EVT_GRP_TSK_FLW_RUNNING_BIT)) // ensure deconstructor has not requested that task be deleted { - if ((parse_packet(&packet, notify_users) != 0)) // check if packet is valid - { - // get feature reports are valid packets but we don't need to notify the user unless they explicitly have requested them - if (notify_users) - { - // execute any registered callbacks - for (auto& cb_fxn : cb_list) - cb_fxn(); - - xEventGroupSetBits(evt_grp_spi, EVT_GRP_SPI_RX_VALID_PACKET_BIT); // indicate valid packet to wait_for_data() - } - } - else - { - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_DEBUG_STATEMENTS - print_packet(&packet); - #endif - // clang-format on - - xEventGroupSetBits(evt_grp_spi, EVT_GRP_SPI_RX_INVALID_PACKET_BIT); // indicated invalid packet to wait_for_data() - } + // PROCESS RX HERE } else { @@ -4087,114 +1005,6 @@ esp_err_t BNO08x::kill_all_tasks() return ESP_OK; } -/** - * @brief Updates period of respective report in report_period_trackers and recalculates host_int_timeout_ms according to next longest report period. - * - * - * @param report_ID report ID to update period of. - * @return void, nothing to return - */ -void BNO08x::update_report_period_trackers(uint8_t report_ID, uint32_t new_period) -{ - uint8_t idx = report_ID_to_report_period_tracker_idx(report_ID); - - if (idx != REPORT_CNT) - { - report_period_trackers[idx].period = new_period; - - if (new_period > largest_sample_period_us) - { - current_slowest_report_ID = report_ID; - largest_sample_period_us = new_period; - host_int_timeout_ms = (2 * (largest_sample_period_us / 1000UL)) / portTICK_PERIOD_MS; - - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_DEBUG_STATEMENTS - ESP_LOGW(TAG, "new hint timeout: %d", static_cast(host_int_timeout_ms)); - #endif - // clang-format on - } - else - { - if (current_slowest_report_ID == report_ID) - { - largest_sample_period_us = 0; - - // no longer true, find the slowest - for (int i = 0; i < REPORT_CNT; i++) - { - if (report_period_trackers[i].period > largest_sample_period_us) - { - current_slowest_report_ID = report_period_trackers[i].report_ID; - largest_sample_period_us = report_period_trackers[i].period; - host_int_timeout_ms = (2 * (largest_sample_period_us / 1000UL)) / portTICK_PERIOD_MS; - - // clang-format off - #ifdef CONFIG_ESP32_BNO08x_DEBUG_STATEMENTS - ESP_LOGW(TAG, "new hint timeout (due to period tracker search): %d", static_cast(host_int_timeout_ms)); - #endif - // clang-format on - } - } - } - } - } -} - -/** - * @brief Converts report id to respective index in report_period_trackers. - * - * - * @param report_ID report ID to return index for. - * @return Index in report_period_trackers corresponding to passed report ID. - */ -uint8_t BNO08x::report_ID_to_report_period_tracker_idx(uint8_t report_ID) -{ - switch (report_ID) - { - case SENSOR_REPORT_ID_ACCELEROMETER: - return 0; - case SENSOR_REPORT_ID_GYROSCOPE: - return 1; - case SENSOR_REPORT_ID_MAGNETIC_FIELD: - return 2; - case SENSOR_REPORT_ID_LINEAR_ACCELERATION: - return 3; - case SENSOR_REPORT_ID_ROTATION_VECTOR: - return 4; - case SENSOR_REPORT_ID_GRAVITY: - return 5; - case SENSOR_REPORT_ID_UNCALIBRATED_GYRO: - return 6; - case SENSOR_REPORT_ID_GAME_ROTATION_VECTOR: - return 7; - case SENSOR_REPORT_ID_GEOMAGNETIC_ROTATION_VECTOR: - return 8; - case SENSOR_REPORT_ID_GYRO_INTEGRATED_ROTATION_VECTOR: - return 9; - case SENSOR_REPORT_ID_TAP_DETECTOR: - return 10; - case SENSOR_REPORT_ID_STEP_COUNTER: - return 11; - case SENSOR_REPORT_ID_STABILITY_CLASSIFIER: - return 12; - case SENSOR_REPORT_ID_RAW_ACCELEROMETER: - return 13; - case SENSOR_REPORT_ID_RAW_GYROSCOPE: - return 14; - case SENSOR_REPORT_ID_RAW_MAGNETOMETER: - return 15; - case SENSOR_REPORT_ID_PERSONAL_ACTIVITY_CLASSIFIER: - return 16; - case SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR: - return 17; - case SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR: - return 18; - default: - return 19; - } -} - /** * @brief HINT interrupt service routine, handles falling edge of BNO08x HINT pin. * diff --git a/test/CallbackTests.cpp b/test/CallbackTests.cpp deleted file mode 100644 index f80538f..0000000 --- a/test/CallbackTests.cpp +++ /dev/null @@ -1,167 +0,0 @@ -#include "unity.h" -#include "../include/BNO08xTestHelper.hpp" - -TEST_CASE("BNO08x Driver Creation for [CallbackTests] Tests", "[CallbackTests]") -{ - const constexpr char* TEST_TAG = "BNO08x Driver Creation for [CallbackTests] Tests"; - BNO08x* imu = nullptr; - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Creating & initializing BNO08x driver."); - BNO08xTestHelper::create_test_imu(); - imu = BNO08xTestHelper::get_test_imu(); - - // ensure IMU initialized successfully - TEST_ASSERT_EQUAL(true, imu->initialize()); -} - -TEST_CASE("Callback Receives New Data (Single Report)", "[CallbackTests]") -{ - const constexpr char* TEST_TAG = "Callback Receives New Data (Single Report)"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - const constexpr uint8_t RX_REPORT_TRIAL_CNT = 5; - const constexpr uint32_t REPORT_PERIOD = 100000UL; // 100ms - bool new_data = false; - char msg_buff[200] = {}; - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - // register a callback and check for new data within it - imu->register_cb( - [&imu, &new_data, &report_data, &prev_report_data, &msg_buff]() - { - static int cb_execution_cnt = 0; - - /* callback code */ - - cb_execution_cnt++; - // check if new data was received from enabled report(s) - BNO08xTestHelper::update_report_data(&report_data); - - if (BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - cb_execution_cnt, report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - }); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Enabling report(s) and checking for new data through subscribed callback."); - imu->enable_accelerometer(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - if (imu->data_available()) - { - // callbacks should ALWAYS execute before data_available returns true, therefore something has gone wrong if new_data is not set to true - TEST_ASSERT_EQUAL(true, new_data); - - // reset all data used in report test - new_data = false; - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Test complete, disabling report(s)."); - imu->disable_accelerometer(); -} - -TEST_CASE("Callback Receives New Data (Dual Report)", "[CallbackTests]") -{ - const constexpr char* TEST_TAG = "Callback Receives New Data (Dual Report)"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - const constexpr uint8_t ENABLED_REPORT_CNT = 2; - const constexpr uint8_t RX_REPORT_TRIAL_CNT = 2 * ENABLED_REPORT_CNT; - const constexpr uint32_t REPORT_PERIOD = 100000UL; // 100ms - bool new_data[2] = {false, false}; - char msg_buff[200] = {}; - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - // register a callback and check for new data within it - imu->register_cb( - [&imu, &new_data, &report_data, &prev_report_data, &msg_buff]() - { - static int cb_execution_cnt = 0; - - /* callback code */ - - cb_execution_cnt++; - // check if new data was received from enabled report(s) - BNO08xTestHelper::update_report_data(&report_data); - - if (BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[0] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - cb_execution_cnt, report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[1] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (cb_execution_cnt + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - }); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Enabling report(s) and checking for new data through subscribed callback."); - imu->enable_accelerometer(REPORT_PERIOD); - imu->enable_linear_accelerometer(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - if (imu->data_available()) - { - // callbacks should ALWAYS execute before data_available returns true - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - } - - // check that the callback received new data for all reports after all trials have completed - TEST_ASSERT_EQUAL(true, new_data[0]); - TEST_ASSERT_EQUAL(true, new_data[1]); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Test complete, disabling report(s)."); - imu->disable_accelerometer(); - imu->disable_linear_accelerometer(); -} - -TEST_CASE("BNO08x Driver Cleanup for [CallbackTests] Tests", "[CallbackTests]") -{ - const constexpr char* TEST_TAG = "BNO08x Driver Cleanup for [CallbackTests] Tests"; - BNO08xTestHelper::print_test_msg(TEST_TAG, "Destroying BNO08x Driver."); - - BNO08xTestHelper::destroy_test_imu(); -} diff --git a/test/InitDeinitTests.cpp b/test/InitDeinitTests.cpp deleted file mode 100644 index 2c73a5f..0000000 --- a/test/InitDeinitTests.cpp +++ /dev/null @@ -1,119 +0,0 @@ -#include "unity.h" -#include "../include/BNO08xTestHelper.hpp" - -TEST_CASE("Init Config Args", "[InitComprehensive]") -{ - const constexpr char* TEST_TAG = "Init Config Args"; - BNO08x* imu = nullptr; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Creating test IMU."); - BNO08xTestHelper::create_test_imu(); - imu = BNO08xTestHelper::get_test_imu(); - - TEST_ASSERT_EQUAL(ESP_OK, BNO08xTestHelper::call_init_config_args()); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Init GPIO", "[InitComprehensive]") -{ - const constexpr char* TEST_TAG = "Init GPIO"; - BNO08x* imu = nullptr; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - TEST_ASSERT_EQUAL(ESP_OK, BNO08xTestHelper::call_init_gpio()); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Init HINT ISR", "[InitComprehensive]") -{ - const constexpr char* TEST_TAG = "Init HINT_ISR"; - BNO08x* imu = nullptr; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - TEST_ASSERT_EQUAL(ESP_OK, BNO08xTestHelper::call_init_hint_isr()); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Init SPI", "[InitComprehensive]") -{ - const constexpr char* TEST_TAG = "Init SPI"; - BNO08x* imu = nullptr; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - TEST_ASSERT_EQUAL(ESP_OK, BNO08xTestHelper::call_init_spi()); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("InitComprehensive Tasks", "[InitComprehensive]") -{ - const constexpr char* TEST_TAG = "Init Tasks"; - BNO08x* imu = nullptr; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - TEST_ASSERT_EQUAL(ESP_OK, BNO08xTestHelper::call_launch_tasks()); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Finish Init", "[InitComprehensive]") -{ - const constexpr char* TEST_TAG = "Finish Init"; - BNO08x* imu = nullptr; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset imu - TEST_ASSERT_EQUAL(true, imu->hard_reset()); - - // check if reason is valid - TEST_ASSERT_NOT_EQUAL(BNO08xResetReason::UNDEFINED, imu->get_reset_reason()); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Destroying test IMU."); - BNO08xTestHelper::destroy_test_imu(); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Init & Deinit", "[InitDenit]") -{ - const constexpr char* TEST_TAG = "Init & Deinit"; - BNO08x* imu = nullptr; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Initializing BNO08x Driver Object attempt 1."); - BNO08xTestHelper::create_test_imu(); - imu = BNO08xTestHelper::get_test_imu(); - TEST_ASSERT_EQUAL(true, imu->initialize()); - BNO08xTestHelper::print_test_msg(TEST_TAG, "Success, deinitializing BNO08x Driver Object."); - BNO08xTestHelper::destroy_test_imu(); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Initializing BNO08x Driver Object attempt 2."); - BNO08xTestHelper::create_test_imu(); - imu = BNO08xTestHelper::get_test_imu(); - TEST_ASSERT_EQUAL(true, imu->initialize()); - BNO08xTestHelper::print_test_msg(TEST_TAG, "Success, deinitializing BNO08x Driver Object."); - BNO08xTestHelper::destroy_test_imu(); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} \ No newline at end of file diff --git a/test/MultiReportTests.cpp b/test/MultiReportTests.cpp deleted file mode 100644 index 37d298b..0000000 --- a/test/MultiReportTests.cpp +++ /dev/null @@ -1,843 +0,0 @@ -#include "unity.h" -#include "../include/BNO08xTestHelper.hpp" - -TEST_CASE("BNO08x Driver Creation for [MultiReportEnableDisable] Tests", "[MultiReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "BNO08x Driver Creation for [MultiReportEnableDisable] Tests"; - BNO08x* imu = nullptr; - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Creating & initializing BNO08x driver."); - BNO08xTestHelper::create_test_imu(); - imu = BNO08xTestHelper::get_test_imu(); - - // ensure IMU initialized successfully - TEST_ASSERT_EQUAL(true, imu->initialize()); -} - -TEST_CASE("Dual Report Enable/Disable", "[MultiReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Dual Report Enable/Disable"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - char msg_buff[200] = {}; - const constexpr uint8_t ENABLED_REPORT_CNT = 2; - const constexpr uint8_t RX_REPORT_TRIAL_CNT = 2 * ENABLED_REPORT_CNT; - const constexpr uint32_t REPORT_PERIOD = 100000UL; // 100ms - - bool new_data[ENABLED_REPORT_CNT] = {false, false}; - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Enabling Accelerometer and Linear Accelerometer reports, checking for new data on both."); - - imu->enable_accelerometer(REPORT_PERIOD); - imu->enable_linear_accelerometer(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - if (BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[0] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[1] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - } - } - - // check that new data was received for each report - TEST_ASSERT_EQUAL(true, new_data[0]); - TEST_ASSERT_EQUAL(true, new_data[1]); - - // reset all data used in report test - new_data[0] = false; - new_data[1] = false; - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Disabling only Linear Accelerometer report and checking for new data on both."); - imu->disable_linear_accelerometer(); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - if (BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[0] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) - { - // no new data should be detected here, report is disabled. - new_data[1] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Failure (REPORT DISABLED): LinearAccel: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - } - } - - // check that new data was received only for accelerometer report - TEST_ASSERT_EQUAL(true, new_data[0]); - TEST_ASSERT_NOT_EQUAL(true, new_data[1]); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Test completed, disabling Accelerometer report"); - imu->disable_accelerometer(); -} - -TEST_CASE("Tri Report Enable/Disable", "[MultiReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Tri Report Enable/Disable"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - char msg_buff[200] = {}; - const constexpr uint8_t ENABLED_REPORT_CNT = 3; - const constexpr uint8_t RX_REPORT_TRIAL_CNT = 2 * ENABLED_REPORT_CNT; - const constexpr uint32_t REPORT_PERIOD = 100000UL; // 100ms - - bool new_data[ENABLED_REPORT_CNT] = {false, false, false}; - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg( - TEST_TAG, "Enabling Accelerometer, Linear Accelerometer, and Magnetometer reports, checking for new data on all."); - - imu->enable_accelerometer(REPORT_PERIOD); - imu->enable_linear_accelerometer(REPORT_PERIOD); - imu->enable_magnetometer(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - if (BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[0] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[1] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::magnetometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[2] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: Magf: mX: %.2lf mY: %.2lf mZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.magf_x, report_data.magf_y, report_data.magf_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.magf_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - } - } - - // check that new data was received for each report - TEST_ASSERT_EQUAL(true, new_data[0]); - TEST_ASSERT_EQUAL(true, new_data[1]); - TEST_ASSERT_EQUAL(true, new_data[2]); - - // reset all data used in report test - new_data[0] = false; - new_data[1] = false; - new_data[2] = false; - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Disabling Magnetometer report and checking for new data on remaining reports."); - imu->disable_magnetometer(); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - if (BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[0] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[1] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::magnetometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[2] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Failure (REPORT DISABLED): Magf: mX: %.2lf mY: %.2lf mZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.magf_x, report_data.magf_y, report_data.magf_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.magf_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - } - } - - // check that new data was received for only enabled reports - TEST_ASSERT_EQUAL(true, new_data[0]); - TEST_ASSERT_EQUAL(true, new_data[1]); - TEST_ASSERT_NOT_EQUAL(true, new_data[2]); - - // reset all data used in report test - new_data[0] = false; - new_data[1] = false; - new_data[2] = false; - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Disabling Linear Accelerometer report and checking for new data on remaining reports."); - imu->disable_linear_accelerometer(); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - if (BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[0] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) - { - // no new data should be detected here, report is disabled. - new_data[1] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Failure (REPORT DISABLED): LinearAccel: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::magnetometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[2] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Failure (REPORT DISABLED): Magf: mX: %.2lf mY: %.2lf mZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.magf_x, report_data.magf_y, report_data.magf_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.magf_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - } - } - - // check that new data was received for only enabled reports - TEST_ASSERT_EQUAL(true, new_data[0]); - TEST_ASSERT_NOT_EQUAL(true, new_data[1]); - TEST_ASSERT_NOT_EQUAL(true, new_data[2]); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Test completed, disabling Accelerometer report"); - imu->disable_accelerometer(); -} - -TEST_CASE("Quad Report Enable/Disable", "[MultiReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Quad Report Enable/Disable"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - char msg_buff[200] = {}; - const constexpr uint8_t ENABLED_REPORT_CNT = 4; - const constexpr uint8_t RX_REPORT_TRIAL_CNT = 2 * ENABLED_REPORT_CNT; - const constexpr uint32_t REPORT_PERIOD = 100000UL; // 100ms - - bool new_data[ENABLED_REPORT_CNT] = {false, false, false, false}; - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg( - TEST_TAG, "Enabling Accelerometer, Linear Accelerometer, Magnetometer, and Rotation Vector reports, checking for new data on all."); - - imu->enable_accelerometer(REPORT_PERIOD); - imu->enable_linear_accelerometer(REPORT_PERIOD); - imu->enable_magnetometer(REPORT_PERIOD); - imu->enable_rotation_vector(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - if (BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[0] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[1] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::magnetometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[2] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: Magf: mX: %.2lf mY: %.2lf mZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.magf_x, report_data.magf_y, report_data.magf_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.magf_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data)) - { - new_data[3] = true; - - sprintf(msg_buff, "Rx Data Trial %d Success: Quat: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), report_data.quat_I, - report_data.quat_J, report_data.quat_K, report_data.quat_real, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - } - } - - // check that new data was received for each report - TEST_ASSERT_EQUAL(true, new_data[0]); - TEST_ASSERT_EQUAL(true, new_data[1]); - TEST_ASSERT_EQUAL(true, new_data[2]); - TEST_ASSERT_EQUAL(true, new_data[3]); - - // reset all data used in report test - new_data[0] = false; - new_data[1] = false; - new_data[2] = false; - new_data[3] = false; - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Disabling Rotation Vector report and checking for new data on remaining reports."); - imu->disable_rotation_vector(); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - if (BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[0] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[1] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::magnetometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[2] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: Magf: mX: %.2lf mY: %.2lf mZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.magf_x, report_data.magf_y, report_data.magf_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.magf_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data)) - { - new_data[3] = true; - - sprintf(msg_buff, "Rx Data Trial %d Failure (REPORT DISABLED): Quat: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), - report_data.quat_I, report_data.quat_J, report_data.quat_K, report_data.quat_real, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - } - } - - // check that new data was received for only enabled reports - TEST_ASSERT_EQUAL(true, new_data[0]); - TEST_ASSERT_EQUAL(true, new_data[1]); - TEST_ASSERT_EQUAL(true, new_data[2]); - TEST_ASSERT_NOT_EQUAL(true, new_data[3]); - - // reset all data used in report test - new_data[0] = false; - new_data[1] = false; - new_data[2] = false; - new_data[3] = false; - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Disabling Magnetometer report and checking for new data on remaining reports."); - imu->disable_magnetometer(); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - if (BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[0] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[1] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::magnetometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[2] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Failure (REPORT DISABLED): Magf: mX: %.2lf mY: %.2lf mZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.magf_x, report_data.magf_y, report_data.magf_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.magf_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data)) - { - new_data[3] = true; - - sprintf(msg_buff, "Rx Data Trial %d Failure (REPORT DISABLED): Quat: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), - report_data.quat_I, report_data.quat_J, report_data.quat_K, report_data.quat_real, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - } - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Disabling Linear Accelerometer report and checking for new data on remaining reports."); - imu->disable_linear_accelerometer(); - - // check that new data was received for only enabled reports - TEST_ASSERT_EQUAL(true, new_data[0]); - TEST_ASSERT_EQUAL(true, new_data[1]); - TEST_ASSERT_NOT_EQUAL(true, new_data[2]); - TEST_ASSERT_NOT_EQUAL(true, new_data[3]); - - // reset all data used in report test - new_data[0] = false; - new_data[1] = false; - new_data[2] = false; - new_data[3] = false; - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - if (BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[0] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[1] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Failure (REPORT DISABLED): LinearAccel: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::magnetometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[2] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Failure (REPORT DISABLED): Magf: mX: %.2lf mY: %.2lf mZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.magf_x, report_data.magf_y, report_data.magf_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.magf_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data)) - { - new_data[3] = true; - - sprintf(msg_buff, "Rx Data Trial %d Failure (REPORT DISABLED): Quat: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), - report_data.quat_I, report_data.quat_J, report_data.quat_K, report_data.quat_real, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - } - } - - // check that new data was received for only enabled reports - TEST_ASSERT_EQUAL(true, new_data[0]); - TEST_ASSERT_NOT_EQUAL(true, new_data[1]); - TEST_ASSERT_NOT_EQUAL(true, new_data[2]); - TEST_ASSERT_NOT_EQUAL(true, new_data[3]); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Test completed, disabling Accelerometer report"); - imu->disable_accelerometer(); -} - -TEST_CASE("Hex Report Enable", "[MultiReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Hex Report Enable"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - char msg_buff[200] = {}; - const constexpr uint8_t ENABLED_REPORT_CNT = 8; - const constexpr uint8_t RX_REPORT_TRIAL_CNT = 2 * ENABLED_REPORT_CNT; - const constexpr uint32_t REPORT_PERIOD = 100000UL; // 100ms - - bool new_data[ENABLED_REPORT_CNT] = {false, false, false, false, false, false, false, false}; - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Enabling Accelerometer, Linear Accelerometer, Magnetometer, Rotation Vector, Uncalibrated Gyro, " - "Calibrated Gyro, Gravity, and Step Counter " - "reports, checking for new data on all."); - - imu->enable_accelerometer(REPORT_PERIOD); - imu->enable_linear_accelerometer(REPORT_PERIOD); - imu->enable_magnetometer(REPORT_PERIOD); - imu->enable_rotation_vector(REPORT_PERIOD); - imu->enable_uncalibrated_gyro(REPORT_PERIOD); - imu->enable_calibrated_gyro(REPORT_PERIOD); - imu->enable_gravity(REPORT_PERIOD); - imu->enable_step_counter(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - if (BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[0] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[1] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::magnetometer_data_is_new(&report_data, &prev_report_data)) - { - new_data[2] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: Magf: mX: %.2lf mY: %.2lf mZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.magf_x, report_data.magf_y, report_data.magf_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.magf_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data)) - { - new_data[3] = true; - - sprintf(msg_buff, "Rx Data Trial %d Success: Quat: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), report_data.quat_I, - report_data.quat_J, report_data.quat_K, report_data.quat_real, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::uncalibrated_gyro_data_is_new(&report_data, &prev_report_data)) - { - new_data[4] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: UncalibratedGyro: vX: %.2lf vY: %.2lf vZ: %.2lf driftX: %.2lf driftY: %.2lf driftZ: " - "%.2lf", - (i + 1), report_data.uncalib_gyro_vel_x, report_data.uncalib_gyro_vel_y, report_data.uncalib_gyro_vel_z, - report_data.uncalib_gyro_drift_x, report_data.uncalib_gyro_drift_y, report_data.uncalib_gyro_drift_z); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::calibrated_gyro_data_is_new(&report_data, &prev_report_data)) - { - new_data[5] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: CalibratedGyro: vX: %.2lf vY: %.2lf vZ: " - "%.2lf", - (i + 1), report_data.calib_gyro_vel_x, report_data.calib_gyro_vel_y, report_data.calib_gyro_vel_z); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::gravity_data_is_new(&report_data, &prev_report_data)) - { - new_data[6] = true; - - sprintf(msg_buff, - "Rx Data Trial %d Success: Gravity: gX: %.2lf gY: %.2lf gZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.grav_x, report_data.grav_y, report_data.grav_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.grav_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - - if (BNO08xTestHelper::step_counter_data_is_new(&report_data, &prev_report_data)) - { - new_data[7] = true; - - sprintf(msg_buff, "Rx Data Trial %d Success: StepCounter: %d steps", (i + 1), report_data.step_count); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - } - } - } - - // check that new data was received for each report - TEST_ASSERT_EQUAL(true, new_data[0]); - TEST_ASSERT_EQUAL(true, new_data[1]); - TEST_ASSERT_EQUAL(true, new_data[2]); - TEST_ASSERT_EQUAL(true, new_data[3]); - TEST_ASSERT_EQUAL(true, new_data[4]); - TEST_ASSERT_EQUAL(true, new_data[5]); - TEST_ASSERT_EQUAL(true, new_data[6]); - TEST_ASSERT_EQUAL(true, new_data[7]); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Test completed, disabling all reports."); - - imu->disable_accelerometer(); - imu->disable_linear_accelerometer(); - imu->disable_magnetometer(); - imu->disable_rotation_vector(); - imu->disable_uncalibrated_gyro(); - imu->disable_calibrated_gyro(); - imu->disable_gravity(); - imu->disable_step_counter(); -} - -TEST_CASE("BNO08x Driver Cleanup for [MultiReportEnableDisable] Tests", "[MultiReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "BNO08x Driver Cleanup for [MultiReportEnableDisable] Tests"; - BNO08xTestHelper::print_test_msg(TEST_TAG, "Destroying BNO08x Driver."); - - BNO08xTestHelper::destroy_test_imu(); -} diff --git a/test/SingleReportTests.cpp b/test/SingleReportTests.cpp deleted file mode 100644 index cac6dd6..0000000 --- a/test/SingleReportTests.cpp +++ /dev/null @@ -1,1289 +0,0 @@ -#include "unity.h" -#include "../include/BNO08xTestHelper.hpp" - -static const constexpr uint8_t RX_REPORT_TRIAL_CNT = 5; -static const constexpr uint32_t REPORT_PERIOD = 100000UL; // 100ms - -TEST_CASE("BNO08x Driver Creation for [SingleReportEnableDisable] Tests", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "BNO08x Driver Creation for [SingleReportEnableDisable] Tests"; - BNO08x* imu = nullptr; - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Creating & initializing BNO08x driver."); - BNO08xTestHelper::create_test_imu(); - imu = BNO08xTestHelper::get_test_imu(); - - // ensure IMU initialized successfully - TEST_ASSERT_EQUAL(true, imu->initialize()); -} - -TEST_CASE("Enable Incorrect Report", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable Incorrect Report"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable linear accelerometer report but check for angular accelerometer data (should remain as default test values) */ - imu->enable_linear_accelerometer(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from accelerometer has not been rx'd, only linear accelerometer data should have been rx'd - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, - "No Rx Data Trial %d Success: AngularAccelDefaults: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - imu->disable_linear_accelerometer(); - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable Rotation Vector", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable Rotation Vector"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_rotation_vector(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, "Rx Data Trial %d Success: Quat: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), report_data.quat_I, - report_data.quat_J, report_data.quat_K, report_data.quat_real, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_rotation_vector(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, "No Rx Data Trial %d Success: QuatDefaults: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), - report_data.quat_I, report_data.quat_J, report_data.quat_K, report_data.quat_real, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable Game Rotation Vector", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable Game Rotation Vector"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_game_rotation_vector(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, "Rx Data Trial %d Success: Quat: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), report_data.quat_I, - report_data.quat_J, report_data.quat_K, report_data.quat_real, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_game_rotation_vector(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, "No Rx Data Trial %d Success: QuatDefaults: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), - report_data.quat_I, report_data.quat_J, report_data.quat_K, report_data.quat_real, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable ARVR Stabilized Rotation Vector", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable ARVR Stabilized Rotation Vector"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_ARVR_stabilized_rotation_vector(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, "Rx Data Trial %d Success: Quat: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), report_data.quat_I, - report_data.quat_J, report_data.quat_K, report_data.quat_real, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_ARVR_stabilized_rotation_vector(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, "No Rx Data Trial %d Success: QuatDefaults: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), - report_data.quat_I, report_data.quat_J, report_data.quat_K, report_data.quat_real, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable ARVR Stabilized Game Rotation Vector", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable ARVR Stabilized Game Rotation Vector"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_ARVR_stabilized_game_rotation_vector(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, "Rx Data Trial %d Success: Quat: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), report_data.quat_I, - report_data.quat_J, report_data.quat_K, report_data.quat_real, BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_ARVR_stabilized_game_rotation_vector(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::rotation_vector_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, "No Rx Data Trial %d Success: QuatDefaults: I: %.2lf J: %.2lf K: %.2lf real: %.2lf Accuracy: %s", (i + 1), - report_data.quat_I, report_data.quat_J, report_data.quat_K, report_data.quat_real, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.quat_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable Gyro Integrated Rotation Vector", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable Gyro Integrated Rotation Vector"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_gyro_integrated_rotation_vector(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::gyro_integrated_rotation_vector_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, - "Rx Data Trial %d Success: GyroIntegratedRotVector: I: %.2lf J: %.2lf K: %.2lf real: %.2lf gyro vel X: %.2lf gyro vel Y: %.2lf gyro " - "vel " - "Z: " - "%.2lf ", - (i + 1), report_data.quat_I, report_data.quat_J, report_data.quat_K, report_data.quat_real, report_data.integrated_gyro_vel_x, - report_data.integrated_gyro_vel_y, report_data.integrated_gyro_vel_z); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_gyro_integrated_rotation_vector(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::gyro_integrated_rotation_vector_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, - "No Rx Data Trial %d Success: GyroIntegratedRotVectorDefaults: I: %.2lf J: %.2lf K: %.2lf real: %.2lf gyro vel X: %.2lf gyro vel Y: " - "%.2lf gyro vel " - "Z: " - "%.2lf ", - (i + 1), report_data.quat_I, report_data.quat_J, report_data.quat_K, report_data.quat_real, report_data.integrated_gyro_vel_x, - report_data.integrated_gyro_vel_y, report_data.integrated_gyro_vel_z); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable Uncalibrated Gyro", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable Uncalibrated Gyro"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_uncalibrated_gyro(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::uncalibrated_gyro_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, - "Rx Data Trial %d Success: UncalibratedGyro: vX: %.2lf vY: %.2lf vZ: %.2lf driftX: %.2lf driftY: %.2lf driftZ: " - "%.2lf", - (i + 1), report_data.uncalib_gyro_vel_x, report_data.uncalib_gyro_vel_y, report_data.uncalib_gyro_vel_z, - report_data.uncalib_gyro_drift_x, report_data.uncalib_gyro_drift_y, report_data.uncalib_gyro_drift_z); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_uncalibrated_gyro(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::uncalibrated_gyro_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, - "No Rx Data Trial %d Success: UncalibratedGyroDefaults: vX: %.2lf vY: %.2lf vZ: %.2lf driftX: %.2lf driftY: %.2lf driftZ: " - "%.2lf", - (i + 1), report_data.uncalib_gyro_vel_x, report_data.uncalib_gyro_vel_y, report_data.uncalib_gyro_vel_z, - report_data.uncalib_gyro_drift_x, report_data.uncalib_gyro_drift_y, report_data.uncalib_gyro_drift_z); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable Calibrated Gyro", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable Calibrated Gyro"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_calibrated_gyro(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::calibrated_gyro_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, - "Rx Data Trial %d Success: CalibratedGyro: vX: %.2lf vY: %.2lf vZ: " - "%.2lf", - (i + 1), report_data.calib_gyro_vel_x, report_data.calib_gyro_vel_y, report_data.calib_gyro_vel_z); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_calibrated_gyro(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::calibrated_gyro_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, - "No Rx Data Trial %d Success: CalibratedGyroDefaults: vX: %.2lf vY: %.2lf vZ: " - "%.2lf", - (i + 1), report_data.calib_gyro_vel_x, report_data.calib_gyro_vel_y, report_data.calib_gyro_vel_z); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable Accelerometer", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable Accelerometer"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_accelerometer(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, - "Rx Data Trial %d Success: AngularAccel: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_accelerometer(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::accelerometer_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, - "No Rx Data Trial %d Success: AngularAccelDefaults: aX: %.2lf accel aY: %.2lf accel aZ: " - "%.2lf Accuracy %s", - (i + 1), report_data.accel_x, report_data.accel_y, report_data.accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable Linear Accelerometer", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable Linear Accelerometer"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_linear_accelerometer(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, - "Rx Data Trial %d Success: LinearAccel: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_linear_accelerometer(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::linear_accelerometer_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, - "No Rx Data Trial %d Success: LinearAccelDefaults: laX: %.2lf laY: %.2lf laZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.lin_accel_x, report_data.lin_accel_y, report_data.lin_accel_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.lin_accel_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable Gravity", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable Gravity"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_gravity(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::gravity_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, - "Rx Data Trial %d Success: Gravity: gX: %.2lf gY: %.2lf gZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.grav_x, report_data.grav_y, report_data.grav_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.grav_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_gravity(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::gravity_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, - "No Rx Data Trial %d Success: GravityDefaults: gX: %.2lf gY: %.2lf gZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.grav_x, report_data.grav_y, report_data.grav_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.grav_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable Magnetometer", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable Magnetometer"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_magnetometer(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::magnetometer_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, - "Rx Data Trial %d Success: Magf: mX: %.2lf mY: %.2lf mZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.magf_x, report_data.magf_y, report_data.magf_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.magf_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_magnetometer(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::magnetometer_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, - "No Rx Data Trial %d Success: MagfDefaults: mX: %.2lf mY: %.2lf mZ: " - "%.2lf Accuracy: %s", - (i + 1), report_data.magf_x, report_data.magf_y, report_data.magf_z, - BNO08xTestHelper::BNO08xAccuracy_to_str(report_data.magf_accuracy)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable Step Counter", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable Step Counter"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_step_counter(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::step_counter_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, "Rx Data Trial %d Success: StepCounter: %d steps", (i + 1), report_data.step_count); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_step_counter(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::step_counter_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, "No Rx Data Trial %d Success: StepCounterDefault: %d steps", (i + 1), report_data.step_count); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable Stability Classifier", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable Stability Classifier"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_stability_classifier(REPORT_PERIOD); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::stability_classifier_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, "Rx Data Trial %d Success: StabilityClassifier: %s", (i + 1), - BNO08xTestHelper::BNO08xStability_to_str(report_data.stability_classifier)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_stability_classifier(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::stability_classifier_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, "No Rx Data Trial %d Success: StabilityClassifierDefault: %s", (i + 1), - BNO08xTestHelper::BNO08xStability_to_str(report_data.stability_classifier)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("Enable/Disable Activity Classifier", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "Enable/Disable Activity Classifier"; - BNO08x* imu = nullptr; - BNO08xTestHelper::imu_report_data_t report_data; - BNO08xTestHelper::imu_report_data_t prev_report_data; - bool new_data = false; - char msg_buff[200] = {}; - uint8_t activity_confidence_vals[9] = {}; - - BNO08xTestHelper::print_test_start_banner(TEST_TAG); - - imu = BNO08xTestHelper::get_test_imu(); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase started."); - /*enable respective report to test and ensure it reports new data */ - imu->enable_activity_classifier(5 * REPORT_PERIOD, BNO08xActivityEnable::ALL, activity_confidence_vals); - - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::activity_classifier_data_is_new(&report_data, &prev_report_data); - } - - // assert that new data from respective report has been received - TEST_ASSERT_EQUAL(true, new_data); - - sprintf(msg_buff, "Rx Data Trial %d Success: ActivityClassifier: %s", (i + 1), - BNO08xTestHelper::BNO08xActivity_to_str(report_data.activity_classifier)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report enabled testing phase completed."); - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase started."); - /*disable respective report to test and ensure it stops reporting new data */ - imu->disable_activity_classifier(); - for (int i = 0; i < RX_REPORT_TRIAL_CNT; i++) - { - new_data = false; - - if (imu->data_available()) - { - prev_report_data = report_data; - BNO08xTestHelper::update_report_data(&report_data); - - // check if any default values have been overwritten, implying new data from respective report - new_data = BNO08xTestHelper::activity_classifier_data_is_new(&report_data, &prev_report_data); - } - - // assert that no new data from respective report has been received - TEST_ASSERT_NOT_EQUAL(true, new_data); - - sprintf(msg_buff, "No Rx Data Trial %d Success: ActivityClassifierDefault: %s", (i + 1), - BNO08xTestHelper::BNO08xActivity_to_str(report_data.activity_classifier)); - - BNO08xTestHelper::print_test_msg(TEST_TAG, msg_buff); - - // reset all data used in report test - BNO08xTestHelper::reset_all_imu_data_to_test_defaults(); - BNO08xTestHelper::update_report_data(&report_data); - } - - BNO08xTestHelper::print_test_msg(TEST_TAG, "Report disabled testing phase completed."); - - BNO08xTestHelper::print_test_end_banner(TEST_TAG); -} - -TEST_CASE("BNO08x Driver Cleanup for [SingleReportEnableDisable] Tests", "[SingleReportEnableDisable]") -{ - const constexpr char* TEST_TAG = "BNO08x Driver Cleanup for [SingleReportEnableDisable] Tests"; - BNO08xTestHelper::print_test_msg(TEST_TAG, "Destroying BNO08x Driver."); - - BNO08xTestHelper::destroy_test_imu(); -}