removed all for re-write with SH2-lib
|
|
@ -1,3 +1,3 @@
|
||||||
idf_component_register(SRC_DIRS "source"
|
idf_component_register(SRC_DIRS "source" "SH2"
|
||||||
INCLUDE_DIRS "include"
|
INCLUDE_DIRS "include" "SH2"
|
||||||
REQUIRES driver esp_timer cmock)
|
REQUIRES driver esp_timer cmock)
|
||||||
|
|
|
||||||
|
|
@ -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 <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#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
|
||||||
|
|
@ -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;
|
||||||
|
}
|
||||||
|
|
@ -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 <stdint.h>
|
||||||
|
|
||||||
|
#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
|
||||||
|
|
@ -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
|
||||||
|
|
@ -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 <stdint.h>
|
||||||
|
|
||||||
|
// 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
|
||||||
|
|
@ -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);
|
||||||
|
}
|
||||||
|
|
@ -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 <stdint.h>
|
||||||
|
|
||||||
|
#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
|
||||||
|
|
@ -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 <string.h>
|
||||||
|
|
||||||
|
// ------------------------------------------------------------------------
|
||||||
|
// 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);
|
||||||
|
}
|
||||||
|
}
|
||||||
|
|
@ -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 <stdint.h>
|
||||||
|
#include <stdbool.h>
|
||||||
|
|
||||||
|
#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
|
||||||
|
|
@ -1,163 +0,0 @@
|
||||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
|
||||||
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US">
|
|
||||||
<head>
|
|
||||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
|
||||||
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
|
|
||||||
<meta name="generator" content="Doxygen 1.10.0"/>
|
|
||||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
|
||||||
<title>esp32_BNO08x: BNO08x.cpp File Reference</title>
|
|
||||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="jquery.js"></script>
|
|
||||||
<script type="text/javascript" src="dynsections.js"></script>
|
|
||||||
<script type="text/javascript" src="clipboard.js"></script>
|
|
||||||
<link href="navtree.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="resize.js"></script>
|
|
||||||
<script type="text/javascript" src="navtreedata.js"></script>
|
|
||||||
<script type="text/javascript" src="navtree.js"></script>
|
|
||||||
<script type="text/javascript" src="cookie.js"></script>
|
|
||||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
|
||||||
<script type="text/javascript" src="search/search.js"></script>
|
|
||||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
|
||||||
<div id="titlearea">
|
|
||||||
<table cellspacing="0" cellpadding="0">
|
|
||||||
<tbody>
|
|
||||||
<tr id="projectrow">
|
|
||||||
<td id="projectalign">
|
|
||||||
<div id="projectname">esp32_BNO08x<span id="projectnumber"> 1.2</span>
|
|
||||||
</div>
|
|
||||||
<div id="projectbrief">C++ BNO08x IMU driver component for esp-idf.</div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
</div>
|
|
||||||
<!-- end header part -->
|
|
||||||
<!-- Generated by Doxygen 1.10.0 -->
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
var searchBox = new SearchBox("searchBox", "search/",'.html');
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<script type="text/javascript" src="menudata.js"></script>
|
|
||||||
<script type="text/javascript" src="menu.js"></script>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() {
|
|
||||||
initMenu('',true,false,'search.php','Search');
|
|
||||||
$(function() { init_search(); });
|
|
||||||
});
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="main-nav"></div>
|
|
||||||
</div><!-- top -->
|
|
||||||
<div id="side-nav" class="ui-resizable side-nav-resizable">
|
|
||||||
<div id="nav-tree">
|
|
||||||
<div id="nav-tree-contents">
|
|
||||||
<div id="nav-sync" class="sync"></div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div id="splitbar" style="-moz-user-select:none;"
|
|
||||||
class="ui-resizable-handle">
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function(){initNavTree('_b_n_o08x_8cpp.html',''); initResizable(); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="doc-content">
|
|
||||||
<!-- window showing the filter options -->
|
|
||||||
<div id="MSearchSelectWindow"
|
|
||||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
|
||||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
|
||||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<!-- iframe showing the search results (closed by default) -->
|
|
||||||
<div id="MSearchResultsWindow">
|
|
||||||
<div id="MSearchResults">
|
|
||||||
<div class="SRPage">
|
|
||||||
<div id="SRIndex">
|
|
||||||
<div id="SRResults"></div>
|
|
||||||
<div class="SRStatus" id="Loading">Loading...</div>
|
|
||||||
<div class="SRStatus" id="Searching">Searching...</div>
|
|
||||||
<div class="SRStatus" id="NoMatches">No Matches</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="header">
|
|
||||||
<div class="headertitle"><div class="title">BNO08x.cpp File Reference</div></div>
|
|
||||||
</div><!--header-->
|
|
||||||
<div class="contents">
|
|
||||||
<div class="textblock"><code>#include "<a class="el" href="_b_n_o08x_8hpp_source.html">BNO08x.hpp</a>"</code><br />
|
|
||||||
<code>#include "<a class="el" href="_b_n_o08x__macros_8hpp_source.html">BNO08x_macros.hpp</a>"</code><br />
|
|
||||||
</div><div class="textblock"><div class="dynheader">
|
|
||||||
Include dependency graph for BNO08x.cpp:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_b_n_o08x_8cpp__incl.png" border="0" usemap="#a_b_n_o08x_8cpp" alt=""/></div>
|
|
||||||
<map name="a_b_n_o08x_8cpp" id="a_b_n_o08x_8cpp">
|
|
||||||
<area shape="rect" title=" " alt="" coords="589,5,684,32"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_8hpp.html" title=" " alt="" coords="1048,80,1143,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="685,25,1033,79,1032,85,684,30"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x__macros_8hpp.html" title=" " alt="" coords="192,80,337,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="589,32,345,79,344,74,588,27"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,155,84,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1047,97,891,99,659,107,384,125,241,139,99,157,99,152,240,134,383,120,658,102,891,94,1047,92"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1065,155,1126,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1098,107,1098,139,1093,139,1093,107"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1150,155,1211,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1112,105,1156,143,1153,147,1108,109"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1234,155,1295,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1126,105,1222,146,1220,151,1124,110"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1318,155,1395,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1141,105,1304,149,1302,155,1140,110"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1418,155,1474,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1144,100,1259,120,1404,151,1403,157,1258,125,1143,105"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1498,155,1575,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1144,98,1291,119,1483,152,1482,157,1291,124,1143,103"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1600,155,1713,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1144,97,1333,119,1585,152,1584,157,1332,124,1143,102"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1737,155,1827,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1143,95,1388,113,1552,129,1722,152,1721,157,1551,135,1387,118,1143,100"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="108,155,248,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1047,100,723,118,498,135,264,157,263,152,497,130,723,113,1047,94"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1851,155,1955,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1143,94,1432,112,1631,129,1836,152,1835,157,1630,134,1432,117,1143,99"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="272,155,428,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1047,101,793,122,443,157,443,152,793,117,1047,96"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="451,155,566,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1047,102,848,123,581,157,581,152,848,118,1047,97"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="590,155,712,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1048,105,728,157,727,152,1047,100"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="736,155,841,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1048,109,857,153,855,148,1046,103"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x__global__types_8hpp.html" title=" " alt="" coords="865,155,1040,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1072,110,992,150,990,145,1069,105"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="767,229,858,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="929,184,852,224,849,219,927,180"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="882,229,1023,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="955,182,955,214,950,214,950,182"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1047,229,1178,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="981,179,1072,220,1070,225,979,184"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="227,110,98,152,97,147,225,105"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="251,109,206,147,203,143,248,105"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="281,105,326,143,322,147,278,109"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
</div></div><!-- contents -->
|
|
||||||
</div><!-- doc-content -->
|
|
||||||
<!-- start footer part -->
|
|
||||||
<div id="nav-path" class="navpath"><!-- id is needed for treeview function! -->
|
|
||||||
<ul>
|
|
||||||
<li class="navelem"><a class="el" href="dir_85e9385bd83516731053aadc7da3c8af.html">imu_update</a></li><li class="navelem"><a class="el" href="dir_c60d9bf80716f90f729fd65c40ec81f7.html">bno08x_update</a></li><li class="navelem"><a class="el" href="dir_fd670e5d11b8bb731501003ff6578ae1.html">components</a></li><li class="navelem"><a class="el" href="dir_a6718ce9703adf4789a693642ffedf7f.html">esp32_BNO08x</a></li><li class="navelem"><a class="el" href="dir_105fd1ee051c171768c94e464b88861d.html">source</a></li><li class="navelem"><a class="el" href="_b_n_o08x_8cpp.html">BNO08x.cpp</a></li>
|
|
||||||
<li class="footer">Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.10.0 </li>
|
|
||||||
</ul>
|
|
||||||
</div>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
||||||
|
|
@ -1,48 +0,0 @@
|
||||||
<map id="BNO08x.cpp" name="BNO08x.cpp">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="589,5,684,32"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$_b_n_o08x_8hpp.html" title=" " alt="" coords="1048,80,1143,107"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="685,25,1033,79,1032,85,684,30"/>
|
|
||||||
<area shape="rect" id="Node000022" href="$_b_n_o08x__macros_8hpp.html" title=" " alt="" coords="192,80,337,107"/>
|
|
||||||
<area shape="poly" id="edge21_Node000001_Node000022" title=" " alt="" coords="589,32,345,79,344,74,588,27"/>
|
|
||||||
<area shape="rect" id="Node000003" title=" " alt="" coords="5,155,84,181"/>
|
|
||||||
<area shape="poly" id="edge2_Node000002_Node000003" title=" " alt="" coords="1047,97,891,99,659,107,384,125,241,139,99,157,99,152,240,134,383,120,658,102,891,94,1047,92"/>
|
|
||||||
<area shape="rect" id="Node000004" title=" " alt="" coords="1065,155,1126,181"/>
|
|
||||||
<area shape="poly" id="edge3_Node000002_Node000004" title=" " alt="" coords="1098,107,1098,139,1093,139,1093,107"/>
|
|
||||||
<area shape="rect" id="Node000005" title=" " alt="" coords="1150,155,1211,181"/>
|
|
||||||
<area shape="poly" id="edge4_Node000002_Node000005" title=" " alt="" coords="1112,105,1156,143,1153,147,1108,109"/>
|
|
||||||
<area shape="rect" id="Node000006" title=" " alt="" coords="1234,155,1295,181"/>
|
|
||||||
<area shape="poly" id="edge5_Node000002_Node000006" title=" " alt="" coords="1126,105,1222,146,1220,151,1124,110"/>
|
|
||||||
<area shape="rect" id="Node000007" title=" " alt="" coords="1318,155,1395,181"/>
|
|
||||||
<area shape="poly" id="edge6_Node000002_Node000007" title=" " alt="" coords="1141,105,1304,149,1302,155,1140,110"/>
|
|
||||||
<area shape="rect" id="Node000008" title=" " alt="" coords="1418,155,1474,181"/>
|
|
||||||
<area shape="poly" id="edge7_Node000002_Node000008" title=" " alt="" coords="1144,100,1259,120,1404,151,1403,157,1258,125,1143,105"/>
|
|
||||||
<area shape="rect" id="Node000009" title=" " alt="" coords="1498,155,1575,181"/>
|
|
||||||
<area shape="poly" id="edge8_Node000002_Node000009" title=" " alt="" coords="1144,98,1291,119,1483,152,1482,157,1291,124,1143,103"/>
|
|
||||||
<area shape="rect" id="Node000010" title=" " alt="" coords="1600,155,1713,181"/>
|
|
||||||
<area shape="poly" id="edge9_Node000002_Node000010" title=" " alt="" coords="1144,97,1333,119,1585,152,1584,157,1332,124,1143,102"/>
|
|
||||||
<area shape="rect" id="Node000011" title=" " alt="" coords="1737,155,1827,181"/>
|
|
||||||
<area shape="poly" id="edge10_Node000002_Node000011" title=" " alt="" coords="1143,95,1388,113,1552,129,1722,152,1721,157,1551,135,1387,118,1143,100"/>
|
|
||||||
<area shape="rect" id="Node000012" title=" " alt="" coords="108,155,248,181"/>
|
|
||||||
<area shape="poly" id="edge11_Node000002_Node000012" title=" " alt="" coords="1047,100,723,118,498,135,264,157,263,152,497,130,723,113,1047,94"/>
|
|
||||||
<area shape="rect" id="Node000013" title=" " alt="" coords="1851,155,1955,181"/>
|
|
||||||
<area shape="poly" id="edge12_Node000002_Node000013" title=" " alt="" coords="1143,94,1432,112,1631,129,1836,152,1835,157,1630,134,1432,117,1143,99"/>
|
|
||||||
<area shape="rect" id="Node000014" title=" " alt="" coords="272,155,428,181"/>
|
|
||||||
<area shape="poly" id="edge13_Node000002_Node000014" title=" " alt="" coords="1047,101,793,122,443,157,443,152,793,117,1047,96"/>
|
|
||||||
<area shape="rect" id="Node000015" title=" " alt="" coords="451,155,566,181"/>
|
|
||||||
<area shape="poly" id="edge14_Node000002_Node000015" title=" " alt="" coords="1047,102,848,123,581,157,581,152,848,118,1047,97"/>
|
|
||||||
<area shape="rect" id="Node000016" title=" " alt="" coords="590,155,712,181"/>
|
|
||||||
<area shape="poly" id="edge15_Node000002_Node000016" title=" " alt="" coords="1048,105,728,157,727,152,1047,100"/>
|
|
||||||
<area shape="rect" id="Node000017" title=" " alt="" coords="736,155,841,181"/>
|
|
||||||
<area shape="poly" id="edge16_Node000002_Node000017" title=" " alt="" coords="1048,109,857,153,855,148,1046,103"/>
|
|
||||||
<area shape="rect" id="Node000018" href="$_b_n_o08x__global__types_8hpp.html" title=" " alt="" coords="865,155,1040,181"/>
|
|
||||||
<area shape="poly" id="edge17_Node000002_Node000018" title=" " alt="" coords="1072,110,992,150,990,145,1069,105"/>
|
|
||||||
<area shape="rect" id="Node000019" title=" " alt="" coords="767,229,858,256"/>
|
|
||||||
<area shape="poly" id="edge18_Node000018_Node000019" title=" " alt="" coords="929,184,852,224,849,219,927,180"/>
|
|
||||||
<area shape="rect" id="Node000020" title=" " alt="" coords="882,229,1023,256"/>
|
|
||||||
<area shape="poly" id="edge19_Node000018_Node000020" title=" " alt="" coords="955,182,955,214,950,214,950,182"/>
|
|
||||||
<area shape="rect" id="Node000021" title=" " alt="" coords="1047,229,1178,256"/>
|
|
||||||
<area shape="poly" id="edge20_Node000018_Node000021" title=" " alt="" coords="981,179,1072,220,1070,225,979,184"/>
|
|
||||||
<area shape="poly" id="edge22_Node000022_Node000003" title=" " alt="" coords="227,110,98,152,97,147,225,105"/>
|
|
||||||
<area shape="poly" id="edge23_Node000022_Node000012" title=" " alt="" coords="251,109,206,147,203,143,248,105"/>
|
|
||||||
<area shape="poly" id="edge24_Node000022_Node000014" title=" " alt="" coords="281,105,326,143,322,147,278,109"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
41f1e1af7ac203ebf5cacac2a846b9ce
|
|
||||||
|
Before Width: | Height: | Size: 49 KiB |
|
|
@ -1,216 +0,0 @@
|
||||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
|
||||||
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US">
|
|
||||||
<head>
|
|
||||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
|
||||||
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
|
|
||||||
<meta name="generator" content="Doxygen 1.10.0"/>
|
|
||||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
|
||||||
<title>esp32_BNO08x: BNO08x.hpp File Reference</title>
|
|
||||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="jquery.js"></script>
|
|
||||||
<script type="text/javascript" src="dynsections.js"></script>
|
|
||||||
<script type="text/javascript" src="clipboard.js"></script>
|
|
||||||
<link href="navtree.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="resize.js"></script>
|
|
||||||
<script type="text/javascript" src="navtreedata.js"></script>
|
|
||||||
<script type="text/javascript" src="navtree.js"></script>
|
|
||||||
<script type="text/javascript" src="cookie.js"></script>
|
|
||||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
|
||||||
<script type="text/javascript" src="search/search.js"></script>
|
|
||||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
|
||||||
<div id="titlearea">
|
|
||||||
<table cellspacing="0" cellpadding="0">
|
|
||||||
<tbody>
|
|
||||||
<tr id="projectrow">
|
|
||||||
<td id="projectalign">
|
|
||||||
<div id="projectname">esp32_BNO08x<span id="projectnumber"> 1.2</span>
|
|
||||||
</div>
|
|
||||||
<div id="projectbrief">C++ BNO08x IMU driver component for esp-idf.</div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
</div>
|
|
||||||
<!-- end header part -->
|
|
||||||
<!-- Generated by Doxygen 1.10.0 -->
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
var searchBox = new SearchBox("searchBox", "search/",'.html');
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<script type="text/javascript" src="menudata.js"></script>
|
|
||||||
<script type="text/javascript" src="menu.js"></script>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() {
|
|
||||||
initMenu('',true,false,'search.php','Search');
|
|
||||||
$(function() { init_search(); });
|
|
||||||
});
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="main-nav"></div>
|
|
||||||
</div><!-- top -->
|
|
||||||
<div id="side-nav" class="ui-resizable side-nav-resizable">
|
|
||||||
<div id="nav-tree">
|
|
||||||
<div id="nav-tree-contents">
|
|
||||||
<div id="nav-sync" class="sync"></div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div id="splitbar" style="-moz-user-select:none;"
|
|
||||||
class="ui-resizable-handle">
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function(){initNavTree('_b_n_o08x_8hpp.html',''); initResizable(); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="doc-content">
|
|
||||||
<!-- window showing the filter options -->
|
|
||||||
<div id="MSearchSelectWindow"
|
|
||||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
|
||||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
|
||||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<!-- iframe showing the search results (closed by default) -->
|
|
||||||
<div id="MSearchResultsWindow">
|
|
||||||
<div id="MSearchResults">
|
|
||||||
<div class="SRPage">
|
|
||||||
<div id="SRIndex">
|
|
||||||
<div id="SRResults"></div>
|
|
||||||
<div class="SRStatus" id="Loading">Loading...</div>
|
|
||||||
<div class="SRStatus" id="Searching">Searching...</div>
|
|
||||||
<div class="SRStatus" id="NoMatches">No Matches</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="header">
|
|
||||||
<div class="summary">
|
|
||||||
<a href="#nested-classes">Classes</a> </div>
|
|
||||||
<div class="headertitle"><div class="title">BNO08x.hpp File Reference</div></div>
|
|
||||||
</div><!--header-->
|
|
||||||
<div class="contents">
|
|
||||||
<div class="textblock"><code>#include <inttypes.h></code><br />
|
|
||||||
<code>#include <math.h></code><br />
|
|
||||||
<code>#include <stdio.h></code><br />
|
|
||||||
<code>#include <cstring></code><br />
|
|
||||||
<code>#include <functional></code><br />
|
|
||||||
<code>#include <vector></code><br />
|
|
||||||
<code>#include <esp_log.h></code><br />
|
|
||||||
<code>#include <esp_rom_gpio.h></code><br />
|
|
||||||
<code>#include <esp_timer.h></code><br />
|
|
||||||
<code>#include <freertos/FreeRTOS.h></code><br />
|
|
||||||
<code>#include <freertos/task.h></code><br />
|
|
||||||
<code>#include <freertos/event_groups.h></code><br />
|
|
||||||
<code>#include <freertos/queue.h></code><br />
|
|
||||||
<code>#include <freertos/semphr.h></code><br />
|
|
||||||
<code>#include <rom/ets_sys.h></code><br />
|
|
||||||
<code>#include "<a class="el" href="_b_n_o08x__global__types_8hpp_source.html">BNO08x_global_types.hpp</a>"</code><br />
|
|
||||||
</div><div class="textblock"><div class="dynheader">
|
|
||||||
Include dependency graph for BNO08x.hpp:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_b_n_o08x_8hpp__incl.png" border="0" usemap="#a_b_n_o08x_8hpp" alt=""/></div>
|
|
||||||
<map name="a_b_n_o08x_8hpp" id="a_b_n_o08x_8hpp">
|
|
||||||
<area shape="rect" title=" " alt="" coords="714,5,810,32"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,80,84,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="714,25,455,41,280,58,99,82,99,77,280,53,455,36,714,19"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="107,80,169,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="714,25,488,41,339,58,184,82,183,77,338,53,488,36,713,20"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="193,80,253,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="714,26,523,44,398,60,269,82,268,77,397,55,522,38,714,21"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="277,80,337,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="714,27,557,47,353,82,352,77,556,42,713,22"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="361,80,437,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="714,31,453,82,452,77,713,26"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="461,80,516,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="715,34,532,82,530,77,713,29"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="541,80,618,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="731,35,626,76,624,71,729,30"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="643,80,756,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="753,34,722,70,718,66,749,31"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="780,80,869,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="775,31,806,66,802,70,771,34"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="893,80,1033,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="798,30,915,72,913,77,796,35"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1058,80,1162,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="810,27,1043,75,1042,81,809,33"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1186,80,1341,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="810,24,1171,76,1170,81,810,30"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1365,80,1479,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="810,21,1038,41,1350,77,1349,82,1038,47,810,26"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1503,80,1626,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="810,20,1093,39,1287,56,1488,77,1488,82,1286,61,1093,44,810,25"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1650,80,1754,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="810,19,1150,34,1388,52,1635,77,1634,82,1388,57,1150,40,810,24"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x__global__types_8hpp.html" title=" " alt="" coords="1778,80,1954,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="810,19,1199,38,1476,55,1763,77,1762,82,1475,60,1199,43,810,25"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1681,155,1771,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1843,110,1765,149,1763,145,1840,105"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1796,155,1936,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1869,107,1869,139,1863,139,1863,107"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1961,155,2091,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1895,105,1985,145,1983,150,1893,110"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
</div><div class="textblock"><div class="dynheader">
|
|
||||||
This graph shows which files directly or indirectly include this file:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_b_n_o08x_8hpp__dep__incl.png" border="0" usemap="#a_b_n_o08x_8hppdep" alt=""/></div>
|
|
||||||
<map name="a_b_n_o08x_8hppdep" id="a_b_n_o08x_8hppdep">
|
|
||||||
<area shape="rect" title=" " alt="" coords="273,5,368,32"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_8cpp.html" title=" " alt="" coords="198,80,294,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="299,45,261,82,257,78,295,41"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_test_helper_8hpp.html" title=" " alt="" coords="318,80,475,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="346,41,385,78,382,82,343,45"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_test_suite_8hpp.html" title=" " alt="" coords="5,155,156,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="327,113,136,157,135,151,326,108"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html" title=" " alt="" coords="180,155,309,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="358,116,272,156,270,152,355,111"/>
|
|
||||||
<area shape="rect" href="_init_deinit_tests_8cpp.html" title=" " alt="" coords="332,155,461,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="399,122,399,154,394,154,394,122"/>
|
|
||||||
<area shape="rect" href="_multi_report_tests_8cpp.html" title=" " alt="" coords="484,155,629,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="439,111,530,152,527,156,437,116"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html" title=" " alt="" coords="652,155,805,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="470,108,671,151,670,157,469,113"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<p><a href="_b_n_o08x_8hpp_source.html">Go to the source code of this file.</a></p>
|
|
||||||
<table class="memberdecls">
|
|
||||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a id="nested-classes" name="nested-classes"></a>
|
|
||||||
Classes</h2></td></tr>
|
|
||||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">class  </td><td class="memItemRight" valign="bottom"><a class="el" href="class_b_n_o08x.html">BNO08x</a></td></tr>
|
|
||||||
<tr class="memdesc:"><td class="mdescLeft"> </td><td class="mdescRight"><a class="el" href="class_b_n_o08x.html" title="BNO08x IMU driver class.">BNO08x</a> IMU driver class. <a href="class_b_n_o08x.html#details">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">struct  </td><td class="memItemRight" valign="bottom"><a class="el" href="struct_b_n_o08x_1_1bno08x__rx__packet__t.html">BNO08x::bno08x_rx_packet_t</a></td></tr>
|
|
||||||
<tr class="memdesc:"><td class="mdescLeft"> </td><td class="mdescRight">Holds data that is received over spi. <a href="struct_b_n_o08x_1_1bno08x__rx__packet__t.html#details">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">struct  </td><td class="memItemRight" valign="bottom"><a class="el" href="struct_b_n_o08x_1_1bno08x__tx__packet__t.html">BNO08x::bno08x_tx_packet_t</a></td></tr>
|
|
||||||
<tr class="memdesc:"><td class="mdescLeft"> </td><td class="mdescRight">Holds data that is sent over spi. <a href="struct_b_n_o08x_1_1bno08x__tx__packet__t.html#details">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">struct  </td><td class="memItemRight" valign="bottom"><a class="el" href="struct_b_n_o08x_1_1bno08x__report__period__tracker__t.html">BNO08x::bno08x_report_period_tracker_t</a></td></tr>
|
|
||||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">struct  </td><td class="memItemRight" valign="bottom"><a class="el" href="struct_b_n_o08x_1_1bno08x__init__status__t.html">BNO08x::bno08x_init_status_t</a></td></tr>
|
|
||||||
<tr class="memdesc:"><td class="mdescLeft"> </td><td class="mdescRight">Holds info about which functionality has been successfully initialized (used by deconstructor during cleanup). <a href="struct_b_n_o08x_1_1bno08x__init__status__t.html#details">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
</table>
|
|
||||||
<a name="details" id="details"></a><h2 class="groupheader">Detailed Description</h2>
|
|
||||||
<div class="textblock"><dl class="section author"><dt>Author</dt><dd>Myles Parfeniuk </dd></dl>
|
|
||||||
</div></div><!-- contents -->
|
|
||||||
</div><!-- doc-content -->
|
|
||||||
<!-- start footer part -->
|
|
||||||
<div id="nav-path" class="navpath"><!-- id is needed for treeview function! -->
|
|
||||||
<ul>
|
|
||||||
<li class="navelem"><a class="el" href="dir_85e9385bd83516731053aadc7da3c8af.html">imu_update</a></li><li class="navelem"><a class="el" href="dir_c60d9bf80716f90f729fd65c40ec81f7.html">bno08x_update</a></li><li class="navelem"><a class="el" href="dir_fd670e5d11b8bb731501003ff6578ae1.html">components</a></li><li class="navelem"><a class="el" href="dir_a6718ce9703adf4789a693642ffedf7f.html">esp32_BNO08x</a></li><li class="navelem"><a class="el" href="dir_9667f1a5b10a5222433e41df91e1bf5d.html">include</a></li><li class="navelem"><a class="el" href="_b_n_o08x_8hpp.html">BNO08x.hpp</a></li>
|
|
||||||
<li class="footer">Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.10.0 </li>
|
|
||||||
</ul>
|
|
||||||
</div>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
||||||
|
|
@ -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" ]
|
|
||||||
];
|
|
||||||
|
|
@ -1,17 +0,0 @@
|
||||||
<map id="BNO08x.hpp" name="BNO08x.hpp">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="273,5,368,32"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$_b_n_o08x_8cpp.html" title=" " alt="" coords="198,80,294,107"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="299,45,261,82,257,78,295,41"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$_b_n_o08x_test_helper_8hpp.html" title=" " alt="" coords="318,80,475,107"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="346,41,385,78,382,82,343,45"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$_b_n_o08x_test_suite_8hpp.html" title=" " alt="" coords="5,155,156,181"/>
|
|
||||||
<area shape="poly" id="edge3_Node000003_Node000004" title=" " alt="" coords="327,113,136,157,135,151,326,108"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$_callback_tests_8cpp.html" title=" " alt="" coords="180,155,309,181"/>
|
|
||||||
<area shape="poly" id="edge4_Node000003_Node000005" title=" " alt="" coords="358,116,272,156,270,152,355,111"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$_init_deinit_tests_8cpp.html" title=" " alt="" coords="332,155,461,181"/>
|
|
||||||
<area shape="poly" id="edge5_Node000003_Node000006" title=" " alt="" coords="399,122,399,154,394,154,394,122"/>
|
|
||||||
<area shape="rect" id="Node000007" href="$_multi_report_tests_8cpp.html" title=" " alt="" coords="484,155,629,181"/>
|
|
||||||
<area shape="poly" id="edge6_Node000003_Node000007" title=" " alt="" coords="439,111,530,152,527,156,437,116"/>
|
|
||||||
<area shape="rect" id="Node000008" href="$_single_report_tests_8cpp.html" title=" " alt="" coords="652,155,805,181"/>
|
|
||||||
<area shape="poly" id="edge7_Node000003_Node000008" title=" " alt="" coords="470,108,671,151,670,157,469,113"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
1c9e1c80262ef4583f7de7fae85142bc
|
|
||||||
|
Before Width: | Height: | Size: 10 KiB |
|
|
@ -1,41 +0,0 @@
|
||||||
<map id="BNO08x.hpp" name="BNO08x.hpp">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="714,5,810,32"/>
|
|
||||||
<area shape="rect" id="Node000002" title=" " alt="" coords="5,80,84,107"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="714,25,455,41,280,58,99,82,99,77,280,53,455,36,714,19"/>
|
|
||||||
<area shape="rect" id="Node000003" title=" " alt="" coords="107,80,169,107"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="714,25,488,41,339,58,184,82,183,77,338,53,488,36,713,20"/>
|
|
||||||
<area shape="rect" id="Node000004" title=" " alt="" coords="193,80,253,107"/>
|
|
||||||
<area shape="poly" id="edge3_Node000001_Node000004" title=" " alt="" coords="714,26,523,44,398,60,269,82,268,77,397,55,522,38,714,21"/>
|
|
||||||
<area shape="rect" id="Node000005" title=" " alt="" coords="277,80,337,107"/>
|
|
||||||
<area shape="poly" id="edge4_Node000001_Node000005" title=" " alt="" coords="714,27,557,47,353,82,352,77,556,42,713,22"/>
|
|
||||||
<area shape="rect" id="Node000006" title=" " alt="" coords="361,80,437,107"/>
|
|
||||||
<area shape="poly" id="edge5_Node000001_Node000006" title=" " alt="" coords="714,31,453,82,452,77,713,26"/>
|
|
||||||
<area shape="rect" id="Node000007" title=" " alt="" coords="461,80,516,107"/>
|
|
||||||
<area shape="poly" id="edge6_Node000001_Node000007" title=" " alt="" coords="715,34,532,82,530,77,713,29"/>
|
|
||||||
<area shape="rect" id="Node000008" title=" " alt="" coords="541,80,618,107"/>
|
|
||||||
<area shape="poly" id="edge7_Node000001_Node000008" title=" " alt="" coords="731,35,626,76,624,71,729,30"/>
|
|
||||||
<area shape="rect" id="Node000009" title=" " alt="" coords="643,80,756,107"/>
|
|
||||||
<area shape="poly" id="edge8_Node000001_Node000009" title=" " alt="" coords="753,34,722,70,718,66,749,31"/>
|
|
||||||
<area shape="rect" id="Node000010" title=" " alt="" coords="780,80,869,107"/>
|
|
||||||
<area shape="poly" id="edge9_Node000001_Node000010" title=" " alt="" coords="775,31,806,66,802,70,771,34"/>
|
|
||||||
<area shape="rect" id="Node000011" title=" " alt="" coords="893,80,1033,107"/>
|
|
||||||
<area shape="poly" id="edge10_Node000001_Node000011" title=" " alt="" coords="798,30,915,72,913,77,796,35"/>
|
|
||||||
<area shape="rect" id="Node000012" title=" " alt="" coords="1058,80,1162,107"/>
|
|
||||||
<area shape="poly" id="edge11_Node000001_Node000012" title=" " alt="" coords="810,27,1043,75,1042,81,809,33"/>
|
|
||||||
<area shape="rect" id="Node000013" title=" " alt="" coords="1186,80,1341,107"/>
|
|
||||||
<area shape="poly" id="edge12_Node000001_Node000013" title=" " alt="" coords="810,24,1171,76,1170,81,810,30"/>
|
|
||||||
<area shape="rect" id="Node000014" title=" " alt="" coords="1365,80,1479,107"/>
|
|
||||||
<area shape="poly" id="edge13_Node000001_Node000014" title=" " alt="" coords="810,21,1038,41,1350,77,1349,82,1038,47,810,26"/>
|
|
||||||
<area shape="rect" id="Node000015" title=" " alt="" coords="1503,80,1626,107"/>
|
|
||||||
<area shape="poly" id="edge14_Node000001_Node000015" title=" " alt="" coords="810,20,1093,39,1287,56,1488,77,1488,82,1286,61,1093,44,810,25"/>
|
|
||||||
<area shape="rect" id="Node000016" title=" " alt="" coords="1650,80,1754,107"/>
|
|
||||||
<area shape="poly" id="edge15_Node000001_Node000016" title=" " alt="" coords="810,19,1150,34,1388,52,1635,77,1634,82,1388,57,1150,40,810,24"/>
|
|
||||||
<area shape="rect" id="Node000017" href="$_b_n_o08x__global__types_8hpp.html" title=" " alt="" coords="1778,80,1954,107"/>
|
|
||||||
<area shape="poly" id="edge16_Node000001_Node000017" title=" " alt="" coords="810,19,1199,38,1476,55,1763,77,1762,82,1475,60,1199,43,810,25"/>
|
|
||||||
<area shape="rect" id="Node000018" title=" " alt="" coords="1681,155,1771,181"/>
|
|
||||||
<area shape="poly" id="edge17_Node000017_Node000018" title=" " alt="" coords="1843,110,1765,149,1763,145,1840,105"/>
|
|
||||||
<area shape="rect" id="Node000019" title=" " alt="" coords="1796,155,1936,181"/>
|
|
||||||
<area shape="poly" id="edge18_Node000017_Node000019" title=" " alt="" coords="1869,107,1869,139,1863,139,1863,107"/>
|
|
||||||
<area shape="rect" id="Node000020" title=" " alt="" coords="1961,155,2091,181"/>
|
|
||||||
<area shape="poly" id="edge19_Node000017_Node000020" title=" " alt="" coords="1895,105,1985,145,1983,150,1893,110"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
1cc9ccb34167ce6e7a68060da21b207f
|
|
||||||
|
Before Width: | Height: | Size: 41 KiB |
|
|
@ -1,469 +0,0 @@
|
||||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
|
||||||
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US">
|
|
||||||
<head>
|
|
||||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
|
||||||
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
|
|
||||||
<meta name="generator" content="Doxygen 1.10.0"/>
|
|
||||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
|
||||||
<title>esp32_BNO08x: BNO08x_global_types.hpp File Reference</title>
|
|
||||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="jquery.js"></script>
|
|
||||||
<script type="text/javascript" src="dynsections.js"></script>
|
|
||||||
<script type="text/javascript" src="clipboard.js"></script>
|
|
||||||
<link href="navtree.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="resize.js"></script>
|
|
||||||
<script type="text/javascript" src="navtreedata.js"></script>
|
|
||||||
<script type="text/javascript" src="navtree.js"></script>
|
|
||||||
<script type="text/javascript" src="cookie.js"></script>
|
|
||||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
|
||||||
<script type="text/javascript" src="search/search.js"></script>
|
|
||||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
|
||||||
<div id="titlearea">
|
|
||||||
<table cellspacing="0" cellpadding="0">
|
|
||||||
<tbody>
|
|
||||||
<tr id="projectrow">
|
|
||||||
<td id="projectalign">
|
|
||||||
<div id="projectname">esp32_BNO08x<span id="projectnumber"> 1.2</span>
|
|
||||||
</div>
|
|
||||||
<div id="projectbrief">C++ BNO08x IMU driver component for esp-idf.</div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
</div>
|
|
||||||
<!-- end header part -->
|
|
||||||
<!-- Generated by Doxygen 1.10.0 -->
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
var searchBox = new SearchBox("searchBox", "search/",'.html');
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<script type="text/javascript" src="menudata.js"></script>
|
|
||||||
<script type="text/javascript" src="menu.js"></script>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() {
|
|
||||||
initMenu('',true,false,'search.php','Search');
|
|
||||||
$(function() { init_search(); });
|
|
||||||
});
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="main-nav"></div>
|
|
||||||
</div><!-- top -->
|
|
||||||
<div id="side-nav" class="ui-resizable side-nav-resizable">
|
|
||||||
<div id="nav-tree">
|
|
||||||
<div id="nav-tree-contents">
|
|
||||||
<div id="nav-sync" class="sync"></div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div id="splitbar" style="-moz-user-select:none;"
|
|
||||||
class="ui-resizable-handle">
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function(){initNavTree('_b_n_o08x__global__types_8hpp.html',''); initResizable(); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="doc-content">
|
|
||||||
<!-- window showing the filter options -->
|
|
||||||
<div id="MSearchSelectWindow"
|
|
||||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
|
||||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
|
||||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<!-- iframe showing the search results (closed by default) -->
|
|
||||||
<div id="MSearchResultsWindow">
|
|
||||||
<div id="MSearchResults">
|
|
||||||
<div class="SRPage">
|
|
||||||
<div id="SRIndex">
|
|
||||||
<div id="SRResults"></div>
|
|
||||||
<div class="SRStatus" id="Loading">Loading...</div>
|
|
||||||
<div class="SRStatus" id="Searching">Searching...</div>
|
|
||||||
<div class="SRStatus" id="NoMatches">No Matches</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="header">
|
|
||||||
<div class="summary">
|
|
||||||
<a href="#nested-classes">Classes</a> |
|
|
||||||
<a href="#typedef-members">Typedefs</a> |
|
|
||||||
<a href="#enum-members">Enumerations</a> </div>
|
|
||||||
<div class="headertitle"><div class="title">BNO08x_global_types.hpp File Reference</div></div>
|
|
||||||
</div><!--header-->
|
|
||||||
<div class="contents">
|
|
||||||
<div class="textblock"><code>#include <driver/gpio.h></code><br />
|
|
||||||
<code>#include <driver/spi_common.h></code><br />
|
|
||||||
<code>#include <driver/spi_master.h></code><br />
|
|
||||||
</div><div class="textblock"><div class="dynheader">
|
|
||||||
Include dependency graph for BNO08x_global_types.hpp:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_b_n_o08x__global__types_8hpp__incl.png" border="0" usemap="#a_b_n_o08x__global__types_8hpp" alt=""/></div>
|
|
||||||
<map name="a_b_n_o08x__global__types_8hpp" id="a_b_n_o08x__global__types_8hpp">
|
|
||||||
<area shape="rect" title=" " alt="" coords="103,5,278,32"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,80,96,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="167,35,90,75,87,70,165,30"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="120,80,261,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="193,33,193,64,188,64,188,33"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="285,80,416,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="219,30,310,71,308,76,217,35"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
</div><div class="textblock"><div class="dynheader">
|
|
||||||
This graph shows which files directly or indirectly include this file:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_b_n_o08x__global__types_8hpp__dep__incl.png" border="0" usemap="#a_b_n_o08x__global__types_8hppdep" alt=""/></div>
|
|
||||||
<map name="a_b_n_o08x__global__types_8hppdep" id="a_b_n_o08x__global__types_8hppdep">
|
|
||||||
<area shape="rect" title=" " alt="" coords="233,5,408,32"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_8hpp.html" title=" " alt="" coords="273,80,368,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="323,48,323,80,318,80,318,48"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_8cpp.html" title=" " alt="" coords="198,155,294,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="299,119,261,156,257,152,295,116"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_test_helper_8hpp.html" title=" " alt="" coords="318,155,475,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="346,116,385,152,382,156,343,119"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_test_suite_8hpp.html" title=" " alt="" coords="5,229,156,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="327,188,136,231,135,226,326,183"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html" title=" " alt="" coords="180,229,309,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="358,191,272,231,270,226,355,186"/>
|
|
||||||
<area shape="rect" href="_init_deinit_tests_8cpp.html" title=" " alt="" coords="332,229,461,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="399,197,399,229,394,229,394,197"/>
|
|
||||||
<area shape="rect" href="_multi_report_tests_8cpp.html" title=" " alt="" coords="484,229,629,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="439,186,530,226,527,231,437,191"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html" title=" " alt="" coords="652,229,805,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="470,183,671,226,670,231,469,188"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<p><a href="_b_n_o08x__global__types_8hpp_source.html">Go to the source code of this file.</a></p>
|
|
||||||
<table class="memberdecls">
|
|
||||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a id="nested-classes" name="nested-classes"></a>
|
|
||||||
Classes</h2></td></tr>
|
|
||||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">struct  </td><td class="memItemRight" valign="bottom"><a class="el" href="structbno08x__config__t.html">bno08x_config_t</a></td></tr>
|
|
||||||
<tr class="memdesc:"><td class="mdescLeft"> </td><td class="mdescRight">IMU configuration settings passed into constructor. <a href="structbno08x__config__t.html#details">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
</table><table class="memberdecls">
|
|
||||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a id="typedef-members" name="typedef-members"></a>
|
|
||||||
Typedefs</h2></td></tr>
|
|
||||||
<tr class="memitem:a03fbbd71180a19088ce30d57ab050a22" id="r_a03fbbd71180a19088ce30d57ab050a22"><td class="memItemLeft" align="right" valign="top">using </td><td class="memItemRight" valign="bottom"><a class="el" href="#a03fbbd71180a19088ce30d57ab050a22">IMUAccuracy</a> = <a class="el" href="#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a></td></tr>
|
|
||||||
<tr class="separator:a03fbbd71180a19088ce30d57ab050a22"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:aeee029e15be2a7d6d8134cabcc7c752b" id="r_aeee029e15be2a7d6d8134cabcc7c752b"><td class="memItemLeft" align="right" valign="top">using </td><td class="memItemRight" valign="bottom"><a class="el" href="#aeee029e15be2a7d6d8134cabcc7c752b">IMUResetReason</a> = <a class="el" href="#ab2a2ace42f7f438d6a799dfcbc243147">BNO08xResetReason</a></td></tr>
|
|
||||||
<tr class="separator:aeee029e15be2a7d6d8134cabcc7c752b"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a648bbdbf22731476890dd8da977d7503" id="r_a648bbdbf22731476890dd8da977d7503"><td class="memItemLeft" align="right" valign="top">typedef struct bno08x_config_t </td><td class="memItemRight" valign="bottom"><a class="el" href="#a648bbdbf22731476890dd8da977d7503">bno08x_config_t</a></td></tr>
|
|
||||||
<tr class="memdesc:a648bbdbf22731476890dd8da977d7503"><td class="mdescLeft"> </td><td class="mdescRight">IMU configuration settings passed into constructor. <br /></td></tr>
|
|
||||||
<tr class="separator:a648bbdbf22731476890dd8da977d7503"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:aae502b3d91ddf903bba797646fd28d00" id="r_aae502b3d91ddf903bba797646fd28d00"><td class="memItemLeft" align="right" valign="top">typedef <a class="el" href="structbno08x__config__t.html">bno08x_config_t</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="#aae502b3d91ddf903bba797646fd28d00">imu_config_t</a></td></tr>
|
|
||||||
<tr class="separator:aae502b3d91ddf903bba797646fd28d00"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
</table><table class="memberdecls">
|
|
||||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a id="enum-members" name="enum-members"></a>
|
|
||||||
Enumerations</h2></td></tr>
|
|
||||||
<tr class="memitem:aed7bab8e55be415938e078ebe72562a0" id="r_aed7bab8e55be415938e078ebe72562a0"><td class="memItemLeft" align="right" valign="top">enum class  </td><td class="memItemRight" valign="bottom"><a class="el" href="#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a> { <a class="el" href="#aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88">LOW</a> = 1
|
|
||||||
, <a class="el" href="#aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c">MED</a>
|
|
||||||
, <a class="el" href="#aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c">HIGH</a>
|
|
||||||
, <a class="el" href="#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">UNDEFINED</a>
|
|
||||||
}</td></tr>
|
|
||||||
<tr class="memdesc:aed7bab8e55be415938e078ebe72562a0"><td class="mdescLeft"> </td><td class="mdescRight">Sensor accuracy returned during sensor calibration. <a href="#aed7bab8e55be415938e078ebe72562a0">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:aed7bab8e55be415938e078ebe72562a0"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:ab2a2ace42f7f438d6a799dfcbc243147" id="r_ab2a2ace42f7f438d6a799dfcbc243147"><td class="memItemLeft" align="right" valign="top">enum class  </td><td class="memItemRight" valign="bottom"><a class="el" href="#ab2a2ace42f7f438d6a799dfcbc243147">BNO08xResetReason</a> { <br />
|
|
||||||
  <a class="el" href="#ab2a2ace42f7f438d6a799dfcbc243147a0db45d2a4141101bdfe48e3314cfbca3">UNDEFINED</a>
|
|
||||||
, <a class="el" href="#ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92">POR</a>
|
|
||||||
, <a class="el" href="#ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f">INT_RST</a>
|
|
||||||
, <a class="el" href="#ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36">WTD</a>
|
|
||||||
, <br />
|
|
||||||
  <a class="el" href="#ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5">EXT_RST</a>
|
|
||||||
, <a class="el" href="#ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb">OTHER</a>
|
|
||||||
<br />
|
|
||||||
}</td></tr>
|
|
||||||
<tr class="memdesc:ab2a2ace42f7f438d6a799dfcbc243147"><td class="mdescLeft"> </td><td class="mdescRight">Reason for previous IMU reset (returned by get_reset_reason()) <a href="#ab2a2ace42f7f438d6a799dfcbc243147">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:ab2a2ace42f7f438d6a799dfcbc243147"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:adc1b530563e35a96fc1b8911ff133e0f" id="r_adc1b530563e35a96fc1b8911ff133e0f"><td class="memItemLeft" align="right" valign="top">enum class  </td><td class="memItemRight" valign="bottom"><a class="el" href="#adc1b530563e35a96fc1b8911ff133e0f">BNO08xActivityEnable</a> { <br />
|
|
||||||
  <a class="el" href="#adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3">UNKNOWN</a> = (1U << 0U)
|
|
||||||
, <a class="el" href="#adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4">IN_VEHICLE</a> = (1U << 1U)
|
|
||||||
, <a class="el" href="#adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4">ON_BICYCLE</a> = (1U << 2U)
|
|
||||||
, <a class="el" href="#adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58">ON_FOOT</a> = (1U << 3U)
|
|
||||||
, <br />
|
|
||||||
  <a class="el" href="#adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6">STILL</a> = (1U << 4U)
|
|
||||||
, <a class="el" href="#adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c">TILTING</a> = (1U << 5U)
|
|
||||||
, <a class="el" href="#adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3">WALKING</a> = (1U << 6U)
|
|
||||||
, <a class="el" href="#adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd">RUNNING</a> = (1U << 7U)
|
|
||||||
, <br />
|
|
||||||
  <a class="el" href="#adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515">ON_STAIRS</a> = (1U << 8U)
|
|
||||||
, <a class="el" href="#adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d">ALL</a> = 0x1FU
|
|
||||||
<br />
|
|
||||||
}</td></tr>
|
|
||||||
<tr class="memdesc:adc1b530563e35a96fc1b8911ff133e0f"><td class="mdescLeft"> </td><td class="mdescRight">BNO08xActivity Classifier enable bits passed to enable_activity_classifier() <a href="#adc1b530563e35a96fc1b8911ff133e0f">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:adc1b530563e35a96fc1b8911ff133e0f"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:abcc5d57e21ea6ed79e792deafcb62187" id="r_abcc5d57e21ea6ed79e792deafcb62187"><td class="memItemLeft" align="right" valign="top">enum class  </td><td class="memItemRight" valign="bottom"><a class="el" href="#abcc5d57e21ea6ed79e792deafcb62187">BNO08xActivity</a> { <br />
|
|
||||||
  <a class="el" href="#abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3">UNKNOWN</a> = 0
|
|
||||||
, <a class="el" href="#abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4">IN_VEHICLE</a> = 1
|
|
||||||
, <a class="el" href="#abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4">ON_BICYCLE</a> = 2
|
|
||||||
, <a class="el" href="#abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58">ON_FOOT</a> = 3
|
|
||||||
, <br />
|
|
||||||
  <a class="el" href="#abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6">STILL</a> = 4
|
|
||||||
, <a class="el" href="#abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c">TILTING</a> = 5
|
|
||||||
, <a class="el" href="#abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3">WALKING</a> = 6
|
|
||||||
, <a class="el" href="#abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd">RUNNING</a> = 7
|
|
||||||
, <br />
|
|
||||||
  <a class="el" href="#abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515">ON_STAIRS</a> = 8
|
|
||||||
, <a class="el" href="#abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3">UNDEFINED</a> = 9
|
|
||||||
<br />
|
|
||||||
}</td></tr>
|
|
||||||
<tr class="memdesc:abcc5d57e21ea6ed79e792deafcb62187"><td class="mdescLeft"> </td><td class="mdescRight">BNO08xActivity states returned from get_activity_classifier() <a href="#abcc5d57e21ea6ed79e792deafcb62187">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:abcc5d57e21ea6ed79e792deafcb62187"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a498b35f9e00b24e51f8f60b029751ab5" id="r_a498b35f9e00b24e51f8f60b029751ab5"><td class="memItemLeft" align="right" valign="top">enum class  </td><td class="memItemRight" valign="bottom"><a class="el" href="#a498b35f9e00b24e51f8f60b029751ab5">BNO08xStability</a> { <a class="el" href="#a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3">UNKNOWN</a> = 0
|
|
||||||
, <a class="el" href="#a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a">ON_TABLE</a> = 1
|
|
||||||
, <a class="el" href="#a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146">STATIONARY</a> = 2
|
|
||||||
, <a class="el" href="#a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3">UNDEFINED</a> = 3
|
|
||||||
}</td></tr>
|
|
||||||
<tr class="memdesc:a498b35f9e00b24e51f8f60b029751ab5"><td class="mdescLeft"> </td><td class="mdescRight">BNO08xStability states returned from get_stability_classifier() <a href="#a498b35f9e00b24e51f8f60b029751ab5">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:a498b35f9e00b24e51f8f60b029751ab5"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
</table>
|
|
||||||
<a name="details" id="details"></a><h2 class="groupheader">Detailed Description</h2>
|
|
||||||
<div class="textblock"><dl class="section author"><dt>Author</dt><dd>Myles Parfeniuk </dd></dl>
|
|
||||||
</div><h2 class="groupheader">Typedef Documentation</h2>
|
|
||||||
<a id="a648bbdbf22731476890dd8da977d7503" name="a648bbdbf22731476890dd8da977d7503"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a648bbdbf22731476890dd8da977d7503">◆ </a></span>bno08x_config_t</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">typedef struct bno08x_config_t bno08x_config_t</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
<p>IMU configuration settings passed into constructor. </p>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="aae502b3d91ddf903bba797646fd28d00" name="aae502b3d91ddf903bba797646fd28d00"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#aae502b3d91ddf903bba797646fd28d00">◆ </a></span>imu_config_t</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">typedef <a class="el" href="structbno08x__config__t.html">bno08x_config_t</a> <a class="el" href="#aae502b3d91ddf903bba797646fd28d00">imu_config_t</a></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a03fbbd71180a19088ce30d57ab050a22" name="a03fbbd71180a19088ce30d57ab050a22"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a03fbbd71180a19088ce30d57ab050a22">◆ </a></span>IMUAccuracy</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">using <a class="el" href="#aed7bab8e55be415938e078ebe72562a0">IMUAccuracy</a> = <a class="el" href="#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="aeee029e15be2a7d6d8134cabcc7c752b" name="aeee029e15be2a7d6d8134cabcc7c752b"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#aeee029e15be2a7d6d8134cabcc7c752b">◆ </a></span>IMUResetReason</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">using <a class="el" href="#ab2a2ace42f7f438d6a799dfcbc243147">IMUResetReason</a> = <a class="el" href="#ab2a2ace42f7f438d6a799dfcbc243147">BNO08xResetReason</a></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<h2 class="groupheader">Enumeration Type Documentation</h2>
|
|
||||||
<a id="aed7bab8e55be415938e078ebe72562a0" name="aed7bab8e55be415938e078ebe72562a0"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#aed7bab8e55be415938e078ebe72562a0">◆ </a></span>BNO08xAccuracy</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="mlabels">
|
|
||||||
<tr>
|
|
||||||
<td class="mlabels-left">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">enum class <a class="el" href="#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</td>
|
|
||||||
<td class="mlabels-right">
|
|
||||||
<span class="mlabels"><span class="mlabel">strong</span></span> </td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
<p>Sensor accuracy returned during sensor calibration. </p>
|
|
||||||
<table class="fieldtable">
|
|
||||||
<tr><th colspan="2">Enumerator</th></tr><tr><td class="fieldname"><a id="aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88" name="aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88"></a>LOW </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c" name="aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c"></a>MED </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c" name="aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c"></a>HIGH </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3" name="aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3"></a>UNDEFINED </td><td class="fielddoc"></td></tr>
|
|
||||||
</table>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="abcc5d57e21ea6ed79e792deafcb62187" name="abcc5d57e21ea6ed79e792deafcb62187"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#abcc5d57e21ea6ed79e792deafcb62187">◆ </a></span>BNO08xActivity</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="mlabels">
|
|
||||||
<tr>
|
|
||||||
<td class="mlabels-left">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">enum class <a class="el" href="#abcc5d57e21ea6ed79e792deafcb62187">BNO08xActivity</a></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</td>
|
|
||||||
<td class="mlabels-right">
|
|
||||||
<span class="mlabels"><span class="mlabel">strong</span></span> </td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
<p>BNO08xActivity states returned from get_activity_classifier() </p>
|
|
||||||
<table class="fieldtable">
|
|
||||||
<tr><th colspan="2">Enumerator</th></tr><tr><td class="fieldname"><a id="abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3" name="abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3"></a>UNKNOWN </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4" name="abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4"></a>IN_VEHICLE </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4" name="abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4"></a>ON_BICYCLE </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58" name="abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58"></a>ON_FOOT </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6" name="abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6"></a>STILL </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c" name="abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c"></a>TILTING </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3" name="abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3"></a>WALKING </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd" name="abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd"></a>RUNNING </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515" name="abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515"></a>ON_STAIRS </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3" name="abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3"></a>UNDEFINED </td><td class="fielddoc"></td></tr>
|
|
||||||
</table>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="adc1b530563e35a96fc1b8911ff133e0f" name="adc1b530563e35a96fc1b8911ff133e0f"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#adc1b530563e35a96fc1b8911ff133e0f">◆ </a></span>BNO08xActivityEnable</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="mlabels">
|
|
||||||
<tr>
|
|
||||||
<td class="mlabels-left">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">enum class <a class="el" href="#adc1b530563e35a96fc1b8911ff133e0f">BNO08xActivityEnable</a></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</td>
|
|
||||||
<td class="mlabels-right">
|
|
||||||
<span class="mlabels"><span class="mlabel">strong</span></span> </td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
<p>BNO08xActivity Classifier enable bits passed to enable_activity_classifier() </p>
|
|
||||||
<table class="fieldtable">
|
|
||||||
<tr><th colspan="2">Enumerator</th></tr><tr><td class="fieldname"><a id="adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3" name="adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3"></a>UNKNOWN </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4" name="adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4"></a>IN_VEHICLE </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4" name="adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4"></a>ON_BICYCLE </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58" name="adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58"></a>ON_FOOT </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6" name="adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6"></a>STILL </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c" name="adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c"></a>TILTING </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3" name="adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3"></a>WALKING </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd" name="adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd"></a>RUNNING </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515" name="adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515"></a>ON_STAIRS </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d" name="adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d"></a>ALL </td><td class="fielddoc"></td></tr>
|
|
||||||
</table>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="ab2a2ace42f7f438d6a799dfcbc243147" name="ab2a2ace42f7f438d6a799dfcbc243147"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#ab2a2ace42f7f438d6a799dfcbc243147">◆ </a></span>BNO08xResetReason</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="mlabels">
|
|
||||||
<tr>
|
|
||||||
<td class="mlabels-left">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">enum class <a class="el" href="#ab2a2ace42f7f438d6a799dfcbc243147">BNO08xResetReason</a></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</td>
|
|
||||||
<td class="mlabels-right">
|
|
||||||
<span class="mlabels"><span class="mlabel">strong</span></span> </td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
<p>Reason for previous IMU reset (returned by get_reset_reason()) </p>
|
|
||||||
<table class="fieldtable">
|
|
||||||
<tr><th colspan="2">Enumerator</th></tr><tr><td class="fieldname"><a id="ab2a2ace42f7f438d6a799dfcbc243147a0db45d2a4141101bdfe48e3314cfbca3" name="ab2a2ace42f7f438d6a799dfcbc243147a0db45d2a4141101bdfe48e3314cfbca3"></a>UNDEFINED </td><td class="fielddoc"><p>Undefined reset reason, this should never occur and is an error. </p>
|
|
||||||
</td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92" name="ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92"></a>POR </td><td class="fielddoc"><p>Previous reset was due to power on reset. </p>
|
|
||||||
</td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f" name="ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f"></a>INT_RST </td><td class="fielddoc"><p>Previous reset was due to internal reset. </p>
|
|
||||||
</td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36" name="ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36"></a>WTD </td><td class="fielddoc"><p>Previous reset was due to watchdog timer. </p>
|
|
||||||
</td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5" name="ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5"></a>EXT_RST </td><td class="fielddoc"><p>Previous reset was due to external reset. </p>
|
|
||||||
</td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb" name="ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb"></a>OTHER </td><td class="fielddoc"><p>Previous reset was due to power other reason. </p>
|
|
||||||
</td></tr>
|
|
||||||
</table>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a498b35f9e00b24e51f8f60b029751ab5" name="a498b35f9e00b24e51f8f60b029751ab5"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a498b35f9e00b24e51f8f60b029751ab5">◆ </a></span>BNO08xStability</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="mlabels">
|
|
||||||
<tr>
|
|
||||||
<td class="mlabels-left">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">enum class <a class="el" href="#a498b35f9e00b24e51f8f60b029751ab5">BNO08xStability</a></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</td>
|
|
||||||
<td class="mlabels-right">
|
|
||||||
<span class="mlabels"><span class="mlabel">strong</span></span> </td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
<p>BNO08xStability states returned from get_stability_classifier() </p>
|
|
||||||
<table class="fieldtable">
|
|
||||||
<tr><th colspan="2">Enumerator</th></tr><tr><td class="fieldname"><a id="a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3" name="a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3"></a>UNKNOWN </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a" name="a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a"></a>ON_TABLE </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146" name="a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146"></a>STATIONARY </td><td class="fielddoc"></td></tr>
|
|
||||||
<tr><td class="fieldname"><a id="a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3" name="a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3"></a>UNDEFINED </td><td class="fielddoc"></td></tr>
|
|
||||||
</table>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div><!-- contents -->
|
|
||||||
</div><!-- doc-content -->
|
|
||||||
<!-- start footer part -->
|
|
||||||
<div id="nav-path" class="navpath"><!-- id is needed for treeview function! -->
|
|
||||||
<ul>
|
|
||||||
<li class="navelem"><a class="el" href="dir_85e9385bd83516731053aadc7da3c8af.html">imu_update</a></li><li class="navelem"><a class="el" href="dir_c60d9bf80716f90f729fd65c40ec81f7.html">bno08x_update</a></li><li class="navelem"><a class="el" href="dir_fd670e5d11b8bb731501003ff6578ae1.html">components</a></li><li class="navelem"><a class="el" href="dir_a6718ce9703adf4789a693642ffedf7f.html">esp32_BNO08x</a></li><li class="navelem"><a class="el" href="dir_9667f1a5b10a5222433e41df91e1bf5d.html">include</a></li><li class="navelem"><a class="el" href="_b_n_o08x__global__types_8hpp.html">BNO08x_global_types.hpp</a></li>
|
|
||||||
<li class="footer">Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.10.0 </li>
|
|
||||||
</ul>
|
|
||||||
</div>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
||||||
|
|
@ -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 ]
|
|
||||||
] ]
|
|
||||||
];
|
|
||||||
|
|
@ -1,19 +0,0 @@
|
||||||
<map id="BNO08x_global_types.hpp" name="BNO08x_global_types.hpp">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="233,5,408,32"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$_b_n_o08x_8hpp.html" title=" " alt="" coords="273,80,368,107"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="323,48,323,80,318,80,318,48"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$_b_n_o08x_8cpp.html" title=" " alt="" coords="198,155,294,181"/>
|
|
||||||
<area shape="poly" id="edge2_Node000002_Node000003" title=" " alt="" coords="299,119,261,156,257,152,295,116"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$_b_n_o08x_test_helper_8hpp.html" title=" " alt="" coords="318,155,475,181"/>
|
|
||||||
<area shape="poly" id="edge3_Node000002_Node000004" title=" " alt="" coords="346,116,385,152,382,156,343,119"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$_b_n_o08x_test_suite_8hpp.html" title=" " alt="" coords="5,229,156,256"/>
|
|
||||||
<area shape="poly" id="edge4_Node000004_Node000005" title=" " alt="" coords="327,188,136,231,135,226,326,183"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$_callback_tests_8cpp.html" title=" " alt="" coords="180,229,309,256"/>
|
|
||||||
<area shape="poly" id="edge5_Node000004_Node000006" title=" " alt="" coords="358,191,272,231,270,226,355,186"/>
|
|
||||||
<area shape="rect" id="Node000007" href="$_init_deinit_tests_8cpp.html" title=" " alt="" coords="332,229,461,256"/>
|
|
||||||
<area shape="poly" id="edge6_Node000004_Node000007" title=" " alt="" coords="399,197,399,229,394,229,394,197"/>
|
|
||||||
<area shape="rect" id="Node000008" href="$_multi_report_tests_8cpp.html" title=" " alt="" coords="484,229,629,256"/>
|
|
||||||
<area shape="poly" id="edge7_Node000004_Node000008" title=" " alt="" coords="439,186,530,226,527,231,437,191"/>
|
|
||||||
<area shape="rect" id="Node000009" href="$_single_report_tests_8cpp.html" title=" " alt="" coords="652,229,805,256"/>
|
|
||||||
<area shape="poly" id="edge8_Node000004_Node000009" title=" " alt="" coords="470,183,671,226,670,231,469,188"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
e110ea5e0b3c2b55f8b0b5c728e78d3c
|
|
||||||
|
Before Width: | Height: | Size: 11 KiB |
|
|
@ -1,9 +0,0 @@
|
||||||
<map id="BNO08x_global_types.hpp" name="BNO08x_global_types.hpp">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="103,5,278,32"/>
|
|
||||||
<area shape="rect" id="Node000002" title=" " alt="" coords="5,80,96,107"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="167,35,90,75,87,70,165,30"/>
|
|
||||||
<area shape="rect" id="Node000003" title=" " alt="" coords="120,80,261,107"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="193,33,193,64,188,64,188,33"/>
|
|
||||||
<area shape="rect" id="Node000004" title=" " alt="" coords="285,80,416,107"/>
|
|
||||||
<area shape="poly" id="edge3_Node000001_Node000004" title=" " alt="" coords="219,30,310,71,308,76,217,35"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
6307718186d33aeef219aebf20b375cb
|
|
||||||
|
Before Width: | Height: | Size: 3.9 KiB |
|
|
@ -1,278 +0,0 @@
|
||||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
|
||||||
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US">
|
|
||||||
<head>
|
|
||||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
|
||||||
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
|
|
||||||
<meta name="generator" content="Doxygen 1.10.0"/>
|
|
||||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
|
||||||
<title>esp32_BNO08x: BNO08x_global_types.hpp Source File</title>
|
|
||||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="jquery.js"></script>
|
|
||||||
<script type="text/javascript" src="dynsections.js"></script>
|
|
||||||
<script type="text/javascript" src="clipboard.js"></script>
|
|
||||||
<link href="navtree.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="resize.js"></script>
|
|
||||||
<script type="text/javascript" src="navtreedata.js"></script>
|
|
||||||
<script type="text/javascript" src="navtree.js"></script>
|
|
||||||
<script type="text/javascript" src="cookie.js"></script>
|
|
||||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
|
||||||
<script type="text/javascript" src="search/search.js"></script>
|
|
||||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
|
||||||
<div id="titlearea">
|
|
||||||
<table cellspacing="0" cellpadding="0">
|
|
||||||
<tbody>
|
|
||||||
<tr id="projectrow">
|
|
||||||
<td id="projectalign">
|
|
||||||
<div id="projectname">esp32_BNO08x<span id="projectnumber"> 1.2</span>
|
|
||||||
</div>
|
|
||||||
<div id="projectbrief">C++ BNO08x IMU driver component for esp-idf.</div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
</div>
|
|
||||||
<!-- end header part -->
|
|
||||||
<!-- Generated by Doxygen 1.10.0 -->
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
var searchBox = new SearchBox("searchBox", "search/",'.html');
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<script type="text/javascript" src="menudata.js"></script>
|
|
||||||
<script type="text/javascript" src="menu.js"></script>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() {
|
|
||||||
initMenu('',true,false,'search.php','Search');
|
|
||||||
$(function() { init_search(); });
|
|
||||||
});
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="main-nav"></div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() { codefold.init(0); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
</div><!-- top -->
|
|
||||||
<div id="side-nav" class="ui-resizable side-nav-resizable">
|
|
||||||
<div id="nav-tree">
|
|
||||||
<div id="nav-tree-contents">
|
|
||||||
<div id="nav-sync" class="sync"></div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div id="splitbar" style="-moz-user-select:none;"
|
|
||||||
class="ui-resizable-handle">
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function(){initNavTree('_b_n_o08x__global__types_8hpp_source.html',''); initResizable(); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="doc-content">
|
|
||||||
<!-- window showing the filter options -->
|
|
||||||
<div id="MSearchSelectWindow"
|
|
||||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
|
||||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
|
||||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<!-- iframe showing the search results (closed by default) -->
|
|
||||||
<div id="MSearchResultsWindow">
|
|
||||||
<div id="MSearchResults">
|
|
||||||
<div class="SRPage">
|
|
||||||
<div id="SRIndex">
|
|
||||||
<div id="SRResults"></div>
|
|
||||||
<div class="SRStatus" id="Loading">Loading...</div>
|
|
||||||
<div class="SRStatus" id="Searching">Searching...</div>
|
|
||||||
<div class="SRStatus" id="NoMatches">No Matches</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="header">
|
|
||||||
<div class="headertitle"><div class="title">BNO08x_global_types.hpp</div></div>
|
|
||||||
</div><!--header-->
|
|
||||||
<div class="contents">
|
|
||||||
<a href="_b_n_o08x__global__types_8hpp.html">Go to the documentation of this file.</a><div class="fragment"><div class="line"><a id="l00001" name="l00001"></a><span class="lineno"> 1</span> </div>
|
|
||||||
<div class="line"><a id="l00005" name="l00005"></a><span class="lineno"> 5</span><span class="preprocessor">#pragma once</span></div>
|
|
||||||
<div class="line"><a id="l00006" name="l00006"></a><span class="lineno"> 6</span> </div>
|
|
||||||
<div class="line"><a id="l00007" name="l00007"></a><span class="lineno"> 7</span><span class="preprocessor">#include <driver/gpio.h></span></div>
|
|
||||||
<div class="line"><a id="l00008" name="l00008"></a><span class="lineno"> 8</span><span class="preprocessor">#include <driver/spi_common.h></span></div>
|
|
||||||
<div class="line"><a id="l00009" name="l00009"></a><span class="lineno"> 9</span><span class="preprocessor">#include <driver/spi_master.h></span></div>
|
|
||||||
<div class="line"><a id="l00010" name="l00010"></a><span class="lineno"> 10</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00012" data-start="{" data-end="};">
|
|
||||||
<div class="line"><a id="l00012" name="l00012"></a><span class="lineno"><a class="line" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0"> 12</a></span><span class="keyword">enum class</span> <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a></div>
|
|
||||||
<div class="line"><a id="l00013" name="l00013"></a><span class="lineno"> 13</span>{</div>
|
|
||||||
<div class="line"><a id="l00014" name="l00014"></a><span class="lineno"> 14</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88">LOW</a> = 1,</div>
|
|
||||||
<div class="line"><a id="l00015" name="l00015"></a><span class="lineno"> 15</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c">MED</a>,</div>
|
|
||||||
<div class="line"><a id="l00016" name="l00016"></a><span class="lineno"> 16</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c">HIGH</a>,</div>
|
|
||||||
<div class="line"><a id="l00017" name="l00017"></a><span class="lineno"> 17</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">UNDEFINED</a></div>
|
|
||||||
<div class="line"><a id="l00018" name="l00018"></a><span class="lineno"> 18</span>};</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00019" name="l00019"></a><span class="lineno"><a class="line" href="_b_n_o08x__global__types_8hpp.html#a03fbbd71180a19088ce30d57ab050a22"> 19</a></span><span class="keyword">using </span><a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0">IMUAccuracy</a> = <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a>; <span class="comment">// legacy version compatibility</span></div>
|
|
||||||
<div class="line"><a id="l00020" name="l00020"></a><span class="lineno"> 20</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00022" data-start="{" data-end="};">
|
|
||||||
<div class="line"><a id="l00022" name="l00022"></a><span class="lineno"><a class="line" href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147"> 22</a></span><span class="keyword">enum class</span> <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147">BNO08xResetReason</a></div>
|
|
||||||
<div class="line"><a id="l00023" name="l00023"></a><span class="lineno"> 23</span>{</div>
|
|
||||||
<div class="line"><a id="l00024" name="l00024"></a><span class="lineno"> 24</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">UNDEFINED</a>, </div>
|
|
||||||
<div class="line"><a id="l00025" name="l00025"></a><span class="lineno"> 25</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92">POR</a>, </div>
|
|
||||||
<div class="line"><a id="l00026" name="l00026"></a><span class="lineno"> 26</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f">INT_RST</a>, </div>
|
|
||||||
<div class="line"><a id="l00027" name="l00027"></a><span class="lineno"> 27</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36">WTD</a>, </div>
|
|
||||||
<div class="line"><a id="l00028" name="l00028"></a><span class="lineno"> 28</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5">EXT_RST</a>, </div>
|
|
||||||
<div class="line"><a id="l00029" name="l00029"></a><span class="lineno"> 29</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb">OTHER</a> </div>
|
|
||||||
<div class="line"><a id="l00030" name="l00030"></a><span class="lineno"> 30</span>};</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00031" name="l00031"></a><span class="lineno"><a class="line" href="_b_n_o08x__global__types_8hpp.html#aeee029e15be2a7d6d8134cabcc7c752b"> 31</a></span><span class="keyword">using </span><a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147">IMUResetReason</a> = <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147">BNO08xResetReason</a>; <span class="comment">// legacy version compatibility</span></div>
|
|
||||||
<div class="line"><a id="l00032" name="l00032"></a><span class="lineno"> 32</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00034" data-start="{" data-end="};">
|
|
||||||
<div class="line"><a id="l00034" name="l00034"></a><span class="lineno"><a class="line" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0f"> 34</a></span><span class="keyword">enum class</span> <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0f">BNO08xActivityEnable</a></div>
|
|
||||||
<div class="line"><a id="l00035" name="l00035"></a><span class="lineno"> 35</span>{</div>
|
|
||||||
<div class="line"><a id="l00036" name="l00036"></a><span class="lineno"> 36</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3">UNKNOWN</a> = (1U << 0U),</div>
|
|
||||||
<div class="line"><a id="l00037" name="l00037"></a><span class="lineno"> 37</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4">IN_VEHICLE</a> = (1U << 1U),</div>
|
|
||||||
<div class="line"><a id="l00038" name="l00038"></a><span class="lineno"> 38</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4">ON_BICYCLE</a> = (1U << 2U),</div>
|
|
||||||
<div class="line"><a id="l00039" name="l00039"></a><span class="lineno"> 39</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58">ON_FOOT</a> = (1U << 3U),</div>
|
|
||||||
<div class="line"><a id="l00040" name="l00040"></a><span class="lineno"> 40</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6">STILL</a> = (1U << 4U),</div>
|
|
||||||
<div class="line"><a id="l00041" name="l00041"></a><span class="lineno"> 41</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c">TILTING</a> = (1U << 5U),</div>
|
|
||||||
<div class="line"><a id="l00042" name="l00042"></a><span class="lineno"> 42</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3">WALKING</a> = (1U << 6U),</div>
|
|
||||||
<div class="line"><a id="l00043" name="l00043"></a><span class="lineno"> 43</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd">RUNNING</a> = (1U << 7U),</div>
|
|
||||||
<div class="line"><a id="l00044" name="l00044"></a><span class="lineno"> 44</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515">ON_STAIRS</a> = (1U << 8U),</div>
|
|
||||||
<div class="line"><a id="l00045" name="l00045"></a><span class="lineno"> 45</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d">ALL</a> = 0x1FU</div>
|
|
||||||
<div class="line"><a id="l00046" name="l00046"></a><span class="lineno"> 46</span>};</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00047" name="l00047"></a><span class="lineno"> 47</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00049" data-start="{" data-end="};">
|
|
||||||
<div class="line"><a id="l00049" name="l00049"></a><span class="lineno"><a class="line" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187"> 49</a></span><span class="keyword">enum class</span> <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187">BNO08xActivity</a></div>
|
|
||||||
<div class="line"><a id="l00050" name="l00050"></a><span class="lineno"> 50</span>{</div>
|
|
||||||
<div class="line"><a id="l00051" name="l00051"></a><span class="lineno"> 51</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3">UNKNOWN</a> = 0, <span class="comment">// 0 = unknown</span></div>
|
|
||||||
<div class="line"><a id="l00052" name="l00052"></a><span class="lineno"> 52</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4">IN_VEHICLE</a> = 1, <span class="comment">// 1 = in vehicle</span></div>
|
|
||||||
<div class="line"><a id="l00053" name="l00053"></a><span class="lineno"> 53</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4">ON_BICYCLE</a> = 2, <span class="comment">// 2 = on bicycle</span></div>
|
|
||||||
<div class="line"><a id="l00054" name="l00054"></a><span class="lineno"> 54</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58">ON_FOOT</a> = 3, <span class="comment">// 3 = on foot</span></div>
|
|
||||||
<div class="line"><a id="l00055" name="l00055"></a><span class="lineno"> 55</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6">STILL</a> = 4, <span class="comment">// 4 = still</span></div>
|
|
||||||
<div class="line"><a id="l00056" name="l00056"></a><span class="lineno"> 56</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c">TILTING</a> = 5, <span class="comment">// 5 = tilting</span></div>
|
|
||||||
<div class="line"><a id="l00057" name="l00057"></a><span class="lineno"> 57</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3">WALKING</a> = 6, <span class="comment">// 6 = walking</span></div>
|
|
||||||
<div class="line"><a id="l00058" name="l00058"></a><span class="lineno"> 58</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd">RUNNING</a> = 7, <span class="comment">// 7 = running</span></div>
|
|
||||||
<div class="line"><a id="l00059" name="l00059"></a><span class="lineno"> 59</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515">ON_STAIRS</a> = 8, <span class="comment">// 8 = on stairs</span></div>
|
|
||||||
<div class="line"><a id="l00060" name="l00060"></a><span class="lineno"> 60</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">UNDEFINED</a> = 9 <span class="comment">// used for unit tests</span></div>
|
|
||||||
<div class="line"><a id="l00061" name="l00061"></a><span class="lineno"> 61</span>};</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00062" name="l00062"></a><span class="lineno"> 62</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00064" data-start="{" data-end="};">
|
|
||||||
<div class="line"><a id="l00064" name="l00064"></a><span class="lineno"><a class="line" href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5"> 64</a></span><span class="keyword">enum class</span> <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5">BNO08xStability</a></div>
|
|
||||||
<div class="line"><a id="l00065" name="l00065"></a><span class="lineno"> 65</span>{</div>
|
|
||||||
<div class="line"><a id="l00066" name="l00066"></a><span class="lineno"> 66</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3">UNKNOWN</a> = 0, <span class="comment">// 0 = unknown</span></div>
|
|
||||||
<div class="line"><a id="l00067" name="l00067"></a><span class="lineno"> 67</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a">ON_TABLE</a> = 1, <span class="comment">// 1 = on table</span></div>
|
|
||||||
<div class="line"><a id="l00068" name="l00068"></a><span class="lineno"> 68</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146">STATIONARY</a> = 2, <span class="comment">// 2 = stationary</span></div>
|
|
||||||
<div class="line"><a id="l00069" name="l00069"></a><span class="lineno"> 69</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">UNDEFINED</a> = 3 <span class="comment">// used for unit tests</span></div>
|
|
||||||
<div class="line"><a id="l00070" name="l00070"></a><span class="lineno"> 70</span>};</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00071" name="l00071"></a><span class="lineno"> 71</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00073" data-start="{" data-end="};">
|
|
||||||
<div class="line"><a id="l00073" name="l00073"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html"> 73</a></span><span class="keyword">typedef</span> <span class="keyword">struct </span><a class="code hl_struct" href="structbno08x__config__t.html">bno08x_config_t</a></div>
|
|
||||||
<div class="line"><a id="l00074" name="l00074"></a><span class="lineno"> 74</span>{</div>
|
|
||||||
<div class="line"><a id="l00075" name="l00075"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html#a020d2343750bb7debc2a108ae038c9ec"> 75</a></span> spi_host_device_t <a class="code hl_variable" href="structbno08x__config__t.html#a020d2343750bb7debc2a108ae038c9ec">spi_peripheral</a>; </div>
|
|
||||||
<div class="line"><a id="l00076" name="l00076"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html#a79023fd80039e41a22b7f73ccd5fc861"> 76</a></span> gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#a79023fd80039e41a22b7f73ccd5fc861">io_mosi</a>; </div>
|
|
||||||
<div class="line"><a id="l00077" name="l00077"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html#a9468180a773892977db39cc5ed9368e3"> 77</a></span> gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#a9468180a773892977db39cc5ed9368e3">io_miso</a>; </div>
|
|
||||||
<div class="line"><a id="l00078" name="l00078"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html#a639685b91ae3198909d722316495246a"> 78</a></span> gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#a639685b91ae3198909d722316495246a">io_sclk</a>; </div>
|
|
||||||
<div class="line"><a id="l00079" name="l00079"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html#ab1b5351b63da0c172c942463d0dc2505"> 79</a></span> gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#ab1b5351b63da0c172c942463d0dc2505">io_cs</a>; </div>
|
|
||||||
<div class="line"><a id="l00080" name="l00080"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html#a3cfe965659cfbc6b0c5269bd0211975f"> 80</a></span> gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#a3cfe965659cfbc6b0c5269bd0211975f">io_int</a>; </div>
|
|
||||||
<div class="line"><a id="l00081" name="l00081"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html#a62745c761219139f66ecd173b51577fc"> 81</a></span> gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#a62745c761219139f66ecd173b51577fc">io_rst</a>; </div>
|
|
||||||
<div class="line"><a id="l00082" name="l00082"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html#a90ad7f316dc443874d19dc7e723a0ce0"> 82</a></span> gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#a90ad7f316dc443874d19dc7e723a0ce0">io_wake</a>; </div>
|
|
||||||
<div class="line"><a id="l00083" name="l00083"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html#a231614c3b20888360def2ce9db83f52a"> 83</a></span> uint32_t <a class="code hl_variable" href="structbno08x__config__t.html#a231614c3b20888360def2ce9db83f52a">sclk_speed</a>; </div>
|
|
||||||
<div class="line"><a id="l00084" name="l00084"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html#a0f629aaef6756aa80fec96b34476c627"> 84</a></span> <span class="keywordtype">bool</span> <a class="code hl_variable" href="structbno08x__config__t.html#a0f629aaef6756aa80fec96b34476c627">install_isr_service</a>; </div>
|
|
||||||
<div class="line"><a id="l00085" name="l00085"></a><span class="lineno"> 85</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00089" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00089" name="l00089"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html#a68e051212415a62e64c23678e7b40552"> 89</a></span> <a class="code hl_function" href="structbno08x__config__t.html#a68e051212415a62e64c23678e7b40552">bno08x_config_t</a>(<span class="keywordtype">bool</span> <a class="code hl_variable" href="structbno08x__config__t.html#a0f629aaef6756aa80fec96b34476c627">install_isr_service</a> = <span class="keyword">true</span>)</div>
|
|
||||||
<div class="line"><a id="l00090" name="l00090"></a><span class="lineno"> 90</span> : <a class="code hl_variable" href="structbno08x__config__t.html#a020d2343750bb7debc2a108ae038c9ec">spi_peripheral</a>((spi_host_device_t) CONFIG_ESP32_BNO08x_SPI_HOST)</div>
|
|
||||||
<div class="line"><a id="l00091" name="l00091"></a><span class="lineno"> 91</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a79023fd80039e41a22b7f73ccd5fc861">io_mosi</a>(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_DI)) <span class="comment">// default: 23</span></div>
|
|
||||||
<div class="line"><a id="l00092" name="l00092"></a><span class="lineno"> 92</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a9468180a773892977db39cc5ed9368e3">io_miso</a>(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_SDA)) <span class="comment">// default: 19</span></div>
|
|
||||||
<div class="line"><a id="l00093" name="l00093"></a><span class="lineno"> 93</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a639685b91ae3198909d722316495246a">io_sclk</a>(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_SCL)) <span class="comment">// default: 18</span></div>
|
|
||||||
<div class="line"><a id="l00094" name="l00094"></a><span class="lineno"> 94</span> , <a class="code hl_variable" href="structbno08x__config__t.html#ab1b5351b63da0c172c942463d0dc2505">io_cs</a>(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_CS)) <span class="comment">// default: 33</span></div>
|
|
||||||
<div class="line"><a id="l00095" name="l00095"></a><span class="lineno"> 95</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a3cfe965659cfbc6b0c5269bd0211975f">io_int</a>(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_HINT)) <span class="comment">// default: 26</span></div>
|
|
||||||
<div class="line"><a id="l00096" name="l00096"></a><span class="lineno"> 96</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a62745c761219139f66ecd173b51577fc">io_rst</a>(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_RST)) <span class="comment">// default: 32</span></div>
|
|
||||||
<div class="line"><a id="l00097" name="l00097"></a><span class="lineno"> 97</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a90ad7f316dc443874d19dc7e723a0ce0">io_wake</a>(static_cast<gpio_num_t>(CONFIG_ESP32_BNO08X_GPIO_WAKE)) <span class="comment">// default: -1 (unused)</span></div>
|
|
||||||
<div class="line"><a id="l00098" name="l00098"></a><span class="lineno"> 98</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a231614c3b20888360def2ce9db83f52a">sclk_speed</a>(static_cast<uint32_t>(CONFIG_ESP32_BNO08X_SCL_SPEED_HZ)) <span class="comment">// default: 2MHz</span></div>
|
|
||||||
<div class="line"><a id="l00099" name="l00099"></a><span class="lineno"> 99</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a0f629aaef6756aa80fec96b34476c627">install_isr_service</a>(<a class="code hl_variable" href="structbno08x__config__t.html#a0f629aaef6756aa80fec96b34476c627">install_isr_service</a>) <span class="comment">// default: true</span></div>
|
|
||||||
<div class="line"><a id="l00100" name="l00100"></a><span class="lineno"> 100</span> </div>
|
|
||||||
<div class="line"><a id="l00101" name="l00101"></a><span class="lineno"> 101</span> {</div>
|
|
||||||
<div class="line"><a id="l00102" name="l00102"></a><span class="lineno"> 102</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00103" name="l00103"></a><span class="lineno"> 103</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00105" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00105" name="l00105"></a><span class="lineno"><a class="line" href="structbno08x__config__t.html#a3a4ef8ef437403592278110a73cafe70"> 105</a></span> <a class="code hl_function" href="structbno08x__config__t.html#a3a4ef8ef437403592278110a73cafe70">bno08x_config_t</a>(spi_host_device_t <a class="code hl_variable" href="structbno08x__config__t.html#a020d2343750bb7debc2a108ae038c9ec">spi_peripheral</a>, gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#a79023fd80039e41a22b7f73ccd5fc861">io_mosi</a>, gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#a9468180a773892977db39cc5ed9368e3">io_miso</a>, gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#a639685b91ae3198909d722316495246a">io_sclk</a>, gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#ab1b5351b63da0c172c942463d0dc2505">io_cs</a>,</div>
|
|
||||||
<div class="line"><a id="l00106" name="l00106"></a><span class="lineno"> 106</span> gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#a3cfe965659cfbc6b0c5269bd0211975f">io_int</a>, gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#a62745c761219139f66ecd173b51577fc">io_rst</a>, gpio_num_t <a class="code hl_variable" href="structbno08x__config__t.html#a90ad7f316dc443874d19dc7e723a0ce0">io_wake</a>, uint32_t <a class="code hl_variable" href="structbno08x__config__t.html#a231614c3b20888360def2ce9db83f52a">sclk_speed</a>, <span class="keywordtype">bool</span> <a class="code hl_variable" href="structbno08x__config__t.html#a0f629aaef6756aa80fec96b34476c627">install_isr_service</a> = <span class="keyword">true</span>)</div>
|
|
||||||
<div class="line"><a id="l00107" name="l00107"></a><span class="lineno"> 107</span> : <a class="code hl_variable" href="structbno08x__config__t.html#a020d2343750bb7debc2a108ae038c9ec">spi_peripheral</a>(<a class="code hl_variable" href="structbno08x__config__t.html#a020d2343750bb7debc2a108ae038c9ec">spi_peripheral</a>)</div>
|
|
||||||
<div class="line"><a id="l00108" name="l00108"></a><span class="lineno"> 108</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a79023fd80039e41a22b7f73ccd5fc861">io_mosi</a>(<a class="code hl_variable" href="structbno08x__config__t.html#a79023fd80039e41a22b7f73ccd5fc861">io_mosi</a>)</div>
|
|
||||||
<div class="line"><a id="l00109" name="l00109"></a><span class="lineno"> 109</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a9468180a773892977db39cc5ed9368e3">io_miso</a>(<a class="code hl_variable" href="structbno08x__config__t.html#a9468180a773892977db39cc5ed9368e3">io_miso</a>)</div>
|
|
||||||
<div class="line"><a id="l00110" name="l00110"></a><span class="lineno"> 110</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a639685b91ae3198909d722316495246a">io_sclk</a>(<a class="code hl_variable" href="structbno08x__config__t.html#a639685b91ae3198909d722316495246a">io_sclk</a>)</div>
|
|
||||||
<div class="line"><a id="l00111" name="l00111"></a><span class="lineno"> 111</span> , <a class="code hl_variable" href="structbno08x__config__t.html#ab1b5351b63da0c172c942463d0dc2505">io_cs</a>(<a class="code hl_variable" href="structbno08x__config__t.html#ab1b5351b63da0c172c942463d0dc2505">io_cs</a>)</div>
|
|
||||||
<div class="line"><a id="l00112" name="l00112"></a><span class="lineno"> 112</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a3cfe965659cfbc6b0c5269bd0211975f">io_int</a>(<a class="code hl_variable" href="structbno08x__config__t.html#a3cfe965659cfbc6b0c5269bd0211975f">io_int</a>)</div>
|
|
||||||
<div class="line"><a id="l00113" name="l00113"></a><span class="lineno"> 113</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a62745c761219139f66ecd173b51577fc">io_rst</a>(<a class="code hl_variable" href="structbno08x__config__t.html#a62745c761219139f66ecd173b51577fc">io_rst</a>)</div>
|
|
||||||
<div class="line"><a id="l00114" name="l00114"></a><span class="lineno"> 114</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a90ad7f316dc443874d19dc7e723a0ce0">io_wake</a>(<a class="code hl_variable" href="structbno08x__config__t.html#a90ad7f316dc443874d19dc7e723a0ce0">io_wake</a>)</div>
|
|
||||||
<div class="line"><a id="l00115" name="l00115"></a><span class="lineno"> 115</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a231614c3b20888360def2ce9db83f52a">sclk_speed</a>(<a class="code hl_variable" href="structbno08x__config__t.html#a231614c3b20888360def2ce9db83f52a">sclk_speed</a>)</div>
|
|
||||||
<div class="line"><a id="l00116" name="l00116"></a><span class="lineno"> 116</span> , <a class="code hl_variable" href="structbno08x__config__t.html#a0f629aaef6756aa80fec96b34476c627">install_isr_service</a>(<a class="code hl_variable" href="structbno08x__config__t.html#a0f629aaef6756aa80fec96b34476c627">install_isr_service</a>)</div>
|
|
||||||
<div class="line"><a id="l00117" name="l00117"></a><span class="lineno"> 117</span> {</div>
|
|
||||||
<div class="line"><a id="l00118" name="l00118"></a><span class="lineno"> 118</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00119" name="l00119"></a><span class="lineno"><a class="line" href="_b_n_o08x__global__types_8hpp.html#a648bbdbf22731476890dd8da977d7503"> 119</a></span>} <a class="code hl_typedef" href="_b_n_o08x__global__types_8hpp.html#a648bbdbf22731476890dd8da977d7503">bno08x_config_t</a>;</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00120" name="l00120"></a><span class="lineno"> 120</span> </div>
|
|
||||||
<div class="line"><a id="l00121" name="l00121"></a><span class="lineno"><a class="line" href="_b_n_o08x__global__types_8hpp.html#aae502b3d91ddf903bba797646fd28d00"> 121</a></span><span class="keyword">typedef</span> <a class="code hl_struct" href="structbno08x__config__t.html">bno08x_config_t</a> <a class="code hl_typedef" href="_b_n_o08x__global__types_8hpp.html#aae502b3d91ddf903bba797646fd28d00">imu_config_t</a>; <span class="comment">// legacy version compatibility</span></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_a498b35f9e00b24e51f8f60b029751ab5"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5">BNO08xStability</a></div><div class="ttdeci">BNO08xStability</div><div class="ttdoc">BNO08xStability states returned from get_stability_classifier()</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:65</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146">BNO08xStability::STATIONARY</a></div><div class="ttdeci">@ STATIONARY</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a">BNO08xStability::ON_TABLE</a></div><div class="ttdeci">@ ON_TABLE</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_a648bbdbf22731476890dd8da977d7503"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#a648bbdbf22731476890dd8da977d7503">bno08x_config_t</a></div><div class="ttdeci">struct bno08x_config_t bno08x_config_t</div><div class="ttdoc">IMU configuration settings passed into constructor.</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_aae502b3d91ddf903bba797646fd28d00"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#aae502b3d91ddf903bba797646fd28d00">imu_config_t</a></div><div class="ttdeci">bno08x_config_t imu_config_t</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:121</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_ab2a2ace42f7f438d6a799dfcbc243147"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147">BNO08xResetReason</a></div><div class="ttdeci">BNO08xResetReason</div><div class="ttdoc">Reason for previous IMU reset (returned by get_reset_reason())</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:23</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a03570470bad94692ce93e32700d2e1cb">BNO08xResetReason::OTHER</a></div><div class="ttdeci">@ OTHER</div><div class="ttdoc">Previous reset was due to power other reason.</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a764caaf44e35ee682f4079bd0878fa36">BNO08xResetReason::WTD</a></div><div class="ttdeci">@ WTD</div><div class="ttdoc">Previous reset was due to watchdog timer.</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147a7b47bb0f9f8c72f84d891e8e22a1fb92">BNO08xResetReason::POR</a></div><div class="ttdeci">@ POR</div><div class="ttdoc">Previous reset was due to power on reset.</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147ac4e100317ca17eda786308c1c39eded5">BNO08xResetReason::EXT_RST</a></div><div class="ttdeci">@ EXT_RST</div><div class="ttdoc">Previous reset was due to external reset.</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#ab2a2ace42f7f438d6a799dfcbc243147acc069cf9b33eb4e7fb3696f0f42d752f">BNO08xResetReason::INT_RST</a></div><div class="ttdeci">@ INT_RST</div><div class="ttdoc">Previous reset was due to internal reset.</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_abcc5d57e21ea6ed79e792deafcb62187"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187">BNO08xActivity</a></div><div class="ttdeci">BNO08xActivity</div><div class="ttdoc">BNO08xActivity states returned from get_activity_classifier()</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:50</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_adc1b530563e35a96fc1b8911ff133e0f"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0f">BNO08xActivityEnable</a></div><div class="ttdeci">BNO08xActivityEnable</div><div class="ttdoc">BNO08xActivity Classifier enable bits passed to enable_activity_classifier()</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:35</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa43491564ebcfd38568918efbd6e840fd">BNO08xActivityEnable::RUNNING</a></div><div class="ttdeci">@ RUNNING</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa5fb1f955b45e38e31789286a1790398d">BNO08xActivityEnable::ALL</a></div><div class="ttdeci">@ ALL</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa606c114184493a665cf1f6a12fbab9d3">BNO08xActivityEnable::WALKING</a></div><div class="ttdeci">@ WALKING</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa696b031073e74bf2cb98e5ef201d4aa3">BNO08xActivityEnable::UNKNOWN</a></div><div class="ttdeci">@ UNKNOWN</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa69909b62e08f212da31719aebf67b70c">BNO08xActivityEnable::TILTING</a></div><div class="ttdeci">@ TILTING</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa7089542e0146a3499986c81e24924b58">BNO08xActivityEnable::ON_FOOT</a></div><div class="ttdeci">@ ON_FOOT</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa8b572d218013b9626d59e6a2b38f18b6">BNO08xActivityEnable::STILL</a></div><div class="ttdeci">@ STILL</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fa93d94a2f3a627533453a40e302fb35a4">BNO08xActivityEnable::ON_BICYCLE</a></div><div class="ttdeci">@ ON_BICYCLE</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fab166a3ce74dd5434e4a940dfa2af76e4">BNO08xActivityEnable::IN_VEHICLE</a></div><div class="ttdeci">@ IN_VEHICLE</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#adc1b530563e35a96fc1b8911ff133e0fabbf2a614429826a84bd76b4a47fc7515">BNO08xActivityEnable::ON_STAIRS</a></div><div class="ttdeci">@ ON_STAIRS</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_aed7bab8e55be415938e078ebe72562a0"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a></div><div class="ttdeci">BNO08xAccuracy</div><div class="ttdoc">Sensor accuracy returned during sensor calibration.</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:13</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">BNO08xAccuracy::UNDEFINED</a></div><div class="ttdeci">@ UNDEFINED</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c">BNO08xAccuracy::MED</a></div><div class="ttdeci">@ MED</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88">BNO08xAccuracy::LOW</a></div><div class="ttdeci">@ LOW</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c">BNO08xAccuracy::HIGH</a></div><div class="ttdeci">@ HIGH</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html"><div class="ttname"><a href="structbno08x__config__t.html">bno08x_config_t</a></div><div class="ttdoc">IMU configuration settings passed into constructor.</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:74</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html_a020d2343750bb7debc2a108ae038c9ec"><div class="ttname"><a href="structbno08x__config__t.html#a020d2343750bb7debc2a108ae038c9ec">bno08x_config_t::spi_peripheral</a></div><div class="ttdeci">spi_host_device_t spi_peripheral</div><div class="ttdoc">SPI peripheral to be used.</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:75</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html_a0f629aaef6756aa80fec96b34476c627"><div class="ttname"><a href="structbno08x__config__t.html#a0f629aaef6756aa80fec96b34476c627">bno08x_config_t::install_isr_service</a></div><div class="ttdeci">bool install_isr_service</div><div class="ttdoc">Indicates whether the ISR service for the HINT should be installed at IMU initialization,...</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:84</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html_a231614c3b20888360def2ce9db83f52a"><div class="ttname"><a href="structbno08x__config__t.html#a231614c3b20888360def2ce9db83f52a">bno08x_config_t::sclk_speed</a></div><div class="ttdeci">uint32_t sclk_speed</div><div class="ttdoc">Desired SPI SCLK speed in Hz (max 3MHz)</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:83</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html_a3a4ef8ef437403592278110a73cafe70"><div class="ttname"><a href="structbno08x__config__t.html#a3a4ef8ef437403592278110a73cafe70">bno08x_config_t::bno08x_config_t</a></div><div class="ttdeci">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)</div><div class="ttdoc">Overloaded IMU configuration settings constructor for custom pin settings.</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:105</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html_a3cfe965659cfbc6b0c5269bd0211975f"><div class="ttname"><a href="structbno08x__config__t.html#a3cfe965659cfbc6b0c5269bd0211975f">bno08x_config_t::io_int</a></div><div class="ttdeci">gpio_num_t io_int</div><div class="ttdoc">Chip select pin (connects to BNO08x CS pin)</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:80</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html_a62745c761219139f66ecd173b51577fc"><div class="ttname"><a href="structbno08x__config__t.html#a62745c761219139f66ecd173b51577fc">bno08x_config_t::io_rst</a></div><div class="ttdeci">gpio_num_t io_rst</div><div class="ttdoc">Host interrupt pin (connects to BNO08x INT pin)</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:81</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html_a639685b91ae3198909d722316495246a"><div class="ttname"><a href="structbno08x__config__t.html#a639685b91ae3198909d722316495246a">bno08x_config_t::io_sclk</a></div><div class="ttdeci">gpio_num_t io_sclk</div><div class="ttdoc">SCLK pin (connects to BNO08x SCL pin)</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:78</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html_a68e051212415a62e64c23678e7b40552"><div class="ttname"><a href="structbno08x__config__t.html#a68e051212415a62e64c23678e7b40552">bno08x_config_t::bno08x_config_t</a></div><div class="ttdeci">bno08x_config_t(bool install_isr_service=true)</div><div class="ttdoc">Default IMU configuration settings constructor. To modify default GPIO pins, run "idf....</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:89</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html_a79023fd80039e41a22b7f73ccd5fc861"><div class="ttname"><a href="structbno08x__config__t.html#a79023fd80039e41a22b7f73ccd5fc861">bno08x_config_t::io_mosi</a></div><div class="ttdeci">gpio_num_t io_mosi</div><div class="ttdoc">MOSI GPIO pin (connects to BNO08x DI pin)</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:76</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html_a90ad7f316dc443874d19dc7e723a0ce0"><div class="ttname"><a href="structbno08x__config__t.html#a90ad7f316dc443874d19dc7e723a0ce0">bno08x_config_t::io_wake</a></div><div class="ttdeci">gpio_num_t io_wake</div><div class="ttdoc">Reset pin (connects to BNO08x RST pin)</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:82</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html_a9468180a773892977db39cc5ed9368e3"><div class="ttname"><a href="structbno08x__config__t.html#a9468180a773892977db39cc5ed9368e3">bno08x_config_t::io_miso</a></div><div class="ttdeci">gpio_num_t io_miso</div><div class="ttdoc">MISO GPIO pin (connects to BNO08x SDA pin)</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:77</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html_ab1b5351b63da0c172c942463d0dc2505"><div class="ttname"><a href="structbno08x__config__t.html#ab1b5351b63da0c172c942463d0dc2505">bno08x_config_t::io_cs</a></div><div class="ttdeci">gpio_num_t io_cs</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:79</div></div>
|
|
||||||
</div><!-- fragment --></div><!-- contents -->
|
|
||||||
</div><!-- doc-content -->
|
|
||||||
<!-- start footer part -->
|
|
||||||
<div id="nav-path" class="navpath"><!-- id is needed for treeview function! -->
|
|
||||||
<ul>
|
|
||||||
<li class="navelem"><a class="el" href="dir_85e9385bd83516731053aadc7da3c8af.html">imu_update</a></li><li class="navelem"><a class="el" href="dir_c60d9bf80716f90f729fd65c40ec81f7.html">bno08x_update</a></li><li class="navelem"><a class="el" href="dir_fd670e5d11b8bb731501003ff6578ae1.html">components</a></li><li class="navelem"><a class="el" href="dir_a6718ce9703adf4789a693642ffedf7f.html">esp32_BNO08x</a></li><li class="navelem"><a class="el" href="dir_9667f1a5b10a5222433e41df91e1bf5d.html">include</a></li><li class="navelem"><a class="el" href="_b_n_o08x__global__types_8hpp.html">BNO08x_global_types.hpp</a></li>
|
|
||||||
<li class="footer">Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.10.0 </li>
|
|
||||||
</ul>
|
|
||||||
</div>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
||||||
|
|
@ -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 ]
|
|
||||||
];
|
|
||||||
|
|
@ -1,5 +0,0 @@
|
||||||
<map id="BNO08x_macros.hpp" name="BNO08x_macros.hpp">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="5,5,151,32"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$_b_n_o08x_8cpp.html" title=" " alt="" coords="30,80,126,107"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="81,48,81,80,75,80,75,48"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
00b34b0458274eeed68f6361cf36c1ab
|
|
||||||
|
Before Width: | Height: | Size: 1.4 KiB |
|
|
@ -1,9 +0,0 @@
|
||||||
<map id="BNO08x_macros.hpp" name="BNO08x_macros.hpp">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="105,5,251,32"/>
|
|
||||||
<area shape="rect" id="Node000002" title=" " alt="" coords="5,80,84,107"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="156,35,82,75,80,70,153,30"/>
|
|
||||||
<area shape="rect" id="Node000003" title=" " alt="" coords="108,80,248,107"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="181,33,181,64,175,64,175,33"/>
|
|
||||||
<area shape="rect" id="Node000004" title=" " alt="" coords="272,80,428,107"/>
|
|
||||||
<area shape="poly" id="edge3_Node000001_Node000004" title=" " alt="" coords="209,30,307,71,305,76,207,35"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
e68037c36c449193c84e3993bb364565
|
|
||||||
|
Before Width: | Height: | Size: 4.6 KiB |
|
|
@ -1,275 +0,0 @@
|
||||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
|
||||||
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US">
|
|
||||||
<head>
|
|
||||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
|
||||||
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
|
|
||||||
<meta name="generator" content="Doxygen 1.10.0"/>
|
|
||||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
|
||||||
<title>esp32_BNO08x: BNO08x_macros.hpp Source File</title>
|
|
||||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="jquery.js"></script>
|
|
||||||
<script type="text/javascript" src="dynsections.js"></script>
|
|
||||||
<script type="text/javascript" src="clipboard.js"></script>
|
|
||||||
<link href="navtree.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="resize.js"></script>
|
|
||||||
<script type="text/javascript" src="navtreedata.js"></script>
|
|
||||||
<script type="text/javascript" src="navtree.js"></script>
|
|
||||||
<script type="text/javascript" src="cookie.js"></script>
|
|
||||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
|
||||||
<script type="text/javascript" src="search/search.js"></script>
|
|
||||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
|
||||||
<div id="titlearea">
|
|
||||||
<table cellspacing="0" cellpadding="0">
|
|
||||||
<tbody>
|
|
||||||
<tr id="projectrow">
|
|
||||||
<td id="projectalign">
|
|
||||||
<div id="projectname">esp32_BNO08x<span id="projectnumber"> 1.2</span>
|
|
||||||
</div>
|
|
||||||
<div id="projectbrief">C++ BNO08x IMU driver component for esp-idf.</div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
</div>
|
|
||||||
<!-- end header part -->
|
|
||||||
<!-- Generated by Doxygen 1.10.0 -->
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
var searchBox = new SearchBox("searchBox", "search/",'.html');
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<script type="text/javascript" src="menudata.js"></script>
|
|
||||||
<script type="text/javascript" src="menu.js"></script>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() {
|
|
||||||
initMenu('',true,false,'search.php','Search');
|
|
||||||
$(function() { init_search(); });
|
|
||||||
});
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="main-nav"></div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() { codefold.init(0); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
</div><!-- top -->
|
|
||||||
<div id="side-nav" class="ui-resizable side-nav-resizable">
|
|
||||||
<div id="nav-tree">
|
|
||||||
<div id="nav-tree-contents">
|
|
||||||
<div id="nav-sync" class="sync"></div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div id="splitbar" style="-moz-user-select:none;"
|
|
||||||
class="ui-resizable-handle">
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function(){initNavTree('_b_n_o08x__macros_8hpp_source.html',''); initResizable(); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="doc-content">
|
|
||||||
<!-- window showing the filter options -->
|
|
||||||
<div id="MSearchSelectWindow"
|
|
||||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
|
||||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
|
||||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<!-- iframe showing the search results (closed by default) -->
|
|
||||||
<div id="MSearchResultsWindow">
|
|
||||||
<div id="MSearchResults">
|
|
||||||
<div class="SRPage">
|
|
||||||
<div id="SRIndex">
|
|
||||||
<div id="SRResults"></div>
|
|
||||||
<div class="SRStatus" id="Loading">Loading...</div>
|
|
||||||
<div class="SRStatus" id="Searching">Searching...</div>
|
|
||||||
<div class="SRStatus" id="NoMatches">No Matches</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="header">
|
|
||||||
<div class="headertitle"><div class="title">BNO08x_macros.hpp</div></div>
|
|
||||||
</div><!--header-->
|
|
||||||
<div class="contents">
|
|
||||||
<a href="_b_n_o08x__macros_8hpp.html">Go to the documentation of this file.</a><div class="fragment"><div class="line"><a id="l00001" name="l00001"></a><span class="lineno"> 1</span> </div>
|
|
||||||
<div class="line"><a id="l00005" name="l00005"></a><span class="lineno"> 5</span><span class="preprocessor">#pragma once</span></div>
|
|
||||||
<div class="line"><a id="l00006" name="l00006"></a><span class="lineno"> 6</span> </div>
|
|
||||||
<div class="line"><a id="l00007" name="l00007"></a><span class="lineno"> 7</span><span class="comment">// standard library includes</span></div>
|
|
||||||
<div class="line"><a id="l00008" name="l00008"></a><span class="lineno"> 8</span><span class="preprocessor">#include <inttypes.h></span></div>
|
|
||||||
<div class="line"><a id="l00009" name="l00009"></a><span class="lineno"> 9</span> </div>
|
|
||||||
<div class="line"><a id="l00010" name="l00010"></a><span class="lineno"> 10</span><span class="comment">// esp-idf includes</span></div>
|
|
||||||
<div class="line"><a id="l00011" name="l00011"></a><span class="lineno"> 11</span><span class="preprocessor">#include <freertos/FreeRTOS.h></span></div>
|
|
||||||
<div class="line"><a id="l00012" name="l00012"></a><span class="lineno"> 12</span><span class="preprocessor">#include <freertos/event_groups.h></span></div>
|
|
||||||
<div class="line"><a id="l00013" name="l00013"></a><span class="lineno"> 13</span> </div>
|
|
||||||
<div class="line"><a id="l00022" name="l00022"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a59dd17f0673fdd60f6a65bba104a6f80"> 22</a></span><span class="preprocessor">#define CHECK_TASKS_RUNNING(evt_grp_task_flow, running_bit) ((xEventGroupGetBits(evt_grp_task_flow) & (running_bit)) != 0)</span></div>
|
|
||||||
<div class="line"><a id="l00023" name="l00023"></a><span class="lineno"> 23</span> </div>
|
|
||||||
<div class="line"><a id="l00024" name="l00024"></a><span class="lineno"> 24</span><span class="comment">// packet parsing macros</span></div>
|
|
||||||
<div class="line"><a id="l00025" name="l00025"></a><span class="lineno"> 25</span> </div>
|
|
||||||
<div class="line"><a id="l00032" name="l00032"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#ad98f2fa811436866ff297a8288e34f40"> 32</a></span><span class="preprocessor">#define UINT16_CLR_MSB(val_16bit) ((val_16bit) & 0x00FFU)</span></div>
|
|
||||||
<div class="line"><a id="l00033" name="l00033"></a><span class="lineno"> 33</span> </div>
|
|
||||||
<div class="line"><a id="l00040" name="l00040"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#ac89a0ae0c3d3067f02e9fa275521606b"> 40</a></span><span class="preprocessor">#define UINT16_CLR_LSB(val_16bit) ((val_16bit) & 0xFF00U)</span></div>
|
|
||||||
<div class="line"><a id="l00041" name="l00041"></a><span class="lineno"> 41</span> </div>
|
|
||||||
<div class="line"><a id="l00049" name="l00049"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a7de5c0b84ba545981105e1216925d8e9"> 49</a></span><span class="preprocessor">#define UINT32_CLR_BYTE(val_32bit, byte2clear) ((val_32bit) & ~(0xFFUL << (byte2clear * 8UL)))</span></div>
|
|
||||||
<div class="line"><a id="l00050" name="l00050"></a><span class="lineno"> 50</span> </div>
|
|
||||||
<div class="line"><a id="l00058" name="l00058"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a6f459cc2cce1722c63d22a9556f06bc8"> 58</a></span><span class="preprocessor">#define UINT32_MSK_BYTE(val_32bit, byte2mask) ((val_32bit) & (0xFFUL << (byte2mask * 8UL)))</span></div>
|
|
||||||
<div class="line"><a id="l00059" name="l00059"></a><span class="lineno"> 59</span> </div>
|
|
||||||
<div class="line"><a id="l00060" name="l00060"></a><span class="lineno"> 60</span><span class="comment">// parsing universal to any packet</span></div>
|
|
||||||
<div class="line"><a id="l00061" name="l00061"></a><span class="lineno"> 61</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00068" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00068" name="l00068"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a432e15325e64ab36d5a3b30b65a71bf1"> 68</a></span><span class="preprocessor">#define PARSE_PACKET_LENGTH(packet_ptr) \</span></div>
|
|
||||||
<div class="line"><a id="l00069" name="l00069"></a><span class="lineno"> 69</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet_ptr->header[1]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet_ptr->header[0])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00070" name="l00070"></a><span class="lineno"> 70</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00077" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00077" name="l00077"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#afa3b6d75bbe499250e69043547a39208"> 77</a></span><span class="preprocessor">#define PARSE_PACKET_TIMESTAMP(packet_ptr) \</span></div>
|
|
||||||
<div class="line"><a id="l00078" name="l00078"></a><span class="lineno"> 78</span><span class="preprocessor"> (UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[4]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[3]) << 16UL, 2UL) | \</span></div>
|
|
||||||
<div class="line"><a id="l00079" name="l00079"></a><span class="lineno"> 79</span><span class="preprocessor"> UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[2]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[1]), 0UL))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00080" name="l00080"></a><span class="lineno"> 80</span> </div>
|
|
||||||
<div class="line"><a id="l00081" name="l00081"></a><span class="lineno"> 81</span><span class="comment">// product id report parsing</span></div>
|
|
||||||
<div class="line"><a id="l00082" name="l00082"></a><span class="lineno"> 82</span> </div>
|
|
||||||
<div class="line"><a id="l00089" name="l00089"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a4c1a6f80fc6ab0ab5d6f803bc175b3e1"> 89</a></span><span class="preprocessor">#define PARSE_PRODUCT_ID_REPORT_RESET_REASON(packet_ptr) UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[1]), 0UL)</span></div>
|
|
||||||
<div class="line"><a id="l00090" name="l00090"></a><span class="lineno"> 90</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00097" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00097" name="l00097"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a5e6be52a05421d50c4b3600c35868540"> 97</a></span><span class="preprocessor">#define PARSE_PRODUCT_ID_REPORT_SW_PART_NO(packet_ptr) \</span></div>
|
|
||||||
<div class="line"><a id="l00098" name="l00098"></a><span class="lineno"> 98</span><span class="preprocessor"> (UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[7]) << 24UL, 3UL) | \</span></div>
|
|
||||||
<div class="line"><a id="l00099" name="l00099"></a><span class="lineno"> 99</span><span class="preprocessor"> UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[6]) << 16UL, 2UL) | \</span></div>
|
|
||||||
<div class="line"><a id="l00100" name="l00100"></a><span class="lineno"> 100</span><span class="preprocessor"> UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[5]) << 8UL, 1UL) | \</span></div>
|
|
||||||
<div class="line"><a id="l00101" name="l00101"></a><span class="lineno"> 101</span><span class="preprocessor"> UINT32_MSK_BYTE(static_cast<uint32_t>(packet_ptr->body[4]), 0UL))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00102" name="l00102"></a><span class="lineno"> 102</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00109" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00109" name="l00109"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a24ff2498d4883f329d70fb2a6f10e04a"> 109</a></span><span class="preprocessor">#define PARSE_PRODUCT_ID_REPORT_SW_BUILD_NO(packet_ptr) \</span></div>
|
|
||||||
<div class="line"><a id="l00110" name="l00110"></a><span class="lineno"> 110</span><span class="preprocessor"> UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[11]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[10]) << 16UL, 2UL) | \</span></div>
|
|
||||||
<div class="line"><a id="l00111" name="l00111"></a><span class="lineno"> 111</span><span class="preprocessor"> UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[9]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[8]), 0UL)</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00112" name="l00112"></a><span class="lineno"> 112</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00119" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00119" name="l00119"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a23baa3c8a71f3b3021f135bef27a8ed9"> 119</a></span><span class="preprocessor">#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_PATCH(packet_ptr) \</span></div>
|
|
||||||
<div class="line"><a id="l00120" name="l00120"></a><span class="lineno"> 120</span><span class="preprocessor"> (UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[13]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[12]), 0UL))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00121" name="l00121"></a><span class="lineno"> 121</span> </div>
|
|
||||||
<div class="line"><a id="l00128" name="l00128"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a37c86278c2de384fe3b9304b8d2d3370"> 128</a></span><span class="preprocessor">#define PARSE_PRODUCT_ID_REPORT_PRODUCT_ID(packet_ptr) UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[0]), 0UL)</span></div>
|
|
||||||
<div class="line"><a id="l00129" name="l00129"></a><span class="lineno"> 129</span> </div>
|
|
||||||
<div class="line"><a id="l00136" name="l00136"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#af59b362a169fe8c11a0b679ca99383ee"> 136</a></span><span class="preprocessor">#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_MAJOR(packet_ptr) UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[2]), 0UL)</span></div>
|
|
||||||
<div class="line"><a id="l00137" name="l00137"></a><span class="lineno"> 137</span> </div>
|
|
||||||
<div class="line"><a id="l00144" name="l00144"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#ad9773ac824ab751df0e331a7c16080a1"> 144</a></span><span class="preprocessor">#define PARSE_PRODUCT_ID_REPORT_SW_VERSION_MINOR(packet_ptr) UINT32_MSK_BYTE(static_cast<uint32_t>(packet->body[3]), 0UL)</span></div>
|
|
||||||
<div class="line"><a id="l00145" name="l00145"></a><span class="lineno"> 145</span> </div>
|
|
||||||
<div class="line"><a id="l00146" name="l00146"></a><span class="lineno"> 146</span><span class="comment">// gyro report parsing</span></div>
|
|
||||||
<div class="line"><a id="l00147" name="l00147"></a><span class="lineno"> 147</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00154" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00154" name="l00154"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a1f20ab3d051d5acb254e5a5e7b4505de"> 154</a></span><span class="preprocessor">#define PARSE_GYRO_REPORT_RAW_QUAT_I(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00155" name="l00155"></a><span class="lineno"> 155</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[1]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[0])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00156" name="l00156"></a><span class="lineno"> 156</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00163" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00163" name="l00163"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#afe721365113756a8b38a5db255f9d061"> 163</a></span><span class="preprocessor">#define PARSE_GYRO_REPORT_RAW_QUAT_J(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00164" name="l00164"></a><span class="lineno"> 164</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[3]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[2])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00165" name="l00165"></a><span class="lineno"> 165</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00172" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00172" name="l00172"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a3ae7fd4e8febc54026e59e1ac544db84"> 172</a></span><span class="preprocessor">#define PARSE_GYRO_REPORT_RAW_QUAT_K(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00173" name="l00173"></a><span class="lineno"> 173</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[4])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00174" name="l00174"></a><span class="lineno"> 174</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00181" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00181" name="l00181"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a73d50f6a746370f614161ee6b9b08424"> 181</a></span><span class="preprocessor">#define PARSE_GYRO_REPORT_RAW_QUAT_REAL(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00182" name="l00182"></a><span class="lineno"> 182</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[7]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[6])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00183" name="l00183"></a><span class="lineno"> 183</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00190" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00190" name="l00190"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a7aed5272074b2ee03da81b6fb7222813"> 190</a></span><span class="preprocessor">#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_X(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00191" name="l00191"></a><span class="lineno"> 191</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[9]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[8])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00192" name="l00192"></a><span class="lineno"> 192</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00199" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00199" name="l00199"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a823d8c92faf40d07f5b0bb324f2a51bd"> 199</a></span><span class="preprocessor">#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_Y(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00200" name="l00200"></a><span class="lineno"> 200</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[11]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[10])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00201" name="l00201"></a><span class="lineno"> 201</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00208" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00208" name="l00208"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#afcc41ef70ba1860c3178072e13ccf512"> 208</a></span><span class="preprocessor">#define PARSE_GYRO_REPORT_RAW_GYRO_VEL_Z(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00209" name="l00209"></a><span class="lineno"> 209</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[13]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[12])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00210" name="l00210"></a><span class="lineno"> 210</span> </div>
|
|
||||||
<div class="line"><a id="l00211" name="l00211"></a><span class="lineno"> 211</span><span class="comment">// input report parsing</span></div>
|
|
||||||
<div class="line"><a id="l00212" name="l00212"></a><span class="lineno"> 212</span> </div>
|
|
||||||
<div class="line"><a id="l00219" name="l00219"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#ac4cad93c425c38fd5cd90d0982897611"> 219</a></span><span class="preprocessor">#define PARSE_INPUT_REPORT_STATUS_BITS(packet) (packet->body[5 + 2] & 0x03U)</span></div>
|
|
||||||
<div class="line"><a id="l00220" name="l00220"></a><span class="lineno"> 220</span> </div>
|
|
||||||
<div class="line"><a id="l00227" name="l00227"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a5be1d9a953a0657a4b8df88681b211bc"> 227</a></span><span class="preprocessor">#define PARSE_INPUT_REPORT_REPORT_ID(packet) UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5]))</span></div>
|
|
||||||
<div class="line"><a id="l00228" name="l00228"></a><span class="lineno"> 228</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00235" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00235" name="l00235"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a4664b5298e0059c173f71bb73a87d239"> 235</a></span><span class="preprocessor">#define PARSE_INPUT_REPORT_DATA_1(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00236" name="l00236"></a><span class="lineno"> 236</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 5]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 4])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00237" name="l00237"></a><span class="lineno"> 237</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00244" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00244" name="l00244"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a455a8649345748be2d5f35036052f78a"> 244</a></span><span class="preprocessor">#define PARSE_INPUT_REPORT_DATA_2(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00245" name="l00245"></a><span class="lineno"> 245</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 7]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 6])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00246" name="l00246"></a><span class="lineno"> 246</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00253" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00253" name="l00253"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a7d38fbfe154c526c822748fc812e7d52"> 253</a></span><span class="preprocessor">#define PARSE_INPUT_REPORT_DATA_3(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00254" name="l00254"></a><span class="lineno"> 254</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 9]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 8])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00255" name="l00255"></a><span class="lineno"> 255</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00262" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00262" name="l00262"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a3d6971a39ce4858314247bdbbb754b33"> 262</a></span><span class="preprocessor">#define PARSE_INPUT_REPORT_DATA_4(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00263" name="l00263"></a><span class="lineno"> 263</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 11]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 10])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00264" name="l00264"></a><span class="lineno"> 264</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00271" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00271" name="l00271"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#afd61b5f28723a3f20874097b1bd46e1a"> 271</a></span><span class="preprocessor">#define PARSE_INPUT_REPORT_DATA_5(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00272" name="l00272"></a><span class="lineno"> 272</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 13]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 12])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00273" name="l00273"></a><span class="lineno"> 273</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00280" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00280" name="l00280"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#ae66870a6ac704d1ee582f4f7bd2ba6a7"> 280</a></span><span class="preprocessor">#define PARSE_INPUT_REPORT_DATA_6(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00281" name="l00281"></a><span class="lineno"> 281</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet->body[5 + 15]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet->body[5 + 14])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00282" name="l00282"></a><span class="lineno"> 282</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00289" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00289" name="l00289"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a84602d112b6000375ad608904de5b0e3"> 289</a></span><span class="preprocessor">#define IS_ROTATION_VECTOR_REPORT(packet) \</span></div>
|
|
||||||
<div class="line"><a id="l00290" name="l00290"></a><span class="lineno"> 290</span><span class="preprocessor"> ((packet)->body[5] == SENSOR_REPORT_ID_ROTATION_VECTOR || (packet)->body[5] == SENSOR_REPORT_ID_GAME_ROTATION_VECTOR || \</span></div>
|
|
||||||
<div class="line"><a id="l00291" name="l00291"></a><span class="lineno"> 291</span><span class="preprocessor"> (packet)->body[5] == SENSOR_REPORT_ID_ARVR_STABILIZED_ROTATION_VECTOR || \</span></div>
|
|
||||||
<div class="line"><a id="l00292" name="l00292"></a><span class="lineno"> 292</span><span class="preprocessor"> (packet)->body[5] == SENSOR_REPORT_ID_ARVR_STABILIZED_GAME_ROTATION_VECTOR)</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00293" name="l00293"></a><span class="lineno"> 293</span> </div>
|
|
||||||
<div class="line"><a id="l00294" name="l00294"></a><span class="lineno"> 294</span><span class="comment">// frs read response report parsing</span></div>
|
|
||||||
<div class="line"><a id="l00295" name="l00295"></a><span class="lineno"> 295</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00302" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00302" name="l00302"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#aa23c7c4d9748ce5551fcc0e5734e0a40"> 302</a></span><span class="preprocessor">#define PARSE_FRS_READ_RESPONSE_REPORT_RECORD_ID(packet_body) \</span></div>
|
|
||||||
<div class="line"><a id="l00303" name="l00303"></a><span class="lineno"> 303</span><span class="preprocessor"> (UINT16_CLR_LSB(static_cast<uint16_t>(packet_body[13]) << 8U) | UINT16_CLR_MSB(static_cast<uint16_t>(packet_body[12])))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00304" name="l00304"></a><span class="lineno"> 304</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00311" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00311" name="l00311"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#ac70cde2db98355de4f0e56c8650556fe"> 311</a></span><span class="preprocessor">#define PARSE_FRS_READ_RESPONSE_REPORT_DATA_1(packet_body) \</span></div>
|
|
||||||
<div class="line"><a id="l00312" name="l00312"></a><span class="lineno"> 312</span><span class="preprocessor"> (UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[7]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[6]) << 16UL, 2UL) | \</span></div>
|
|
||||||
<div class="line"><a id="l00313" name="l00313"></a><span class="lineno"> 313</span><span class="preprocessor"> UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[5]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[4]), 0UL))</span></div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00314" name="l00314"></a><span class="lineno"> 314</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00321" data-start="" data-end="">
|
|
||||||
<div class="line"><a id="l00321" name="l00321"></a><span class="lineno"><a class="line" href="_b_n_o08x__macros_8hpp.html#a2fcd254e9531069d6982795f575cb17a"> 321</a></span><span class="preprocessor">#define PARSE_FRS_READ_RESPONSE_REPORT_DATA_2(packet_body) \</span></div>
|
|
||||||
<div class="line"><a id="l00322" name="l00322"></a><span class="lineno"> 322</span><span class="preprocessor"> (UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[11]) << 24UL, 3UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[10]) << 16UL, 2UL) | \</span></div>
|
|
||||||
<div class="line"><a id="l00323" name="l00323"></a><span class="lineno"> 323</span><span class="preprocessor"> UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[9]) << 8UL, 1UL) | UINT32_MSK_BYTE(static_cast<uint32_t>(packet_body[8]), 0UL))</span></div>
|
|
||||||
</div>
|
|
||||||
</div><!-- fragment --></div><!-- contents -->
|
|
||||||
</div><!-- doc-content -->
|
|
||||||
<!-- start footer part -->
|
|
||||||
<div id="nav-path" class="navpath"><!-- id is needed for treeview function! -->
|
|
||||||
<ul>
|
|
||||||
<li class="navelem"><a class="el" href="dir_85e9385bd83516731053aadc7da3c8af.html">imu_update</a></li><li class="navelem"><a class="el" href="dir_c60d9bf80716f90f729fd65c40ec81f7.html">bno08x_update</a></li><li class="navelem"><a class="el" href="dir_fd670e5d11b8bb731501003ff6578ae1.html">components</a></li><li class="navelem"><a class="el" href="dir_a6718ce9703adf4789a693642ffedf7f.html">esp32_BNO08x</a></li><li class="navelem"><a class="el" href="dir_9667f1a5b10a5222433e41df91e1bf5d.html">include</a></li><li class="navelem"><a class="el" href="_b_n_o08x__macros_8hpp.html">BNO08x_macros.hpp</a></li>
|
|
||||||
<li class="footer">Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.10.0 </li>
|
|
||||||
</ul>
|
|
||||||
</div>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
||||||
|
|
@ -1,193 +0,0 @@
|
||||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
|
||||||
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US">
|
|
||||||
<head>
|
|
||||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
|
||||||
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
|
|
||||||
<meta name="generator" content="Doxygen 1.10.0"/>
|
|
||||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
|
||||||
<title>esp32_BNO08x: BNO08xTestHelper.hpp File Reference</title>
|
|
||||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="jquery.js"></script>
|
|
||||||
<script type="text/javascript" src="dynsections.js"></script>
|
|
||||||
<script type="text/javascript" src="clipboard.js"></script>
|
|
||||||
<link href="navtree.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="resize.js"></script>
|
|
||||||
<script type="text/javascript" src="navtreedata.js"></script>
|
|
||||||
<script type="text/javascript" src="navtree.js"></script>
|
|
||||||
<script type="text/javascript" src="cookie.js"></script>
|
|
||||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
|
||||||
<script type="text/javascript" src="search/search.js"></script>
|
|
||||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
|
||||||
<div id="titlearea">
|
|
||||||
<table cellspacing="0" cellpadding="0">
|
|
||||||
<tbody>
|
|
||||||
<tr id="projectrow">
|
|
||||||
<td id="projectalign">
|
|
||||||
<div id="projectname">esp32_BNO08x<span id="projectnumber"> 1.2</span>
|
|
||||||
</div>
|
|
||||||
<div id="projectbrief">C++ BNO08x IMU driver component for esp-idf.</div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
</div>
|
|
||||||
<!-- end header part -->
|
|
||||||
<!-- Generated by Doxygen 1.10.0 -->
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
var searchBox = new SearchBox("searchBox", "search/",'.html');
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<script type="text/javascript" src="menudata.js"></script>
|
|
||||||
<script type="text/javascript" src="menu.js"></script>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() {
|
|
||||||
initMenu('',true,false,'search.php','Search');
|
|
||||||
$(function() { init_search(); });
|
|
||||||
});
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="main-nav"></div>
|
|
||||||
</div><!-- top -->
|
|
||||||
<div id="side-nav" class="ui-resizable side-nav-resizable">
|
|
||||||
<div id="nav-tree">
|
|
||||||
<div id="nav-tree-contents">
|
|
||||||
<div id="nav-sync" class="sync"></div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div id="splitbar" style="-moz-user-select:none;"
|
|
||||||
class="ui-resizable-handle">
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function(){initNavTree('_b_n_o08x_test_helper_8hpp.html',''); initResizable(); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="doc-content">
|
|
||||||
<!-- window showing the filter options -->
|
|
||||||
<div id="MSearchSelectWindow"
|
|
||||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
|
||||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
|
||||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<!-- iframe showing the search results (closed by default) -->
|
|
||||||
<div id="MSearchResultsWindow">
|
|
||||||
<div id="MSearchResults">
|
|
||||||
<div class="SRPage">
|
|
||||||
<div id="SRIndex">
|
|
||||||
<div id="SRResults"></div>
|
|
||||||
<div class="SRStatus" id="Loading">Loading...</div>
|
|
||||||
<div class="SRStatus" id="Searching">Searching...</div>
|
|
||||||
<div class="SRStatus" id="NoMatches">No Matches</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="header">
|
|
||||||
<div class="summary">
|
|
||||||
<a href="#nested-classes">Classes</a> </div>
|
|
||||||
<div class="headertitle"><div class="title">BNO08xTestHelper.hpp File Reference</div></div>
|
|
||||||
</div><!--header-->
|
|
||||||
<div class="contents">
|
|
||||||
<div class="textblock"><code>#include "stdio.h"</code><br />
|
|
||||||
<code>#include "<a class="el" href="_b_n_o08x_8hpp_source.html">BNO08x.hpp</a>"</code><br />
|
|
||||||
</div><div class="textblock"><div class="dynheader">
|
|
||||||
Include dependency graph for BNO08xTestHelper.hpp:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_b_n_o08x_test_helper_8hpp__incl.png" border="0" usemap="#a_b_n_o08x_test_helper_8hpp" alt=""/></div>
|
|
||||||
<map name="a_b_n_o08x_test_helper_8hpp" id="a_b_n_o08x_test_helper_8hpp">
|
|
||||||
<area shape="rect" title=" " alt="" coords="289,5,446,32"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,155,66,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="340,35,79,150,77,146,338,30"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_8hpp.html" title=" " alt="" coords="652,80,747,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="426,30,637,76,636,81,425,35"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,99,410,115,249,132,81,157,80,152,248,127,410,109,651,94"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="90,155,168,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="651,101,451,120,320,136,184,157,183,152,319,131,451,115,651,96"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="192,155,253,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,102,486,121,379,137,268,157,267,152,378,132,485,116,651,96"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="277,155,338,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,104,521,124,354,157,352,151,520,119,651,98"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="361,155,438,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,109,454,156,452,151,651,104"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="461,155,517,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="664,110,532,155,530,150,662,105"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="541,155,618,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="680,109,615,149,612,144,677,105"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="643,155,756,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="702,107,702,139,697,139,697,107"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="780,155,870,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="723,105,791,144,789,149,720,110"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="893,155,1034,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="746,105,904,148,902,153,745,110"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1058,155,1162,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,100,1043,151,1042,157,747,105"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1186,155,1341,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,98,1171,152,1170,157,747,103"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1365,155,1479,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,95,1001,115,1172,131,1350,152,1349,157,1172,136,1000,120,747,100"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1504,155,1626,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,94,1055,112,1268,129,1488,152,1488,157,1267,135,1055,118,747,100"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1650,155,1754,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,93,1112,108,1369,125,1635,152,1634,157,1368,130,1112,113,747,98"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x__global__types_8hpp.html" title=" " alt="" coords="1779,155,1954,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,94,1161,112,1456,129,1763,152,1763,157,1456,134,1160,117,747,99"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1681,229,1771,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1843,184,1766,224,1763,219,1841,180"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1796,229,1936,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1869,182,1869,214,1864,214,1864,182"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1961,229,2091,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1895,179,1986,220,1983,225,1893,184"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
</div><div class="textblock"><div class="dynheader">
|
|
||||||
This graph shows which files directly or indirectly include this file:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_b_n_o08x_test_helper_8hpp__dep__incl.png" border="0" usemap="#a_b_n_o08x_test_helper_8hppdep" alt=""/></div>
|
|
||||||
<map name="a_b_n_o08x_test_helper_8hppdep" id="a_b_n_o08x_test_helper_8hppdep">
|
|
||||||
<area shape="rect" title=" " alt="" coords="318,5,475,32"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_test_suite_8hpp.html" title=" " alt="" coords="5,80,156,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="327,39,136,82,135,77,326,33"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html" title=" " alt="" coords="180,80,309,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="358,41,272,82,270,77,355,37"/>
|
|
||||||
<area shape="rect" href="_init_deinit_tests_8cpp.html" title=" " alt="" coords="332,80,461,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="399,48,399,80,394,80,394,48"/>
|
|
||||||
<area shape="rect" href="_multi_report_tests_8cpp.html" title=" " alt="" coords="484,80,629,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="439,36,530,77,527,82,437,41"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html" title=" " alt="" coords="652,80,805,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="470,33,671,77,670,82,469,38"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<p><a href="_b_n_o08x_test_helper_8hpp_source.html">Go to the source code of this file.</a></p>
|
|
||||||
<table class="memberdecls">
|
|
||||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a id="nested-classes" name="nested-classes"></a>
|
|
||||||
Classes</h2></td></tr>
|
|
||||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">class  </td><td class="memItemRight" valign="bottom"><a class="el" href="class_b_n_o08x_test_helper.html">BNO08xTestHelper</a></td></tr>
|
|
||||||
<tr class="memdesc:"><td class="mdescLeft"> </td><td class="mdescRight"><a class="el" href="class_b_n_o08x.html" title="BNO08x IMU driver class.">BNO08x</a> unit test helper class. <a href="class_b_n_o08x_test_helper.html#details">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">struct  </td><td class="memItemRight" valign="bottom"><a class="el" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">BNO08xTestHelper::imu_report_data_t</a></td></tr>
|
|
||||||
<tr class="memdesc:"><td class="mdescLeft"> </td><td class="mdescRight">IMU configuration settings passed into constructor. <a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#details">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
</table>
|
|
||||||
<a name="details" id="details"></a><h2 class="groupheader">Detailed Description</h2>
|
|
||||||
<div class="textblock"><dl class="section author"><dt>Author</dt><dd>Myles Parfeniuk </dd></dl>
|
|
||||||
</div></div><!-- contents -->
|
|
||||||
</div><!-- doc-content -->
|
|
||||||
<!-- start footer part -->
|
|
||||||
<div id="nav-path" class="navpath"><!-- id is needed for treeview function! -->
|
|
||||||
<ul>
|
|
||||||
<li class="navelem"><a class="el" href="dir_85e9385bd83516731053aadc7da3c8af.html">imu_update</a></li><li class="navelem"><a class="el" href="dir_c60d9bf80716f90f729fd65c40ec81f7.html">bno08x_update</a></li><li class="navelem"><a class="el" href="dir_fd670e5d11b8bb731501003ff6578ae1.html">components</a></li><li class="navelem"><a class="el" href="dir_a6718ce9703adf4789a693642ffedf7f.html">esp32_BNO08x</a></li><li class="navelem"><a class="el" href="dir_9667f1a5b10a5222433e41df91e1bf5d.html">include</a></li><li class="navelem"><a class="el" href="_b_n_o08x_test_helper_8hpp.html">BNO08xTestHelper.hpp</a></li>
|
|
||||||
<li class="footer">Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.10.0 </li>
|
|
||||||
</ul>
|
|
||||||
</div>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
||||||
|
|
@ -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" ]
|
|
||||||
];
|
|
||||||
|
|
@ -1,13 +0,0 @@
|
||||||
<map id="BNO08xTestHelper.hpp" name="BNO08xTestHelper.hpp">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="318,5,475,32"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$_b_n_o08x_test_suite_8hpp.html" title=" " alt="" coords="5,80,156,107"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="327,39,136,82,135,77,326,33"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$_callback_tests_8cpp.html" title=" " alt="" coords="180,80,309,107"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="358,41,272,82,270,77,355,37"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$_init_deinit_tests_8cpp.html" title=" " alt="" coords="332,80,461,107"/>
|
|
||||||
<area shape="poly" id="edge3_Node000001_Node000004" title=" " alt="" coords="399,48,399,80,394,80,394,48"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$_multi_report_tests_8cpp.html" title=" " alt="" coords="484,80,629,107"/>
|
|
||||||
<area shape="poly" id="edge4_Node000001_Node000005" title=" " alt="" coords="439,36,530,77,527,82,437,41"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$_single_report_tests_8cpp.html" title=" " alt="" coords="652,80,805,107"/>
|
|
||||||
<area shape="poly" id="edge5_Node000001_Node000006" title=" " alt="" coords="470,33,671,77,670,82,469,38"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
7c045f55b15b7efe09be4db57983753a
|
|
||||||
|
Before Width: | Height: | Size: 7.2 KiB |
|
|
@ -1,44 +0,0 @@
|
||||||
<map id="BNO08xTestHelper.hpp" name="BNO08xTestHelper.hpp">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="289,5,446,32"/>
|
|
||||||
<area shape="rect" id="Node000002" title=" " alt="" coords="5,155,66,181"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="340,35,79,150,77,146,338,30"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$_b_n_o08x_8hpp.html" title=" " alt="" coords="652,80,747,107"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="426,30,637,76,636,81,425,35"/>
|
|
||||||
<area shape="poly" id="edge5_Node000003_Node000002" title=" " alt="" coords="652,99,410,115,249,132,81,157,80,152,248,127,410,109,651,94"/>
|
|
||||||
<area shape="rect" id="Node000004" title=" " alt="" coords="90,155,168,181"/>
|
|
||||||
<area shape="poly" id="edge3_Node000003_Node000004" title=" " alt="" coords="651,101,451,120,320,136,184,157,183,152,319,131,451,115,651,96"/>
|
|
||||||
<area shape="rect" id="Node000005" title=" " alt="" coords="192,155,253,181"/>
|
|
||||||
<area shape="poly" id="edge4_Node000003_Node000005" title=" " alt="" coords="652,102,486,121,379,137,268,157,267,152,378,132,485,116,651,96"/>
|
|
||||||
<area shape="rect" id="Node000006" title=" " alt="" coords="277,155,338,181"/>
|
|
||||||
<area shape="poly" id="edge6_Node000003_Node000006" title=" " alt="" coords="652,104,521,124,354,157,352,151,520,119,651,98"/>
|
|
||||||
<area shape="rect" id="Node000007" title=" " alt="" coords="361,155,438,181"/>
|
|
||||||
<area shape="poly" id="edge7_Node000003_Node000007" title=" " alt="" coords="652,109,454,156,452,151,651,104"/>
|
|
||||||
<area shape="rect" id="Node000008" title=" " alt="" coords="461,155,517,181"/>
|
|
||||||
<area shape="poly" id="edge8_Node000003_Node000008" title=" " alt="" coords="664,110,532,155,530,150,662,105"/>
|
|
||||||
<area shape="rect" id="Node000009" title=" " alt="" coords="541,155,618,181"/>
|
|
||||||
<area shape="poly" id="edge9_Node000003_Node000009" title=" " alt="" coords="680,109,615,149,612,144,677,105"/>
|
|
||||||
<area shape="rect" id="Node000010" title=" " alt="" coords="643,155,756,181"/>
|
|
||||||
<area shape="poly" id="edge10_Node000003_Node000010" title=" " alt="" coords="702,107,702,139,697,139,697,107"/>
|
|
||||||
<area shape="rect" id="Node000011" title=" " alt="" coords="780,155,870,181"/>
|
|
||||||
<area shape="poly" id="edge11_Node000003_Node000011" title=" " alt="" coords="723,105,791,144,789,149,720,110"/>
|
|
||||||
<area shape="rect" id="Node000012" title=" " alt="" coords="893,155,1034,181"/>
|
|
||||||
<area shape="poly" id="edge12_Node000003_Node000012" title=" " alt="" coords="746,105,904,148,902,153,745,110"/>
|
|
||||||
<area shape="rect" id="Node000013" title=" " alt="" coords="1058,155,1162,181"/>
|
|
||||||
<area shape="poly" id="edge13_Node000003_Node000013" title=" " alt="" coords="748,100,1043,151,1042,157,747,105"/>
|
|
||||||
<area shape="rect" id="Node000014" title=" " alt="" coords="1186,155,1341,181"/>
|
|
||||||
<area shape="poly" id="edge14_Node000003_Node000014" title=" " alt="" coords="748,98,1171,152,1170,157,747,103"/>
|
|
||||||
<area shape="rect" id="Node000015" title=" " alt="" coords="1365,155,1479,181"/>
|
|
||||||
<area shape="poly" id="edge15_Node000003_Node000015" title=" " alt="" coords="748,95,1001,115,1172,131,1350,152,1349,157,1172,136,1000,120,747,100"/>
|
|
||||||
<area shape="rect" id="Node000016" title=" " alt="" coords="1504,155,1626,181"/>
|
|
||||||
<area shape="poly" id="edge16_Node000003_Node000016" title=" " alt="" coords="748,94,1055,112,1268,129,1488,152,1488,157,1267,135,1055,118,747,100"/>
|
|
||||||
<area shape="rect" id="Node000017" title=" " alt="" coords="1650,155,1754,181"/>
|
|
||||||
<area shape="poly" id="edge17_Node000003_Node000017" title=" " alt="" coords="748,93,1112,108,1369,125,1635,152,1634,157,1368,130,1112,113,747,98"/>
|
|
||||||
<area shape="rect" id="Node000018" href="$_b_n_o08x__global__types_8hpp.html" title=" " alt="" coords="1779,155,1954,181"/>
|
|
||||||
<area shape="poly" id="edge18_Node000003_Node000018" title=" " alt="" coords="748,94,1161,112,1456,129,1763,152,1763,157,1456,134,1160,117,747,99"/>
|
|
||||||
<area shape="rect" id="Node000019" title=" " alt="" coords="1681,229,1771,256"/>
|
|
||||||
<area shape="poly" id="edge19_Node000018_Node000019" title=" " alt="" coords="1843,184,1766,224,1763,219,1841,180"/>
|
|
||||||
<area shape="rect" id="Node000020" title=" " alt="" coords="1796,229,1936,256"/>
|
|
||||||
<area shape="poly" id="edge20_Node000018_Node000020" title=" " alt="" coords="1869,182,1869,214,1864,214,1864,182"/>
|
|
||||||
<area shape="rect" id="Node000021" title=" " alt="" coords="1961,229,2091,256"/>
|
|
||||||
<area shape="poly" id="edge21_Node000018_Node000021" title=" " alt="" coords="1895,179,1986,220,1983,225,1893,184"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
143e4d04830ff9fbc07d6d1d4e2b0003
|
|
||||||
|
Before Width: | Height: | Size: 47 KiB |
|
|
@ -1,844 +0,0 @@
|
||||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
|
||||||
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US">
|
|
||||||
<head>
|
|
||||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
|
||||||
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
|
|
||||||
<meta name="generator" content="Doxygen 1.10.0"/>
|
|
||||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
|
||||||
<title>esp32_BNO08x: BNO08xTestHelper.hpp Source File</title>
|
|
||||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="jquery.js"></script>
|
|
||||||
<script type="text/javascript" src="dynsections.js"></script>
|
|
||||||
<script type="text/javascript" src="clipboard.js"></script>
|
|
||||||
<link href="navtree.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="resize.js"></script>
|
|
||||||
<script type="text/javascript" src="navtreedata.js"></script>
|
|
||||||
<script type="text/javascript" src="navtree.js"></script>
|
|
||||||
<script type="text/javascript" src="cookie.js"></script>
|
|
||||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
|
||||||
<script type="text/javascript" src="search/search.js"></script>
|
|
||||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
|
||||||
<div id="titlearea">
|
|
||||||
<table cellspacing="0" cellpadding="0">
|
|
||||||
<tbody>
|
|
||||||
<tr id="projectrow">
|
|
||||||
<td id="projectalign">
|
|
||||||
<div id="projectname">esp32_BNO08x<span id="projectnumber"> 1.2</span>
|
|
||||||
</div>
|
|
||||||
<div id="projectbrief">C++ BNO08x IMU driver component for esp-idf.</div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
</div>
|
|
||||||
<!-- end header part -->
|
|
||||||
<!-- Generated by Doxygen 1.10.0 -->
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
var searchBox = new SearchBox("searchBox", "search/",'.html');
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<script type="text/javascript" src="menudata.js"></script>
|
|
||||||
<script type="text/javascript" src="menu.js"></script>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() {
|
|
||||||
initMenu('',true,false,'search.php','Search');
|
|
||||||
$(function() { init_search(); });
|
|
||||||
});
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="main-nav"></div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() { codefold.init(0); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
</div><!-- top -->
|
|
||||||
<div id="side-nav" class="ui-resizable side-nav-resizable">
|
|
||||||
<div id="nav-tree">
|
|
||||||
<div id="nav-tree-contents">
|
|
||||||
<div id="nav-sync" class="sync"></div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div id="splitbar" style="-moz-user-select:none;"
|
|
||||||
class="ui-resizable-handle">
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function(){initNavTree('_b_n_o08x_test_helper_8hpp_source.html',''); initResizable(); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="doc-content">
|
|
||||||
<!-- window showing the filter options -->
|
|
||||||
<div id="MSearchSelectWindow"
|
|
||||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
|
||||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
|
||||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<!-- iframe showing the search results (closed by default) -->
|
|
||||||
<div id="MSearchResultsWindow">
|
|
||||||
<div id="MSearchResults">
|
|
||||||
<div class="SRPage">
|
|
||||||
<div id="SRIndex">
|
|
||||||
<div id="SRResults"></div>
|
|
||||||
<div class="SRStatus" id="Loading">Loading...</div>
|
|
||||||
<div class="SRStatus" id="Searching">Searching...</div>
|
|
||||||
<div class="SRStatus" id="NoMatches">No Matches</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="header">
|
|
||||||
<div class="headertitle"><div class="title">BNO08xTestHelper.hpp</div></div>
|
|
||||||
</div><!--header-->
|
|
||||||
<div class="contents">
|
|
||||||
<a href="_b_n_o08x_test_helper_8hpp.html">Go to the documentation of this file.</a><div class="fragment"><div class="line"><a id="l00001" name="l00001"></a><span class="lineno"> 1</span> </div>
|
|
||||||
<div class="line"><a id="l00005" name="l00005"></a><span class="lineno"> 5</span><span class="preprocessor">#pragma once</span></div>
|
|
||||||
<div class="line"><a id="l00006" name="l00006"></a><span class="lineno"> 6</span> </div>
|
|
||||||
<div class="line"><a id="l00007" name="l00007"></a><span class="lineno"> 7</span><span class="preprocessor">#include "stdio.h"</span></div>
|
|
||||||
<div class="line"><a id="l00008" name="l00008"></a><span class="lineno"> 8</span><span class="preprocessor">#include "<a class="code" href="_b_n_o08x_8hpp.html">BNO08x.hpp</a>"</span></div>
|
|
||||||
<div class="line"><a id="l00009" name="l00009"></a><span class="lineno"> 9</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00015" data-start="{" data-end="};">
|
|
||||||
<div class="line"><a id="l00015" name="l00015"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html"> 15</a></span><span class="keyword">class </span><a class="code hl_class" href="class_b_n_o08x_test_helper.html">BNO08xTestHelper</a></div>
|
|
||||||
<div class="line"><a id="l00016" name="l00016"></a><span class="lineno"> 16</span>{</div>
|
|
||||||
<div class="line"><a id="l00017" name="l00017"></a><span class="lineno"> 17</span> <span class="keyword">private</span>:</div>
|
|
||||||
<div class="line"><a id="l00018" name="l00018"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243"> 18</a></span> <span class="keyword">inline</span> <span class="keyword">static</span> <a class="code hl_class" href="class_b_n_o08x.html">BNO08x</a>* <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a> = <span class="keyword">nullptr</span>;</div>
|
|
||||||
<div class="line"><a id="l00019" name="l00019"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a008b268f705b9d2925230cb8193c9f28"> 19</a></span> <span class="keyword">inline</span> <span class="keyword">static</span> <a class="code hl_struct" href="structbno08x__config__t.html">bno08x_config_t</a> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a008b268f705b9d2925230cb8193c9f28">imu_cfg</a>;</div>
|
|
||||||
<div class="line"><a id="l00020" name="l00020"></a><span class="lineno"> 20</span> </div>
|
|
||||||
<div class="line"><a id="l00021" name="l00021"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#aa09d388a5da3a925ac25125b9c5c3a90"> 21</a></span> <span class="keyword">static</span> <span class="keyword">const</span> <span class="keyword">constexpr</span> <span class="keywordtype">char</span>* <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#aa09d388a5da3a925ac25125b9c5c3a90">TAG</a> = <span class="stringliteral">"BNO08xTestHelper"</span>;</div>
|
|
||||||
<div class="line"><a id="l00022" name="l00022"></a><span class="lineno"> 22</span> </div>
|
|
||||||
<div class="line"><a id="l00023" name="l00023"></a><span class="lineno"> 23</span> <span class="keyword">public</span>:</div>
|
|
||||||
<div class="foldopen" id="foldopen00025" data-start="{" data-end="};">
|
|
||||||
<div class="line"><a id="l00025" name="l00025"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html"> 25</a></span> <span class="keyword">typedef</span> <span class="keyword">struct </span><a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a></div>
|
|
||||||
<div class="line"><a id="l00026" name="l00026"></a><span class="lineno"> 26</span> {</div>
|
|
||||||
<div class="line"><a id="l00027" name="l00027"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae5e8705ad014ed3f70e5de527cb2cb66"> 27</a></span> uint32_t <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae5e8705ad014ed3f70e5de527cb2cb66">time_stamp</a>;</div>
|
|
||||||
<div class="line"><a id="l00028" name="l00028"></a><span class="lineno"> 28</span> </div>
|
|
||||||
<div class="line"><a id="l00029" name="l00029"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8d2c3cd33943cb1b4fd0e800f822607e"> 29</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8d2c3cd33943cb1b4fd0e800f822607e">quat_I</a>;</div>
|
|
||||||
<div class="line"><a id="l00030" name="l00030"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a20a09d197d5128aae64b7449df576c27"> 30</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a20a09d197d5128aae64b7449df576c27">quat_J</a>;</div>
|
|
||||||
<div class="line"><a id="l00031" name="l00031"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3c74d4c93fc4390f52b75e6ff2bea95b"> 31</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3c74d4c93fc4390f52b75e6ff2bea95b">quat_K</a>;</div>
|
|
||||||
<div class="line"><a id="l00032" name="l00032"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a80525c4943154f825a62539b10337976"> 32</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a80525c4943154f825a62539b10337976">quat_real</a>;</div>
|
|
||||||
<div class="line"><a id="l00033" name="l00033"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae0a8fef0227dd4304d08466c43d901a5"> 33</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae0a8fef0227dd4304d08466c43d901a5">quat_radian_accuracy</a>;</div>
|
|
||||||
<div class="line"><a id="l00034" name="l00034"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#aac84ad10b65403ae1ee21dab5cdc77db"> 34</a></span> <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#aac84ad10b65403ae1ee21dab5cdc77db">quat_accuracy</a>;</div>
|
|
||||||
<div class="line"><a id="l00035" name="l00035"></a><span class="lineno"> 35</span> </div>
|
|
||||||
<div class="line"><a id="l00036" name="l00036"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a077a94b4de0b5c280d69611325208cf7"> 36</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a077a94b4de0b5c280d69611325208cf7">integrated_gyro_vel_x</a>;</div>
|
|
||||||
<div class="line"><a id="l00037" name="l00037"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af4b75b320bc390c90656905711f1c791"> 37</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af4b75b320bc390c90656905711f1c791">integrated_gyro_vel_y</a>;</div>
|
|
||||||
<div class="line"><a id="l00038" name="l00038"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a1aa67da9c3c6449dfce361a528c418d3"> 38</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a1aa67da9c3c6449dfce361a528c418d3">integrated_gyro_vel_z</a>;</div>
|
|
||||||
<div class="line"><a id="l00039" name="l00039"></a><span class="lineno"> 39</span> </div>
|
|
||||||
<div class="line"><a id="l00040" name="l00040"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5c01b349cc9e4e45c78c576882d633fd"> 40</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5c01b349cc9e4e45c78c576882d633fd">accel_x</a>;</div>
|
|
||||||
<div class="line"><a id="l00041" name="l00041"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e594d0a1e86fb575f72c6f330c8983c"> 41</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e594d0a1e86fb575f72c6f330c8983c">accel_y</a>;</div>
|
|
||||||
<div class="line"><a id="l00042" name="l00042"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af134cb789c29120033d81916e0c100d4"> 42</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af134cb789c29120033d81916e0c100d4">accel_z</a>;</div>
|
|
||||||
<div class="line"><a id="l00043" name="l00043"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac5d393de0f15176ba81bc63a80b49ca3"> 43</a></span> <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac5d393de0f15176ba81bc63a80b49ca3">accel_accuracy</a>;</div>
|
|
||||||
<div class="line"><a id="l00044" name="l00044"></a><span class="lineno"> 44</span> </div>
|
|
||||||
<div class="line"><a id="l00045" name="l00045"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3a62ed280657cd409d723e64f0c313b5"> 45</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3a62ed280657cd409d723e64f0c313b5">lin_accel_x</a>;</div>
|
|
||||||
<div class="line"><a id="l00046" name="l00046"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a553942aa784c35c833543ecc9a05f606"> 46</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a553942aa784c35c833543ecc9a05f606">lin_accel_y</a>;</div>
|
|
||||||
<div class="line"><a id="l00047" name="l00047"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5bf43fc0daf3a86954924e066cad3a9b"> 47</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5bf43fc0daf3a86954924e066cad3a9b">lin_accel_z</a>;</div>
|
|
||||||
<div class="line"><a id="l00048" name="l00048"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a48a249994c27f59ca4167b56bdda311a"> 48</a></span> <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a48a249994c27f59ca4167b56bdda311a">lin_accel_accuracy</a>;</div>
|
|
||||||
<div class="line"><a id="l00049" name="l00049"></a><span class="lineno"> 49</span> </div>
|
|
||||||
<div class="line"><a id="l00050" name="l00050"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ad2c17ea111250ebc1a4a763dae3c072a"> 50</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ad2c17ea111250ebc1a4a763dae3c072a">grav_x</a>;</div>
|
|
||||||
<div class="line"><a id="l00051" name="l00051"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a19fc4af8a26c10a027cbd859d67dba4a"> 51</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a19fc4af8a26c10a027cbd859d67dba4a">grav_y</a>;</div>
|
|
||||||
<div class="line"><a id="l00052" name="l00052"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af1887bdfef4fc2c683fe2134cb5cfb50"> 52</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af1887bdfef4fc2c683fe2134cb5cfb50">grav_z</a>;</div>
|
|
||||||
<div class="line"><a id="l00053" name="l00053"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a735d099f3dd0ead4b8d986fd139af43d"> 53</a></span> <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a735d099f3dd0ead4b8d986fd139af43d">grav_accuracy</a>;</div>
|
|
||||||
<div class="line"><a id="l00054" name="l00054"></a><span class="lineno"> 54</span> </div>
|
|
||||||
<div class="line"><a id="l00055" name="l00055"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a89b427579a281440ab94a340c0ec8443"> 55</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a89b427579a281440ab94a340c0ec8443">calib_gyro_vel_x</a>;</div>
|
|
||||||
<div class="line"><a id="l00056" name="l00056"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af9e11fd749123f5723b2e281c8d2fd16"> 56</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af9e11fd749123f5723b2e281c8d2fd16">calib_gyro_vel_y</a>;</div>
|
|
||||||
<div class="line"><a id="l00057" name="l00057"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a769ddae74a6c89a2d319c28f95ed6479"> 57</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a769ddae74a6c89a2d319c28f95ed6479">calib_gyro_vel_z</a>;</div>
|
|
||||||
<div class="line"><a id="l00058" name="l00058"></a><span class="lineno"> 58</span> </div>
|
|
||||||
<div class="line"><a id="l00059" name="l00059"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a292b1c36fed6a9c9742edf730299c4f4"> 59</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a292b1c36fed6a9c9742edf730299c4f4">uncalib_gyro_vel_x</a>;</div>
|
|
||||||
<div class="line"><a id="l00060" name="l00060"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#adfd6bf2e2264cf25bd02814446600ab4"> 60</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#adfd6bf2e2264cf25bd02814446600ab4">uncalib_gyro_vel_y</a>;</div>
|
|
||||||
<div class="line"><a id="l00061" name="l00061"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ab39fd6f409288bb35fb1542ff4b9cbe4"> 61</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ab39fd6f409288bb35fb1542ff4b9cbe4">uncalib_gyro_vel_z</a>;</div>
|
|
||||||
<div class="line"><a id="l00062" name="l00062"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac70a65027c3e740eca2b1f172b7cefa3"> 62</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac70a65027c3e740eca2b1f172b7cefa3">uncalib_gyro_drift_x</a>;</div>
|
|
||||||
<div class="line"><a id="l00063" name="l00063"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a29d5ae3e0ed3463cb9297f9cdc0e8472"> 63</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a29d5ae3e0ed3463cb9297f9cdc0e8472">uncalib_gyro_drift_y</a>;</div>
|
|
||||||
<div class="line"><a id="l00064" name="l00064"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a27b52e2d96cb948c4257de4553053f72"> 64</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a27b52e2d96cb948c4257de4553053f72">uncalib_gyro_drift_z</a>;</div>
|
|
||||||
<div class="line"><a id="l00065" name="l00065"></a><span class="lineno"> 65</span> </div>
|
|
||||||
<div class="line"><a id="l00066" name="l00066"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0e72f6dde1411e4aa1c616cedcc556c1"> 66</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0e72f6dde1411e4aa1c616cedcc556c1">magf_x</a>;</div>
|
|
||||||
<div class="line"><a id="l00067" name="l00067"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8738f60a2b9bd49d2b8dd0487db7ac97"> 67</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8738f60a2b9bd49d2b8dd0487db7ac97">magf_y</a>;</div>
|
|
||||||
<div class="line"><a id="l00068" name="l00068"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a55187ebe06fa77def93681bcdf62595c"> 68</a></span> <span class="keywordtype">float</span> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a55187ebe06fa77def93681bcdf62595c">magf_z</a>;</div>
|
|
||||||
<div class="line"><a id="l00069" name="l00069"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0c962609a3bf7927204542521e9c5113"> 69</a></span> <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0c962609a3bf7927204542521e9c5113">magf_accuracy</a>;</div>
|
|
||||||
<div class="line"><a id="l00070" name="l00070"></a><span class="lineno"> 70</span> </div>
|
|
||||||
<div class="line"><a id="l00071" name="l00071"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a94befe7132d3a6a6ce2a7890e96ec091"> 71</a></span> uint16_t <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a94befe7132d3a6a6ce2a7890e96ec091">raw_mems_gyro_x</a>;</div>
|
|
||||||
<div class="line"><a id="l00072" name="l00072"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e9cd7e43d70932c5f84e3cfadf8bb47"> 72</a></span> uint16_t <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e9cd7e43d70932c5f84e3cfadf8bb47">raw_mems_gyro_y</a>;</div>
|
|
||||||
<div class="line"><a id="l00073" name="l00073"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a9df84179bd44a7febfa1058afe3dad6c"> 73</a></span> uint16_t <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a9df84179bd44a7febfa1058afe3dad6c">raw_mems_gyro_z</a>;</div>
|
|
||||||
<div class="line"><a id="l00074" name="l00074"></a><span class="lineno"> 74</span> </div>
|
|
||||||
<div class="line"><a id="l00075" name="l00075"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae8435a931eac7f4376a94acfcbf6a784"> 75</a></span> uint16_t <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae8435a931eac7f4376a94acfcbf6a784">step_count</a>;</div>
|
|
||||||
<div class="line"><a id="l00076" name="l00076"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a86473c2bd8cbe2c76276393ee20d568b"> 76</a></span> <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5">BNO08xStability</a> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a86473c2bd8cbe2c76276393ee20d568b">stability_classifier</a>;</div>
|
|
||||||
<div class="line"><a id="l00077" name="l00077"></a><span class="lineno"><a class="line" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0455033deba9570f248e8059cf6a3ce1"> 77</a></span> <a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187">BNO08xActivity</a> <a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0455033deba9570f248e8059cf6a3ce1">activity_classifier</a>;</div>
|
|
||||||
<div class="line"><a id="l00078" name="l00078"></a><span class="lineno"> 78</span> </div>
|
|
||||||
<div class="line"><a id="l00079" name="l00079"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a0b3d9379e670b0c532ba76801cfb7580"> 79</a></span> } <a class="code hl_typedef" href="class_b_n_o08x_test_helper.html#a0b3d9379e670b0c532ba76801cfb7580">imu_report_data_t</a>;</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00080" name="l00080"></a><span class="lineno"> 80</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00088" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00088" name="l00088"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885"> 88</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885">print_test_start_banner</a>(<span class="keyword">const</span> <span class="keywordtype">char</span>* TEST_TAG)</div>
|
|
||||||
<div class="line"><a id="l00089" name="l00089"></a><span class="lineno"> 89</span> {</div>
|
|
||||||
<div class="line"><a id="l00090" name="l00090"></a><span class="lineno"> 90</span> printf(<span class="stringliteral">"------------------------ BEGIN TEST: %s ------------------------\n\r"</span>, TEST_TAG);</div>
|
|
||||||
<div class="line"><a id="l00091" name="l00091"></a><span class="lineno"> 91</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00092" name="l00092"></a><span class="lineno"> 92</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00100" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00100" name="l00100"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919"> 100</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919">print_test_end_banner</a>(<span class="keyword">const</span> <span class="keywordtype">char</span>* TEST_TAG)</div>
|
|
||||||
<div class="line"><a id="l00101" name="l00101"></a><span class="lineno"> 101</span> {</div>
|
|
||||||
<div class="line"><a id="l00102" name="l00102"></a><span class="lineno"> 102</span> printf(<span class="stringliteral">"------------------------ END TEST: %s ------------------------\n\r"</span>, TEST_TAG);</div>
|
|
||||||
<div class="line"><a id="l00103" name="l00103"></a><span class="lineno"> 103</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00104" name="l00104"></a><span class="lineno"> 104</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00113" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00113" name="l00113"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002"> 113</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002">print_test_msg</a>(<span class="keyword">const</span> <span class="keywordtype">char</span>* TEST_TAG, <span class="keyword">const</span> <span class="keywordtype">char</span>* msg)</div>
|
|
||||||
<div class="line"><a id="l00114" name="l00114"></a><span class="lineno"> 114</span> {</div>
|
|
||||||
<div class="line"><a id="l00115" name="l00115"></a><span class="lineno"> 115</span> printf(<span class="stringliteral">"%s: %s: %s\n\r"</span>, <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#aa09d388a5da3a925ac25125b9c5c3a90">TAG</a>, TEST_TAG, msg);</div>
|
|
||||||
<div class="line"><a id="l00116" name="l00116"></a><span class="lineno"> 116</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00117" name="l00117"></a><span class="lineno"> 117</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00125" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00125" name="l00125"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a9e2f9bf13f28f1a6ba87e86bc5947cf1"> 125</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a9e2f9bf13f28f1a6ba87e86bc5947cf1">set_test_imu_cfg</a>(<a class="code hl_struct" href="structbno08x__config__t.html">bno08x_config_t</a> cfg)</div>
|
|
||||||
<div class="line"><a id="l00126" name="l00126"></a><span class="lineno"> 126</span> {</div>
|
|
||||||
<div class="line"><a id="l00127" name="l00127"></a><span class="lineno"> 127</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a008b268f705b9d2925230cb8193c9f28">imu_cfg</a> = cfg;</div>
|
|
||||||
<div class="line"><a id="l00128" name="l00128"></a><span class="lineno"> 128</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00129" name="l00129"></a><span class="lineno"> 129</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00135" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00135" name="l00135"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a6bd040c7d670a9713f2ab8a8a3913518"> 135</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a6bd040c7d670a9713f2ab8a8a3913518">create_test_imu</a>()</div>
|
|
||||||
<div class="line"><a id="l00136" name="l00136"></a><span class="lineno"> 136</span> {</div>
|
|
||||||
<div class="line"><a id="l00137" name="l00137"></a><span class="lineno"> 137</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a> != <span class="keyword">nullptr</span>)</div>
|
|
||||||
<div class="line"><a id="l00138" name="l00138"></a><span class="lineno"> 138</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40">destroy_test_imu</a>();</div>
|
|
||||||
<div class="line"><a id="l00139" name="l00139"></a><span class="lineno"> 139</span> </div>
|
|
||||||
<div class="line"><a id="l00140" name="l00140"></a><span class="lineno"> 140</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a> = <span class="keyword">new</span> <a class="code hl_class" href="class_b_n_o08x.html">BNO08x</a>();</div>
|
|
||||||
<div class="line"><a id="l00141" name="l00141"></a><span class="lineno"> 141</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00142" name="l00142"></a><span class="lineno"> 142</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00148" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00148" name="l00148"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40"> 148</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40">destroy_test_imu</a>()</div>
|
|
||||||
<div class="line"><a id="l00149" name="l00149"></a><span class="lineno"> 149</span> {</div>
|
|
||||||
<div class="line"><a id="l00150" name="l00150"></a><span class="lineno"> 150</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a> != <span class="keyword">nullptr</span>)</div>
|
|
||||||
<div class="line"><a id="l00151" name="l00151"></a><span class="lineno"> 151</span> {</div>
|
|
||||||
<div class="line"><a id="l00152" name="l00152"></a><span class="lineno"> 152</span> <span class="keyword">delete</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>;</div>
|
|
||||||
<div class="line"><a id="l00153" name="l00153"></a><span class="lineno"> 153</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a> = <span class="keyword">nullptr</span>;</div>
|
|
||||||
<div class="line"><a id="l00154" name="l00154"></a><span class="lineno"> 154</span> }</div>
|
|
||||||
<div class="line"><a id="l00155" name="l00155"></a><span class="lineno"> 155</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00156" name="l00156"></a><span class="lineno"> 156</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00162" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00162" name="l00162"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b"> 162</a></span> <span class="keyword">static</span> <a class="code hl_class" href="class_b_n_o08x.html">BNO08x</a>* <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b">get_test_imu</a>()</div>
|
|
||||||
<div class="line"><a id="l00163" name="l00163"></a><span class="lineno"> 163</span> {</div>
|
|
||||||
<div class="line"><a id="l00164" name="l00164"></a><span class="lineno"> 164</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>;</div>
|
|
||||||
<div class="line"><a id="l00165" name="l00165"></a><span class="lineno"> 165</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00166" name="l00166"></a><span class="lineno"> 166</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00172" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00172" name="l00172"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a71d9fd7d459a98a7e9089a8587a21f8d"> 172</a></span> <span class="keyword">static</span> esp_err_t <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a71d9fd7d459a98a7e9089a8587a21f8d">call_init_config_args</a>()</div>
|
|
||||||
<div class="line"><a id="l00173" name="l00173"></a><span class="lineno"> 173</span> {</div>
|
|
||||||
<div class="line"><a id="l00174" name="l00174"></a><span class="lineno"> 174</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a> == <span class="keyword">nullptr</span>)</div>
|
|
||||||
<div class="line"><a id="l00175" name="l00175"></a><span class="lineno"> 175</span> <span class="keywordflow">return</span> ESP_FAIL;</div>
|
|
||||||
<div class="line"><a id="l00176" name="l00176"></a><span class="lineno"> 176</span> </div>
|
|
||||||
<div class="line"><a id="l00177" name="l00177"></a><span class="lineno"> 177</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#a589eb9780f5bf613bbd447ef5b9ade3d">init_config_args</a>();</div>
|
|
||||||
<div class="line"><a id="l00178" name="l00178"></a><span class="lineno"> 178</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00179" name="l00179"></a><span class="lineno"> 179</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00185" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00185" name="l00185"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a504749533ccd91890d73440809d38161"> 185</a></span> <span class="keyword">static</span> esp_err_t <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a504749533ccd91890d73440809d38161">call_init_gpio</a>()</div>
|
|
||||||
<div class="line"><a id="l00186" name="l00186"></a><span class="lineno"> 186</span> {</div>
|
|
||||||
<div class="line"><a id="l00187" name="l00187"></a><span class="lineno"> 187</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a> == <span class="keyword">nullptr</span>)</div>
|
|
||||||
<div class="line"><a id="l00188" name="l00188"></a><span class="lineno"> 188</span> <span class="keywordflow">return</span> ESP_FAIL;</div>
|
|
||||||
<div class="line"><a id="l00189" name="l00189"></a><span class="lineno"> 189</span> </div>
|
|
||||||
<div class="line"><a id="l00190" name="l00190"></a><span class="lineno"> 190</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#ae0dab25557befcf62bf384fdc241ef10">init_gpio</a>();</div>
|
|
||||||
<div class="line"><a id="l00191" name="l00191"></a><span class="lineno"> 191</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00192" name="l00192"></a><span class="lineno"> 192</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00198" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00198" name="l00198"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a836c928981ac85d34668c9b97af17a15"> 198</a></span> <span class="keyword">static</span> esp_err_t <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a836c928981ac85d34668c9b97af17a15">call_init_hint_isr</a>()</div>
|
|
||||||
<div class="line"><a id="l00199" name="l00199"></a><span class="lineno"> 199</span> {</div>
|
|
||||||
<div class="line"><a id="l00200" name="l00200"></a><span class="lineno"> 200</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a> == <span class="keyword">nullptr</span>)</div>
|
|
||||||
<div class="line"><a id="l00201" name="l00201"></a><span class="lineno"> 201</span> <span class="keywordflow">return</span> ESP_FAIL;</div>
|
|
||||||
<div class="line"><a id="l00202" name="l00202"></a><span class="lineno"> 202</span> </div>
|
|
||||||
<div class="line"><a id="l00203" name="l00203"></a><span class="lineno"> 203</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#aa27026da2c52b4aca49b78863f10ec61">init_hint_isr</a>();</div>
|
|
||||||
<div class="line"><a id="l00204" name="l00204"></a><span class="lineno"> 204</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00205" name="l00205"></a><span class="lineno"> 205</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00211" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00211" name="l00211"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a7d2d784da1e850dab41154b35d7cdab5"> 211</a></span> <span class="keyword">static</span> esp_err_t <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a7d2d784da1e850dab41154b35d7cdab5">call_init_spi</a>()</div>
|
|
||||||
<div class="line"><a id="l00212" name="l00212"></a><span class="lineno"> 212</span> {</div>
|
|
||||||
<div class="line"><a id="l00213" name="l00213"></a><span class="lineno"> 213</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a> == <span class="keyword">nullptr</span>)</div>
|
|
||||||
<div class="line"><a id="l00214" name="l00214"></a><span class="lineno"> 214</span> <span class="keywordflow">return</span> ESP_FAIL;</div>
|
|
||||||
<div class="line"><a id="l00215" name="l00215"></a><span class="lineno"> 215</span> </div>
|
|
||||||
<div class="line"><a id="l00216" name="l00216"></a><span class="lineno"> 216</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#a58f43c8bb1e7fe8560ce442d46240e81">init_spi</a>();</div>
|
|
||||||
<div class="line"><a id="l00217" name="l00217"></a><span class="lineno"> 217</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00218" name="l00218"></a><span class="lineno"> 218</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00224" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00224" name="l00224"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#adf2488d1f7e3dec21a0d0c99417c181a"> 224</a></span> <span class="keyword">static</span> esp_err_t <a class="code hl_function" href="class_b_n_o08x_test_helper.html#adf2488d1f7e3dec21a0d0c99417c181a">call_launch_tasks</a>()</div>
|
|
||||||
<div class="line"><a id="l00225" name="l00225"></a><span class="lineno"> 225</span> {</div>
|
|
||||||
<div class="line"><a id="l00226" name="l00226"></a><span class="lineno"> 226</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a> == <span class="keyword">nullptr</span>)</div>
|
|
||||||
<div class="line"><a id="l00227" name="l00227"></a><span class="lineno"> 227</span> <span class="keywordflow">return</span> ESP_FAIL;</div>
|
|
||||||
<div class="line"><a id="l00228" name="l00228"></a><span class="lineno"> 228</span> </div>
|
|
||||||
<div class="line"><a id="l00229" name="l00229"></a><span class="lineno"> 229</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#a06f99a6b2182b49a0e61e2107f2be6be">launch_tasks</a>();</div>
|
|
||||||
<div class="line"><a id="l00230" name="l00230"></a><span class="lineno"> 230</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00231" name="l00231"></a><span class="lineno"> 231</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00240" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00240" name="l00240"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#aeb8cd985faf8e403f62b60fced9cb2fd"> 240</a></span> <span class="keyword">static</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#aeb8cd985faf8e403f62b60fced9cb2fd">rotation_vector_data_is_new</a>(<a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, <a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* default_report_data)</div>
|
|
||||||
<div class="line"><a id="l00241" name="l00241"></a><span class="lineno"> 241</span> {</div>
|
|
||||||
<div class="line"><a id="l00242" name="l00242"></a><span class="lineno"> 242</span> <span class="keywordtype">bool</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">false</span>;</div>
|
|
||||||
<div class="line"><a id="l00243" name="l00243"></a><span class="lineno"> 243</span> </div>
|
|
||||||
<div class="line"><a id="l00244" name="l00244"></a><span class="lineno"> 244</span> <span class="comment">// prev report should always contain the default test values as per test structure</span></div>
|
|
||||||
<div class="line"><a id="l00245" name="l00245"></a><span class="lineno"> 245</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8d2c3cd33943cb1b4fd0e800f822607e">quat_I</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8d2c3cd33943cb1b4fd0e800f822607e">quat_I</a>)</div>
|
|
||||||
<div class="line"><a id="l00246" name="l00246"></a><span class="lineno"> 246</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00247" name="l00247"></a><span class="lineno"> 247</span> </div>
|
|
||||||
<div class="line"><a id="l00248" name="l00248"></a><span class="lineno"> 248</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a20a09d197d5128aae64b7449df576c27">quat_J</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a20a09d197d5128aae64b7449df576c27">quat_J</a>)</div>
|
|
||||||
<div class="line"><a id="l00249" name="l00249"></a><span class="lineno"> 249</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00250" name="l00250"></a><span class="lineno"> 250</span> </div>
|
|
||||||
<div class="line"><a id="l00251" name="l00251"></a><span class="lineno"> 251</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3c74d4c93fc4390f52b75e6ff2bea95b">quat_K</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3c74d4c93fc4390f52b75e6ff2bea95b">quat_K</a>)</div>
|
|
||||||
<div class="line"><a id="l00252" name="l00252"></a><span class="lineno"> 252</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00253" name="l00253"></a><span class="lineno"> 253</span> </div>
|
|
||||||
<div class="line"><a id="l00254" name="l00254"></a><span class="lineno"> 254</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a80525c4943154f825a62539b10337976">quat_real</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a80525c4943154f825a62539b10337976">quat_real</a>)</div>
|
|
||||||
<div class="line"><a id="l00255" name="l00255"></a><span class="lineno"> 255</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00256" name="l00256"></a><span class="lineno"> 256</span> </div>
|
|
||||||
<div class="line"><a id="l00257" name="l00257"></a><span class="lineno"> 257</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#aac84ad10b65403ae1ee21dab5cdc77db">quat_accuracy</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#aac84ad10b65403ae1ee21dab5cdc77db">quat_accuracy</a>)</div>
|
|
||||||
<div class="line"><a id="l00258" name="l00258"></a><span class="lineno"> 258</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00259" name="l00259"></a><span class="lineno"> 259</span> </div>
|
|
||||||
<div class="line"><a id="l00260" name="l00260"></a><span class="lineno"> 260</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae0a8fef0227dd4304d08466c43d901a5">quat_radian_accuracy</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae0a8fef0227dd4304d08466c43d901a5">quat_radian_accuracy</a>)</div>
|
|
||||||
<div class="line"><a id="l00261" name="l00261"></a><span class="lineno"> 261</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00262" name="l00262"></a><span class="lineno"> 262</span> </div>
|
|
||||||
<div class="line"><a id="l00263" name="l00263"></a><span class="lineno"> 263</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a>;</div>
|
|
||||||
<div class="line"><a id="l00264" name="l00264"></a><span class="lineno"> 264</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00265" name="l00265"></a><span class="lineno"> 265</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00274" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00274" name="l00274"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#ac5b0ac4c70bbfcba9f2e8f353b35f9f6"> 274</a></span> <span class="keyword">static</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#ac5b0ac4c70bbfcba9f2e8f353b35f9f6">gyro_integrated_rotation_vector_data_is_new</a>(<a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, <a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* default_report_data)</div>
|
|
||||||
<div class="line"><a id="l00275" name="l00275"></a><span class="lineno"> 275</span> {</div>
|
|
||||||
<div class="line"><a id="l00276" name="l00276"></a><span class="lineno"> 276</span> <span class="keywordtype">bool</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">false</span>;</div>
|
|
||||||
<div class="line"><a id="l00277" name="l00277"></a><span class="lineno"> 277</span> </div>
|
|
||||||
<div class="line"><a id="l00278" name="l00278"></a><span class="lineno"> 278</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8d2c3cd33943cb1b4fd0e800f822607e">quat_I</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8d2c3cd33943cb1b4fd0e800f822607e">quat_I</a>)</div>
|
|
||||||
<div class="line"><a id="l00279" name="l00279"></a><span class="lineno"> 279</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00280" name="l00280"></a><span class="lineno"> 280</span> </div>
|
|
||||||
<div class="line"><a id="l00281" name="l00281"></a><span class="lineno"> 281</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a20a09d197d5128aae64b7449df576c27">quat_J</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a20a09d197d5128aae64b7449df576c27">quat_J</a>)</div>
|
|
||||||
<div class="line"><a id="l00282" name="l00282"></a><span class="lineno"> 282</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00283" name="l00283"></a><span class="lineno"> 283</span> </div>
|
|
||||||
<div class="line"><a id="l00284" name="l00284"></a><span class="lineno"> 284</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3c74d4c93fc4390f52b75e6ff2bea95b">quat_K</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3c74d4c93fc4390f52b75e6ff2bea95b">quat_K</a>)</div>
|
|
||||||
<div class="line"><a id="l00285" name="l00285"></a><span class="lineno"> 285</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00286" name="l00286"></a><span class="lineno"> 286</span> </div>
|
|
||||||
<div class="line"><a id="l00287" name="l00287"></a><span class="lineno"> 287</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a80525c4943154f825a62539b10337976">quat_real</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a80525c4943154f825a62539b10337976">quat_real</a>)</div>
|
|
||||||
<div class="line"><a id="l00288" name="l00288"></a><span class="lineno"> 288</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00289" name="l00289"></a><span class="lineno"> 289</span> </div>
|
|
||||||
<div class="line"><a id="l00290" name="l00290"></a><span class="lineno"> 290</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a077a94b4de0b5c280d69611325208cf7">integrated_gyro_vel_x</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a077a94b4de0b5c280d69611325208cf7">integrated_gyro_vel_x</a>)</div>
|
|
||||||
<div class="line"><a id="l00291" name="l00291"></a><span class="lineno"> 291</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00292" name="l00292"></a><span class="lineno"> 292</span> </div>
|
|
||||||
<div class="line"><a id="l00293" name="l00293"></a><span class="lineno"> 293</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af4b75b320bc390c90656905711f1c791">integrated_gyro_vel_y</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af4b75b320bc390c90656905711f1c791">integrated_gyro_vel_y</a>)</div>
|
|
||||||
<div class="line"><a id="l00294" name="l00294"></a><span class="lineno"> 294</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00295" name="l00295"></a><span class="lineno"> 295</span> </div>
|
|
||||||
<div class="line"><a id="l00296" name="l00296"></a><span class="lineno"> 296</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a1aa67da9c3c6449dfce361a528c418d3">integrated_gyro_vel_z</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a1aa67da9c3c6449dfce361a528c418d3">integrated_gyro_vel_z</a>)</div>
|
|
||||||
<div class="line"><a id="l00297" name="l00297"></a><span class="lineno"> 297</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00298" name="l00298"></a><span class="lineno"> 298</span> </div>
|
|
||||||
<div class="line"><a id="l00299" name="l00299"></a><span class="lineno"> 299</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a>;</div>
|
|
||||||
<div class="line"><a id="l00300" name="l00300"></a><span class="lineno"> 300</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00301" name="l00301"></a><span class="lineno"> 301</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00310" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00310" name="l00310"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#adb5952b2b96b553024b6a841e30adad2"> 310</a></span> <span class="keyword">static</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#adb5952b2b96b553024b6a841e30adad2">uncalibrated_gyro_data_is_new</a>(<a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, <a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* default_report_data)</div>
|
|
||||||
<div class="line"><a id="l00311" name="l00311"></a><span class="lineno"> 311</span> {</div>
|
|
||||||
<div class="line"><a id="l00312" name="l00312"></a><span class="lineno"> 312</span> <span class="keywordtype">bool</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">false</span>;</div>
|
|
||||||
<div class="line"><a id="l00313" name="l00313"></a><span class="lineno"> 313</span> </div>
|
|
||||||
<div class="line"><a id="l00314" name="l00314"></a><span class="lineno"> 314</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a292b1c36fed6a9c9742edf730299c4f4">uncalib_gyro_vel_x</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a292b1c36fed6a9c9742edf730299c4f4">uncalib_gyro_vel_x</a>)</div>
|
|
||||||
<div class="line"><a id="l00315" name="l00315"></a><span class="lineno"> 315</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00316" name="l00316"></a><span class="lineno"> 316</span> </div>
|
|
||||||
<div class="line"><a id="l00317" name="l00317"></a><span class="lineno"> 317</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#adfd6bf2e2264cf25bd02814446600ab4">uncalib_gyro_vel_y</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#adfd6bf2e2264cf25bd02814446600ab4">uncalib_gyro_vel_y</a>)</div>
|
|
||||||
<div class="line"><a id="l00318" name="l00318"></a><span class="lineno"> 318</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00319" name="l00319"></a><span class="lineno"> 319</span> </div>
|
|
||||||
<div class="line"><a id="l00320" name="l00320"></a><span class="lineno"> 320</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ab39fd6f409288bb35fb1542ff4b9cbe4">uncalib_gyro_vel_z</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ab39fd6f409288bb35fb1542ff4b9cbe4">uncalib_gyro_vel_z</a>)</div>
|
|
||||||
<div class="line"><a id="l00321" name="l00321"></a><span class="lineno"> 321</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00322" name="l00322"></a><span class="lineno"> 322</span> </div>
|
|
||||||
<div class="line"><a id="l00323" name="l00323"></a><span class="lineno"> 323</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac70a65027c3e740eca2b1f172b7cefa3">uncalib_gyro_drift_x</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac70a65027c3e740eca2b1f172b7cefa3">uncalib_gyro_drift_x</a>)</div>
|
|
||||||
<div class="line"><a id="l00324" name="l00324"></a><span class="lineno"> 324</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00325" name="l00325"></a><span class="lineno"> 325</span> </div>
|
|
||||||
<div class="line"><a id="l00326" name="l00326"></a><span class="lineno"> 326</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a29d5ae3e0ed3463cb9297f9cdc0e8472">uncalib_gyro_drift_y</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a29d5ae3e0ed3463cb9297f9cdc0e8472">uncalib_gyro_drift_y</a>)</div>
|
|
||||||
<div class="line"><a id="l00327" name="l00327"></a><span class="lineno"> 327</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00328" name="l00328"></a><span class="lineno"> 328</span> </div>
|
|
||||||
<div class="line"><a id="l00329" name="l00329"></a><span class="lineno"> 329</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a27b52e2d96cb948c4257de4553053f72">uncalib_gyro_drift_z</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a27b52e2d96cb948c4257de4553053f72">uncalib_gyro_drift_z</a>)</div>
|
|
||||||
<div class="line"><a id="l00330" name="l00330"></a><span class="lineno"> 330</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00331" name="l00331"></a><span class="lineno"> 331</span> </div>
|
|
||||||
<div class="line"><a id="l00332" name="l00332"></a><span class="lineno"> 332</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a>;</div>
|
|
||||||
<div class="line"><a id="l00333" name="l00333"></a><span class="lineno"> 333</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00334" name="l00334"></a><span class="lineno"> 334</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00343" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00343" name="l00343"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a084e65ff5c0e2f429b39ebb53b0e03c9"> 343</a></span> <span class="keyword">static</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a084e65ff5c0e2f429b39ebb53b0e03c9">calibrated_gyro_data_is_new</a>(<a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, <a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* default_report_data)</div>
|
|
||||||
<div class="line"><a id="l00344" name="l00344"></a><span class="lineno"> 344</span> {</div>
|
|
||||||
<div class="line"><a id="l00345" name="l00345"></a><span class="lineno"> 345</span> <span class="keywordtype">bool</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">false</span>;</div>
|
|
||||||
<div class="line"><a id="l00346" name="l00346"></a><span class="lineno"> 346</span> </div>
|
|
||||||
<div class="line"><a id="l00347" name="l00347"></a><span class="lineno"> 347</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a89b427579a281440ab94a340c0ec8443">calib_gyro_vel_x</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a89b427579a281440ab94a340c0ec8443">calib_gyro_vel_x</a>)</div>
|
|
||||||
<div class="line"><a id="l00348" name="l00348"></a><span class="lineno"> 348</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00349" name="l00349"></a><span class="lineno"> 349</span> </div>
|
|
||||||
<div class="line"><a id="l00350" name="l00350"></a><span class="lineno"> 350</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af9e11fd749123f5723b2e281c8d2fd16">calib_gyro_vel_y</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af9e11fd749123f5723b2e281c8d2fd16">calib_gyro_vel_y</a>)</div>
|
|
||||||
<div class="line"><a id="l00351" name="l00351"></a><span class="lineno"> 351</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00352" name="l00352"></a><span class="lineno"> 352</span> </div>
|
|
||||||
<div class="line"><a id="l00353" name="l00353"></a><span class="lineno"> 353</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a769ddae74a6c89a2d319c28f95ed6479">calib_gyro_vel_z</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a769ddae74a6c89a2d319c28f95ed6479">calib_gyro_vel_z</a>)</div>
|
|
||||||
<div class="line"><a id="l00354" name="l00354"></a><span class="lineno"> 354</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00355" name="l00355"></a><span class="lineno"> 355</span> </div>
|
|
||||||
<div class="line"><a id="l00356" name="l00356"></a><span class="lineno"> 356</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a>;</div>
|
|
||||||
<div class="line"><a id="l00357" name="l00357"></a><span class="lineno"> 357</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00358" name="l00358"></a><span class="lineno"> 358</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00367" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00367" name="l00367"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea"> 367</a></span> <span class="keyword">static</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea">accelerometer_data_is_new</a>(<a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, <a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* default_report_data)</div>
|
|
||||||
<div class="line"><a id="l00368" name="l00368"></a><span class="lineno"> 368</span> {</div>
|
|
||||||
<div class="line"><a id="l00369" name="l00369"></a><span class="lineno"> 369</span> <span class="keywordtype">bool</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">false</span>;</div>
|
|
||||||
<div class="line"><a id="l00370" name="l00370"></a><span class="lineno"> 370</span> </div>
|
|
||||||
<div class="line"><a id="l00371" name="l00371"></a><span class="lineno"> 371</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5c01b349cc9e4e45c78c576882d633fd">accel_x</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5c01b349cc9e4e45c78c576882d633fd">accel_x</a>)</div>
|
|
||||||
<div class="line"><a id="l00372" name="l00372"></a><span class="lineno"> 372</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00373" name="l00373"></a><span class="lineno"> 373</span> </div>
|
|
||||||
<div class="line"><a id="l00374" name="l00374"></a><span class="lineno"> 374</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e594d0a1e86fb575f72c6f330c8983c">accel_y</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e594d0a1e86fb575f72c6f330c8983c">accel_y</a>)</div>
|
|
||||||
<div class="line"><a id="l00375" name="l00375"></a><span class="lineno"> 375</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00376" name="l00376"></a><span class="lineno"> 376</span> </div>
|
|
||||||
<div class="line"><a id="l00377" name="l00377"></a><span class="lineno"> 377</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af134cb789c29120033d81916e0c100d4">accel_z</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af134cb789c29120033d81916e0c100d4">accel_z</a>)</div>
|
|
||||||
<div class="line"><a id="l00378" name="l00378"></a><span class="lineno"> 378</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00379" name="l00379"></a><span class="lineno"> 379</span> </div>
|
|
||||||
<div class="line"><a id="l00380" name="l00380"></a><span class="lineno"> 380</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac5d393de0f15176ba81bc63a80b49ca3">accel_accuracy</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac5d393de0f15176ba81bc63a80b49ca3">accel_accuracy</a>)</div>
|
|
||||||
<div class="line"><a id="l00381" name="l00381"></a><span class="lineno"> 381</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00382" name="l00382"></a><span class="lineno"> 382</span> </div>
|
|
||||||
<div class="line"><a id="l00383" name="l00383"></a><span class="lineno"> 383</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a>;</div>
|
|
||||||
<div class="line"><a id="l00384" name="l00384"></a><span class="lineno"> 384</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00385" name="l00385"></a><span class="lineno"> 385</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00394" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00394" name="l00394"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#ad398739ce46400c1ac35e1cf7603d590"> 394</a></span> <span class="keyword">static</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#ad398739ce46400c1ac35e1cf7603d590">linear_accelerometer_data_is_new</a>(<a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, <a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* default_report_data)</div>
|
|
||||||
<div class="line"><a id="l00395" name="l00395"></a><span class="lineno"> 395</span> {</div>
|
|
||||||
<div class="line"><a id="l00396" name="l00396"></a><span class="lineno"> 396</span> <span class="keywordtype">bool</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">false</span>;</div>
|
|
||||||
<div class="line"><a id="l00397" name="l00397"></a><span class="lineno"> 397</span> </div>
|
|
||||||
<div class="line"><a id="l00398" name="l00398"></a><span class="lineno"> 398</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3a62ed280657cd409d723e64f0c313b5">lin_accel_x</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3a62ed280657cd409d723e64f0c313b5">lin_accel_x</a>)</div>
|
|
||||||
<div class="line"><a id="l00399" name="l00399"></a><span class="lineno"> 399</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00400" name="l00400"></a><span class="lineno"> 400</span> </div>
|
|
||||||
<div class="line"><a id="l00401" name="l00401"></a><span class="lineno"> 401</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a553942aa784c35c833543ecc9a05f606">lin_accel_y</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a553942aa784c35c833543ecc9a05f606">lin_accel_y</a>)</div>
|
|
||||||
<div class="line"><a id="l00402" name="l00402"></a><span class="lineno"> 402</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00403" name="l00403"></a><span class="lineno"> 403</span> </div>
|
|
||||||
<div class="line"><a id="l00404" name="l00404"></a><span class="lineno"> 404</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5bf43fc0daf3a86954924e066cad3a9b">lin_accel_z</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5bf43fc0daf3a86954924e066cad3a9b">lin_accel_z</a>)</div>
|
|
||||||
<div class="line"><a id="l00405" name="l00405"></a><span class="lineno"> 405</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00406" name="l00406"></a><span class="lineno"> 406</span> </div>
|
|
||||||
<div class="line"><a id="l00407" name="l00407"></a><span class="lineno"> 407</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a48a249994c27f59ca4167b56bdda311a">lin_accel_accuracy</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a48a249994c27f59ca4167b56bdda311a">lin_accel_accuracy</a>)</div>
|
|
||||||
<div class="line"><a id="l00408" name="l00408"></a><span class="lineno"> 408</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00409" name="l00409"></a><span class="lineno"> 409</span> </div>
|
|
||||||
<div class="line"><a id="l00410" name="l00410"></a><span class="lineno"> 410</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a>;</div>
|
|
||||||
<div class="line"><a id="l00411" name="l00411"></a><span class="lineno"> 411</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00412" name="l00412"></a><span class="lineno"> 412</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00421" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00421" name="l00421"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a3c2514f3bad3f091de4646c5798f487a"> 421</a></span> <span class="keyword">static</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a3c2514f3bad3f091de4646c5798f487a">gravity_data_is_new</a>(<a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, <a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* default_report_data)</div>
|
|
||||||
<div class="line"><a id="l00422" name="l00422"></a><span class="lineno"> 422</span> {</div>
|
|
||||||
<div class="line"><a id="l00423" name="l00423"></a><span class="lineno"> 423</span> <span class="keywordtype">bool</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">false</span>;</div>
|
|
||||||
<div class="line"><a id="l00424" name="l00424"></a><span class="lineno"> 424</span> </div>
|
|
||||||
<div class="line"><a id="l00425" name="l00425"></a><span class="lineno"> 425</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ad2c17ea111250ebc1a4a763dae3c072a">grav_x</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ad2c17ea111250ebc1a4a763dae3c072a">grav_x</a>)</div>
|
|
||||||
<div class="line"><a id="l00426" name="l00426"></a><span class="lineno"> 426</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00427" name="l00427"></a><span class="lineno"> 427</span> </div>
|
|
||||||
<div class="line"><a id="l00428" name="l00428"></a><span class="lineno"> 428</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a19fc4af8a26c10a027cbd859d67dba4a">grav_y</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a19fc4af8a26c10a027cbd859d67dba4a">grav_y</a>)</div>
|
|
||||||
<div class="line"><a id="l00429" name="l00429"></a><span class="lineno"> 429</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00430" name="l00430"></a><span class="lineno"> 430</span> </div>
|
|
||||||
<div class="line"><a id="l00431" name="l00431"></a><span class="lineno"> 431</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af1887bdfef4fc2c683fe2134cb5cfb50">grav_z</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af1887bdfef4fc2c683fe2134cb5cfb50">grav_z</a>)</div>
|
|
||||||
<div class="line"><a id="l00432" name="l00432"></a><span class="lineno"> 432</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00433" name="l00433"></a><span class="lineno"> 433</span> </div>
|
|
||||||
<div class="line"><a id="l00434" name="l00434"></a><span class="lineno"> 434</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a735d099f3dd0ead4b8d986fd139af43d">grav_accuracy</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a735d099f3dd0ead4b8d986fd139af43d">grav_accuracy</a>)</div>
|
|
||||||
<div class="line"><a id="l00435" name="l00435"></a><span class="lineno"> 435</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00436" name="l00436"></a><span class="lineno"> 436</span> </div>
|
|
||||||
<div class="line"><a id="l00437" name="l00437"></a><span class="lineno"> 437</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a>;</div>
|
|
||||||
<div class="line"><a id="l00438" name="l00438"></a><span class="lineno"> 438</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00439" name="l00439"></a><span class="lineno"> 439</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00448" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00448" name="l00448"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a157342da2def8b659d27ae4d24063cb5"> 448</a></span> <span class="keyword">static</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a157342da2def8b659d27ae4d24063cb5">magnetometer_data_is_new</a>(<a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, <a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* default_report_data)</div>
|
|
||||||
<div class="line"><a id="l00449" name="l00449"></a><span class="lineno"> 449</span> {</div>
|
|
||||||
<div class="line"><a id="l00450" name="l00450"></a><span class="lineno"> 450</span> <span class="keywordtype">bool</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">false</span>;</div>
|
|
||||||
<div class="line"><a id="l00451" name="l00451"></a><span class="lineno"> 451</span> </div>
|
|
||||||
<div class="line"><a id="l00452" name="l00452"></a><span class="lineno"> 452</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0e72f6dde1411e4aa1c616cedcc556c1">magf_x</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0e72f6dde1411e4aa1c616cedcc556c1">magf_x</a>)</div>
|
|
||||||
<div class="line"><a id="l00453" name="l00453"></a><span class="lineno"> 453</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00454" name="l00454"></a><span class="lineno"> 454</span> </div>
|
|
||||||
<div class="line"><a id="l00455" name="l00455"></a><span class="lineno"> 455</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8738f60a2b9bd49d2b8dd0487db7ac97">magf_y</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8738f60a2b9bd49d2b8dd0487db7ac97">magf_y</a>)</div>
|
|
||||||
<div class="line"><a id="l00456" name="l00456"></a><span class="lineno"> 456</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00457" name="l00457"></a><span class="lineno"> 457</span> </div>
|
|
||||||
<div class="line"><a id="l00458" name="l00458"></a><span class="lineno"> 458</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a55187ebe06fa77def93681bcdf62595c">magf_z</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a55187ebe06fa77def93681bcdf62595c">magf_z</a>)</div>
|
|
||||||
<div class="line"><a id="l00459" name="l00459"></a><span class="lineno"> 459</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00460" name="l00460"></a><span class="lineno"> 460</span> </div>
|
|
||||||
<div class="line"><a id="l00461" name="l00461"></a><span class="lineno"> 461</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0c962609a3bf7927204542521e9c5113">magf_accuracy</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0c962609a3bf7927204542521e9c5113">magf_accuracy</a>)</div>
|
|
||||||
<div class="line"><a id="l00462" name="l00462"></a><span class="lineno"> 462</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00463" name="l00463"></a><span class="lineno"> 463</span> </div>
|
|
||||||
<div class="line"><a id="l00464" name="l00464"></a><span class="lineno"> 464</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a>;</div>
|
|
||||||
<div class="line"><a id="l00465" name="l00465"></a><span class="lineno"> 465</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00466" name="l00466"></a><span class="lineno"> 466</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00475" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00475" name="l00475"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#aa7eb152d4192c3949bb3443ef6221782"> 475</a></span> <span class="keyword">static</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#aa7eb152d4192c3949bb3443ef6221782">step_counter_data_is_new</a>(<a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, <a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* default_report_data)</div>
|
|
||||||
<div class="line"><a id="l00476" name="l00476"></a><span class="lineno"> 476</span> {</div>
|
|
||||||
<div class="line"><a id="l00477" name="l00477"></a><span class="lineno"> 477</span> <span class="keywordtype">bool</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">false</span>;</div>
|
|
||||||
<div class="line"><a id="l00478" name="l00478"></a><span class="lineno"> 478</span> </div>
|
|
||||||
<div class="line"><a id="l00479" name="l00479"></a><span class="lineno"> 479</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae8435a931eac7f4376a94acfcbf6a784">step_count</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae8435a931eac7f4376a94acfcbf6a784">step_count</a>)</div>
|
|
||||||
<div class="line"><a id="l00480" name="l00480"></a><span class="lineno"> 480</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00481" name="l00481"></a><span class="lineno"> 481</span> </div>
|
|
||||||
<div class="line"><a id="l00482" name="l00482"></a><span class="lineno"> 482</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a>;</div>
|
|
||||||
<div class="line"><a id="l00483" name="l00483"></a><span class="lineno"> 483</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00484" name="l00484"></a><span class="lineno"> 484</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00493" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00493" name="l00493"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a95ed21657224358877a66d010eeefad3"> 493</a></span> <span class="keyword">static</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a95ed21657224358877a66d010eeefad3">stability_classifier_data_is_new</a>(<a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, <a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* default_report_data)</div>
|
|
||||||
<div class="line"><a id="l00494" name="l00494"></a><span class="lineno"> 494</span> {</div>
|
|
||||||
<div class="line"><a id="l00495" name="l00495"></a><span class="lineno"> 495</span> <span class="keywordtype">bool</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">false</span>;</div>
|
|
||||||
<div class="line"><a id="l00496" name="l00496"></a><span class="lineno"> 496</span> </div>
|
|
||||||
<div class="line"><a id="l00497" name="l00497"></a><span class="lineno"> 497</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a86473c2bd8cbe2c76276393ee20d568b">stability_classifier</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a86473c2bd8cbe2c76276393ee20d568b">stability_classifier</a>)</div>
|
|
||||||
<div class="line"><a id="l00498" name="l00498"></a><span class="lineno"> 498</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00499" name="l00499"></a><span class="lineno"> 499</span> </div>
|
|
||||||
<div class="line"><a id="l00500" name="l00500"></a><span class="lineno"> 500</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a>;</div>
|
|
||||||
<div class="line"><a id="l00501" name="l00501"></a><span class="lineno"> 501</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00502" name="l00502"></a><span class="lineno"> 502</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00511" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00511" name="l00511"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#afc6cc734ad843aca30a7cb76ad6dedb9"> 511</a></span> <span class="keyword">static</span> <span class="keywordtype">bool</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#afc6cc734ad843aca30a7cb76ad6dedb9">activity_classifier_data_is_new</a>(<a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, <a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* default_report_data)</div>
|
|
||||||
<div class="line"><a id="l00512" name="l00512"></a><span class="lineno"> 512</span> {</div>
|
|
||||||
<div class="line"><a id="l00513" name="l00513"></a><span class="lineno"> 513</span> <span class="keywordtype">bool</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">false</span>;</div>
|
|
||||||
<div class="line"><a id="l00514" name="l00514"></a><span class="lineno"> 514</span> </div>
|
|
||||||
<div class="line"><a id="l00515" name="l00515"></a><span class="lineno"> 515</span> <span class="keywordflow">if</span> (<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0455033deba9570f248e8059cf6a3ce1">activity_classifier</a> != default_report_data-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0455033deba9570f248e8059cf6a3ce1">activity_classifier</a>)</div>
|
|
||||||
<div class="line"><a id="l00516" name="l00516"></a><span class="lineno"> 516</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = <span class="keyword">true</span>;</div>
|
|
||||||
<div class="line"><a id="l00517" name="l00517"></a><span class="lineno"> 517</span> </div>
|
|
||||||
<div class="line"><a id="l00518" name="l00518"></a><span class="lineno"> 518</span> <span class="keywordflow">return</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a>;</div>
|
|
||||||
<div class="line"><a id="l00519" name="l00519"></a><span class="lineno"> 519</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00520" name="l00520"></a><span class="lineno"> 520</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00528" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00528" name="l00528"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2"> 528</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2">update_report_data</a>(<a class="code hl_struct" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">imu_report_data_t</a>* <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>)</div>
|
|
||||||
<div class="line"><a id="l00529" name="l00529"></a><span class="lineno"> 529</span> {</div>
|
|
||||||
<div class="line"><a id="l00530" name="l00530"></a><span class="lineno"> 530</span> </div>
|
|
||||||
<div class="line"><a id="l00531" name="l00531"></a><span class="lineno"> 531</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a">get_quat</a>(<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8d2c3cd33943cb1b4fd0e800f822607e">quat_I</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a20a09d197d5128aae64b7449df576c27">quat_J</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3c74d4c93fc4390f52b75e6ff2bea95b">quat_K</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a80525c4943154f825a62539b10337976">quat_real</a>,</div>
|
|
||||||
<div class="line"><a id="l00532" name="l00532"></a><span class="lineno"> 532</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae0a8fef0227dd4304d08466c43d901a5">quat_radian_accuracy</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#aac84ad10b65403ae1ee21dab5cdc77db">quat_accuracy</a>);</div>
|
|
||||||
<div class="line"><a id="l00533" name="l00533"></a><span class="lineno"> 533</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f">get_integrated_gyro_velocity</a>(</div>
|
|
||||||
<div class="line"><a id="l00534" name="l00534"></a><span class="lineno"> 534</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a077a94b4de0b5c280d69611325208cf7">integrated_gyro_vel_x</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af4b75b320bc390c90656905711f1c791">integrated_gyro_vel_y</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a1aa67da9c3c6449dfce361a528c418d3">integrated_gyro_vel_z</a>);</div>
|
|
||||||
<div class="line"><a id="l00535" name="l00535"></a><span class="lineno"> 535</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885">get_accel</a>(<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5c01b349cc9e4e45c78c576882d633fd">accel_x</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e594d0a1e86fb575f72c6f330c8983c">accel_y</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af134cb789c29120033d81916e0c100d4">accel_z</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac5d393de0f15176ba81bc63a80b49ca3">accel_accuracy</a>);</div>
|
|
||||||
<div class="line"><a id="l00536" name="l00536"></a><span class="lineno"> 536</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46">get_linear_accel</a>(<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3a62ed280657cd409d723e64f0c313b5">lin_accel_x</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a553942aa784c35c833543ecc9a05f606">lin_accel_y</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5bf43fc0daf3a86954924e066cad3a9b">lin_accel_z</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a48a249994c27f59ca4167b56bdda311a">lin_accel_accuracy</a>);</div>
|
|
||||||
<div class="line"><a id="l00537" name="l00537"></a><span class="lineno"> 537</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#a067678914e928a6691625b17c40237a0">get_gravity</a>(<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ad2c17ea111250ebc1a4a763dae3c072a">grav_x</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a19fc4af8a26c10a027cbd859d67dba4a">grav_y</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af1887bdfef4fc2c683fe2134cb5cfb50">grav_z</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a735d099f3dd0ead4b8d986fd139af43d">grav_accuracy</a>);</div>
|
|
||||||
<div class="line"><a id="l00538" name="l00538"></a><span class="lineno"> 538</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f">get_calibrated_gyro_velocity</a>(<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a89b427579a281440ab94a340c0ec8443">calib_gyro_vel_x</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af9e11fd749123f5723b2e281c8d2fd16">calib_gyro_vel_y</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a769ddae74a6c89a2d319c28f95ed6479">calib_gyro_vel_z</a>);</div>
|
|
||||||
<div class="line"><a id="l00539" name="l00539"></a><span class="lineno"> 539</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104">get_uncalibrated_gyro_velocity</a>(<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a292b1c36fed6a9c9742edf730299c4f4">uncalib_gyro_vel_x</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#adfd6bf2e2264cf25bd02814446600ab4">uncalib_gyro_vel_y</a>,</div>
|
|
||||||
<div class="line"><a id="l00540" name="l00540"></a><span class="lineno"> 540</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ab39fd6f409288bb35fb1542ff4b9cbe4">uncalib_gyro_vel_z</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac70a65027c3e740eca2b1f172b7cefa3">uncalib_gyro_drift_x</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a29d5ae3e0ed3463cb9297f9cdc0e8472">uncalib_gyro_drift_y</a>,</div>
|
|
||||||
<div class="line"><a id="l00541" name="l00541"></a><span class="lineno"> 541</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a27b52e2d96cb948c4257de4553053f72">uncalib_gyro_drift_z</a>);</div>
|
|
||||||
<div class="line"><a id="l00542" name="l00542"></a><span class="lineno"> 542</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb">get_magf</a>(<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0e72f6dde1411e4aa1c616cedcc556c1">magf_x</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8738f60a2b9bd49d2b8dd0487db7ac97">magf_y</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a55187ebe06fa77def93681bcdf62595c">magf_z</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0c962609a3bf7927204542521e9c5113">magf_accuracy</a>);</div>
|
|
||||||
<div class="line"><a id="l00543" name="l00543"></a><span class="lineno"> 543</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27">get_raw_mems_gyro</a>(<a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a94befe7132d3a6a6ce2a7890e96ec091">raw_mems_gyro_x</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e9cd7e43d70932c5f84e3cfadf8bb47">raw_mems_gyro_y</a>, <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a9df84179bd44a7febfa1058afe3dad6c">raw_mems_gyro_z</a>);</div>
|
|
||||||
<div class="line"><a id="l00544" name="l00544"></a><span class="lineno"> 544</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae8435a931eac7f4376a94acfcbf6a784">step_count</a> = <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef">get_step_count</a>();</div>
|
|
||||||
<div class="line"><a id="l00545" name="l00545"></a><span class="lineno"> 545</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a86473c2bd8cbe2c76276393ee20d568b">stability_classifier</a> = <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#a248544b262582d10d917a687190cb454">get_stability_classifier</a>();</div>
|
|
||||||
<div class="line"><a id="l00546" name="l00546"></a><span class="lineno"> 546</span> <a class="code hl_variable" href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a>-><a class="code hl_variable" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0455033deba9570f248e8059cf6a3ce1">activity_classifier</a> = <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_function" href="class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed">get_activity_classifier</a>();</div>
|
|
||||||
<div class="line"><a id="l00547" name="l00547"></a><span class="lineno"> 547</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00548" name="l00548"></a><span class="lineno"> 548</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00554" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00554" name="l00554"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#ade6be1fd8ef3a99e0edae4cbf25eb528"> 554</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_helper.html#ade6be1fd8ef3a99e0edae4cbf25eb528">reset_all_imu_data_to_test_defaults</a>()</div>
|
|
||||||
<div class="line"><a id="l00555" name="l00555"></a><span class="lineno"> 555</span> {</div>
|
|
||||||
<div class="line"><a id="l00556" name="l00556"></a><span class="lineno"> 556</span> <span class="keyword">static</span> <span class="keyword">const</span> <span class="keyword">constexpr</span> uint16_t TEST_VAL_UINT16 = 65535U;</div>
|
|
||||||
<div class="line"><a id="l00557" name="l00557"></a><span class="lineno"> 557</span> <span class="keyword">static</span> <span class="keyword">const</span> <span class="keyword">constexpr</span> uint16_t TEST_VAL_UINT8 = 255;</div>
|
|
||||||
<div class="line"><a id="l00558" name="l00558"></a><span class="lineno"> 558</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#abc972db20affbd0040b4e6c4892dd57b">time_stamp</a> = 0UL;</div>
|
|
||||||
<div class="line"><a id="l00559" name="l00559"></a><span class="lineno"> 559</span> </div>
|
|
||||||
<div class="line"><a id="l00560" name="l00560"></a><span class="lineno"> 560</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a75fb2f06c5bbe26e3f3c794934ef954c">raw_accel_X</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00561" name="l00561"></a><span class="lineno"> 561</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#ab56e2ba505fa293d03e955137625c562">raw_accel_Y</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00562" name="l00562"></a><span class="lineno"> 562</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#af254d245b368027df6952b7d7522bd35">raw_accel_Z</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00563" name="l00563"></a><span class="lineno"> 563</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a3365b7ebde01e284274e655c60343df9">accel_accuracy</a> = <span class="keyword">static_cast<</span>uint16_t<span class="keyword">></span>(<a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">BNO08xAccuracy::UNDEFINED</a>);</div>
|
|
||||||
<div class="line"><a id="l00564" name="l00564"></a><span class="lineno"> 564</span> </div>
|
|
||||||
<div class="line"><a id="l00565" name="l00565"></a><span class="lineno"> 565</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#ae1f71a432cb15e75f522fa18f29f4d50">raw_lin_accel_X</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00566" name="l00566"></a><span class="lineno"> 566</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#aff3a5590471d1c9fc485a5610433915f">raw_lin_accel_Y</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00567" name="l00567"></a><span class="lineno"> 567</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#abc8add47f1babc66c812a015614143d3">raw_lin_accel_Z</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00568" name="l00568"></a><span class="lineno"> 568</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a35e1635ef5edde8fc8640f978c6f2e3c">accel_lin_accuracy</a> = <span class="keyword">static_cast<</span>uint16_t<span class="keyword">></span>(<a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">BNO08xAccuracy::UNDEFINED</a>);</div>
|
|
||||||
<div class="line"><a id="l00569" name="l00569"></a><span class="lineno"> 569</span> </div>
|
|
||||||
<div class="line"><a id="l00570" name="l00570"></a><span class="lineno"> 570</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a87faca2c8c71ff46bf2e6ad4ba271b3a">raw_calib_gyro_X</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00571" name="l00571"></a><span class="lineno"> 571</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a66c48af1d4162a9ec25c3a1c95660fe4">raw_calib_gyro_Y</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00572" name="l00572"></a><span class="lineno"> 572</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#af5450d1a9c20c2a5c62c960e3df11c0e">raw_calib_gyro_Z</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00573" name="l00573"></a><span class="lineno"> 573</span> </div>
|
|
||||||
<div class="line"><a id="l00574" name="l00574"></a><span class="lineno"> 574</span> <span class="comment">// reset quaternion to nan</span></div>
|
|
||||||
<div class="line"><a id="l00575" name="l00575"></a><span class="lineno"> 575</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a69dc7e97875060213085ba964b3bd987">raw_quat_I</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00576" name="l00576"></a><span class="lineno"> 576</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a61ae05dc5572b326541bf8099f0c2a54">raw_quat_J</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00577" name="l00577"></a><span class="lineno"> 577</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a7720c44ed1c0f1a0663d2adc5e1a1ea1">raw_quat_K</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00578" name="l00578"></a><span class="lineno"> 578</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a867354267253ae828be4fae15c062db3">raw_quat_real</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00579" name="l00579"></a><span class="lineno"> 579</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a033d6cb1aa137743b69cc3e401df67b7">raw_quat_radian_accuracy</a> = <span class="keyword">static_cast<</span>uint16_t<span class="keyword">></span>(<a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">BNO08xAccuracy::UNDEFINED</a>);</div>
|
|
||||||
<div class="line"><a id="l00580" name="l00580"></a><span class="lineno"> 580</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a36223f7124751fa71e860b2ef55dd2ac">quat_accuracy</a> = <span class="keyword">static_cast<</span>uint16_t<span class="keyword">></span>(<a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">BNO08xAccuracy::UNDEFINED</a>);</div>
|
|
||||||
<div class="line"><a id="l00581" name="l00581"></a><span class="lineno"> 581</span> </div>
|
|
||||||
<div class="line"><a id="l00582" name="l00582"></a><span class="lineno"> 582</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a6537ed69245cf71cad6a6a44480dddaa">integrated_gyro_velocity_X</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00583" name="l00583"></a><span class="lineno"> 583</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a00b39e22ea9fe306e88aaed490ee0a51">integrated_gyro_velocity_Y</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00584" name="l00584"></a><span class="lineno"> 584</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#ad112beb64badd22a2e1d717e1ee921c8">integrated_gyro_velocity_Z</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00585" name="l00585"></a><span class="lineno"> 585</span> </div>
|
|
||||||
<div class="line"><a id="l00586" name="l00586"></a><span class="lineno"> 586</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#af45016be9ea523d80be8467b2907b499">gravity_X</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00587" name="l00587"></a><span class="lineno"> 587</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#af20dcd487a9fe8fa6243817d51e37be5">gravity_Y</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00588" name="l00588"></a><span class="lineno"> 588</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#afa1cf5c3afbb258d97c55c5fb187f2d6">gravity_Z</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00589" name="l00589"></a><span class="lineno"> 589</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#ae01698d287ea999179a11e2244902022">gravity_accuracy</a> = <span class="keyword">static_cast<</span>uint16_t<span class="keyword">></span>(<a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">BNO08xAccuracy::UNDEFINED</a>);</div>
|
|
||||||
<div class="line"><a id="l00590" name="l00590"></a><span class="lineno"> 590</span> </div>
|
|
||||||
<div class="line"><a id="l00591" name="l00591"></a><span class="lineno"> 591</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#afdc5cdb65bd0b36528b5b671b9d27053">raw_uncalib_gyro_X</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00592" name="l00592"></a><span class="lineno"> 592</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#acc2c66e2985975266a286385ea855117">raw_uncalib_gyro_Y</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00593" name="l00593"></a><span class="lineno"> 593</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#afac9dd4161f4c0051255293680c9082b">raw_uncalib_gyro_Z</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00594" name="l00594"></a><span class="lineno"> 594</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a8a2667f668317cee0a9fc4ef0accc3f5">raw_bias_X</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00595" name="l00595"></a><span class="lineno"> 595</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#ac38ff5eb93d3c3db0af2504ba02fd93c">raw_bias_Y</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00596" name="l00596"></a><span class="lineno"> 596</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a0968eaed9b3d979a2caa1aba6e6b417a">raw_bias_Z</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00597" name="l00597"></a><span class="lineno"> 597</span> </div>
|
|
||||||
<div class="line"><a id="l00598" name="l00598"></a><span class="lineno"> 598</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#aa5bdf740161b7c37adcac0154a410118">raw_magf_X</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00599" name="l00599"></a><span class="lineno"> 599</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#acd365418f24a6da61122c66d82086639">raw_magf_Y</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00600" name="l00600"></a><span class="lineno"> 600</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#ab4862de31d0874b44b6745678e1c905e">raw_magf_Z</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00601" name="l00601"></a><span class="lineno"> 601</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#ac5d4e151690774687efa951ca41c16ae">magf_accuracy</a> = <span class="keyword">static_cast<</span>uint16_t<span class="keyword">></span>(<a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">BNO08xAccuracy::UNDEFINED</a>);</div>
|
|
||||||
<div class="line"><a id="l00602" name="l00602"></a><span class="lineno"> 602</span> </div>
|
|
||||||
<div class="line"><a id="l00603" name="l00603"></a><span class="lineno"> 603</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a1171a5738a4e6831ec7fa32a29f15554">tap_detector</a> = TEST_VAL_UINT8;</div>
|
|
||||||
<div class="line"><a id="l00604" name="l00604"></a><span class="lineno"> 604</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#ad80a77973371b12d722ea39063c648be">step_count</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00605" name="l00605"></a><span class="lineno"> 605</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a1b12471e92536a79d0c425d77676f2e1">stability_classifier</a> = <span class="keyword">static_cast<</span>uint16_t<span class="keyword">></span>(<a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3">BNO08xStability::UNDEFINED</a>);</div>
|
|
||||||
<div class="line"><a id="l00606" name="l00606"></a><span class="lineno"> 606</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a75cea49c1c08ca28d9fa7e5ed61c6e7b">activity_classifier</a> = <span class="keyword">static_cast<</span>uint16_t<span class="keyword">></span>(<a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3">BNO08xActivity::UNDEFINED</a>);</div>
|
|
||||||
<div class="line"><a id="l00607" name="l00607"></a><span class="lineno"> 607</span> </div>
|
|
||||||
<div class="line"><a id="l00608" name="l00608"></a><span class="lineno"> 608</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a937cbdc4edaac72c8cad041d79de5701">mems_raw_accel_X</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00609" name="l00609"></a><span class="lineno"> 609</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#ad83cecb8a5d2be01db6792755b6057e9">mems_raw_accel_Y</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00610" name="l00610"></a><span class="lineno"> 610</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a59a4d75f1302ab693b1b26e9ccaa5341">mems_raw_accel_Z</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00611" name="l00611"></a><span class="lineno"> 611</span> </div>
|
|
||||||
<div class="line"><a id="l00612" name="l00612"></a><span class="lineno"> 612</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a3d6b6257462951ea023af7076c80f6dd">mems_raw_gyro_X</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00613" name="l00613"></a><span class="lineno"> 613</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#ab6b142416912a096886dd63ad0beb865">mems_raw_gyro_Y</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00614" name="l00614"></a><span class="lineno"> 614</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#ac35d5b12721ab876eaeb1f714a9b3b1d">mems_raw_gyro_Z</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00615" name="l00615"></a><span class="lineno"> 615</span> </div>
|
|
||||||
<div class="line"><a id="l00616" name="l00616"></a><span class="lineno"> 616</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#ab587cdf991342b69b7fff3b33f537eb5">mems_raw_magf_X</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00617" name="l00617"></a><span class="lineno"> 617</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#aad926054c81818fff611e10ed913706a">mems_raw_magf_Y</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00618" name="l00618"></a><span class="lineno"> 618</span> <a class="code hl_variable" href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">test_imu</a>-><a class="code hl_variable" href="class_b_n_o08x.html#a90f0cdf11decc276006f76a494d42ce3">mems_raw_magf_Z</a> = TEST_VAL_UINT16;</div>
|
|
||||||
<div class="line"><a id="l00619" name="l00619"></a><span class="lineno"> 619</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00620" name="l00620"></a><span class="lineno"> 620</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00628" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00628" name="l00628"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3"> 628</a></span> <span class="keyword">static</span> <span class="keyword">const</span> <span class="keywordtype">char</span>* <a class="code hl_function" href="class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3">BNO08xAccuracy_to_str</a>(<a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a> accuracy)</div>
|
|
||||||
<div class="line"><a id="l00629" name="l00629"></a><span class="lineno"> 629</span> {</div>
|
|
||||||
<div class="line"><a id="l00630" name="l00630"></a><span class="lineno"> 630</span> <span class="keywordflow">switch</span> (accuracy)</div>
|
|
||||||
<div class="line"><a id="l00631" name="l00631"></a><span class="lineno"> 631</span> {</div>
|
|
||||||
<div class="line"><a id="l00632" name="l00632"></a><span class="lineno"> 632</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88">BNO08xAccuracy::LOW</a>:</div>
|
|
||||||
<div class="line"><a id="l00633" name="l00633"></a><span class="lineno"> 633</span> <span class="keywordflow">return</span> <span class="stringliteral">"LOW"</span>;</div>
|
|
||||||
<div class="line"><a id="l00634" name="l00634"></a><span class="lineno"> 634</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c">BNO08xAccuracy::MED</a>:</div>
|
|
||||||
<div class="line"><a id="l00635" name="l00635"></a><span class="lineno"> 635</span> <span class="keywordflow">return</span> <span class="stringliteral">"MED"</span>;</div>
|
|
||||||
<div class="line"><a id="l00636" name="l00636"></a><span class="lineno"> 636</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c">BNO08xAccuracy::HIGH</a>:</div>
|
|
||||||
<div class="line"><a id="l00637" name="l00637"></a><span class="lineno"> 637</span> <span class="keywordflow">return</span> <span class="stringliteral">"HIGH"</span>;</div>
|
|
||||||
<div class="line"><a id="l00638" name="l00638"></a><span class="lineno"> 638</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">BNO08xAccuracy::UNDEFINED</a>:</div>
|
|
||||||
<div class="line"><a id="l00639" name="l00639"></a><span class="lineno"> 639</span> <span class="keywordflow">return</span> <span class="stringliteral">"UNDEFINED"</span>;</div>
|
|
||||||
<div class="line"><a id="l00640" name="l00640"></a><span class="lineno"> 640</span> <span class="keywordflow">default</span>:</div>
|
|
||||||
<div class="line"><a id="l00641" name="l00641"></a><span class="lineno"> 641</span> <span class="keywordflow">return</span> <span class="stringliteral">"INVALID"</span>;</div>
|
|
||||||
<div class="line"><a id="l00642" name="l00642"></a><span class="lineno"> 642</span> }</div>
|
|
||||||
<div class="line"><a id="l00643" name="l00643"></a><span class="lineno"> 643</span> };</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00644" name="l00644"></a><span class="lineno"> 644</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00652" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00652" name="l00652"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#ae922f36719ab085550ef270d5a149059"> 652</a></span> <span class="keyword">static</span> <span class="keyword">const</span> <span class="keywordtype">char</span>* <a class="code hl_function" href="class_b_n_o08x_test_helper.html#ae922f36719ab085550ef270d5a149059">BNO08xStability_to_str</a>(<a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5">BNO08xStability</a> stability)</div>
|
|
||||||
<div class="line"><a id="l00653" name="l00653"></a><span class="lineno"> 653</span> {</div>
|
|
||||||
<div class="line"><a id="l00654" name="l00654"></a><span class="lineno"> 654</span> <span class="keywordflow">switch</span> (stability)</div>
|
|
||||||
<div class="line"><a id="l00655" name="l00655"></a><span class="lineno"> 655</span> {</div>
|
|
||||||
<div class="line"><a id="l00656" name="l00656"></a><span class="lineno"> 656</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3">BNO08xStability::UNKNOWN</a>:</div>
|
|
||||||
<div class="line"><a id="l00657" name="l00657"></a><span class="lineno"> 657</span> <span class="keywordflow">return</span> <span class="stringliteral">"UNKNOWN"</span>;</div>
|
|
||||||
<div class="line"><a id="l00658" name="l00658"></a><span class="lineno"> 658</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a">BNO08xStability::ON_TABLE</a>:</div>
|
|
||||||
<div class="line"><a id="l00659" name="l00659"></a><span class="lineno"> 659</span> <span class="keywordflow">return</span> <span class="stringliteral">"ON TABLE"</span>;</div>
|
|
||||||
<div class="line"><a id="l00660" name="l00660"></a><span class="lineno"> 660</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146">BNO08xStability::STATIONARY</a>:</div>
|
|
||||||
<div class="line"><a id="l00661" name="l00661"></a><span class="lineno"> 661</span> <span class="keywordflow">return</span> <span class="stringliteral">"STATIONARY"</span>;</div>
|
|
||||||
<div class="line"><a id="l00662" name="l00662"></a><span class="lineno"> 662</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3">BNO08xStability::UNDEFINED</a>:</div>
|
|
||||||
<div class="line"><a id="l00663" name="l00663"></a><span class="lineno"> 663</span> <span class="keywordflow">return</span> <span class="stringliteral">"UNDEFINED"</span>;</div>
|
|
||||||
<div class="line"><a id="l00664" name="l00664"></a><span class="lineno"> 664</span> <span class="keywordflow">default</span>:</div>
|
|
||||||
<div class="line"><a id="l00665" name="l00665"></a><span class="lineno"> 665</span> <span class="keywordflow">return</span> <span class="stringliteral">"INVALID"</span>;</div>
|
|
||||||
<div class="line"><a id="l00666" name="l00666"></a><span class="lineno"> 666</span> }</div>
|
|
||||||
<div class="line"><a id="l00667" name="l00667"></a><span class="lineno"> 667</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00668" name="l00668"></a><span class="lineno"> 668</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00676" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00676" name="l00676"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_helper.html#ac95ba2892d54e6219123ad3ca0104750"> 676</a></span> <span class="keyword">static</span> <span class="keyword">const</span> <span class="keywordtype">char</span>* <a class="code hl_function" href="class_b_n_o08x_test_helper.html#ac95ba2892d54e6219123ad3ca0104750">BNO08xActivity_to_str</a>(<a class="code hl_enumeration" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187">BNO08xActivity</a> activity)</div>
|
|
||||||
<div class="line"><a id="l00677" name="l00677"></a><span class="lineno"> 677</span> {</div>
|
|
||||||
<div class="line"><a id="l00678" name="l00678"></a><span class="lineno"> 678</span> <span class="keywordflow">switch</span> (activity)</div>
|
|
||||||
<div class="line"><a id="l00679" name="l00679"></a><span class="lineno"> 679</span> {</div>
|
|
||||||
<div class="line"><a id="l00680" name="l00680"></a><span class="lineno"> 680</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3">BNO08xActivity::UNKNOWN</a>:</div>
|
|
||||||
<div class="line"><a id="l00681" name="l00681"></a><span class="lineno"> 681</span> <span class="keywordflow">return</span> <span class="stringliteral">"UNKNOWN"</span>;</div>
|
|
||||||
<div class="line"><a id="l00682" name="l00682"></a><span class="lineno"> 682</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4">BNO08xActivity::IN_VEHICLE</a>:</div>
|
|
||||||
<div class="line"><a id="l00683" name="l00683"></a><span class="lineno"> 683</span> <span class="keywordflow">return</span> <span class="stringliteral">"IN VEHICLE"</span>;</div>
|
|
||||||
<div class="line"><a id="l00684" name="l00684"></a><span class="lineno"> 684</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4">BNO08xActivity::ON_BICYCLE</a>:</div>
|
|
||||||
<div class="line"><a id="l00685" name="l00685"></a><span class="lineno"> 685</span> <span class="keywordflow">return</span> <span class="stringliteral">"ON BICYCLE"</span>;</div>
|
|
||||||
<div class="line"><a id="l00686" name="l00686"></a><span class="lineno"> 686</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58">BNO08xActivity::ON_FOOT</a>:</div>
|
|
||||||
<div class="line"><a id="l00687" name="l00687"></a><span class="lineno"> 687</span> <span class="keywordflow">return</span> <span class="stringliteral">"ON FOOT"</span>;</div>
|
|
||||||
<div class="line"><a id="l00688" name="l00688"></a><span class="lineno"> 688</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6">BNO08xActivity::STILL</a>:</div>
|
|
||||||
<div class="line"><a id="l00689" name="l00689"></a><span class="lineno"> 689</span> <span class="keywordflow">return</span> <span class="stringliteral">"STILL"</span>;</div>
|
|
||||||
<div class="line"><a id="l00690" name="l00690"></a><span class="lineno"> 690</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c">BNO08xActivity::TILTING</a>:</div>
|
|
||||||
<div class="line"><a id="l00691" name="l00691"></a><span class="lineno"> 691</span> <span class="keywordflow">return</span> <span class="stringliteral">"TILTING"</span>;</div>
|
|
||||||
<div class="line"><a id="l00692" name="l00692"></a><span class="lineno"> 692</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3">BNO08xActivity::WALKING</a>:</div>
|
|
||||||
<div class="line"><a id="l00693" name="l00693"></a><span class="lineno"> 693</span> <span class="keywordflow">return</span> <span class="stringliteral">"WALKING"</span>;</div>
|
|
||||||
<div class="line"><a id="l00694" name="l00694"></a><span class="lineno"> 694</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd">BNO08xActivity::RUNNING</a>:</div>
|
|
||||||
<div class="line"><a id="l00695" name="l00695"></a><span class="lineno"> 695</span> <span class="keywordflow">return</span> <span class="stringliteral">"RUNNING"</span>;</div>
|
|
||||||
<div class="line"><a id="l00696" name="l00696"></a><span class="lineno"> 696</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515">BNO08xActivity::ON_STAIRS</a>:</div>
|
|
||||||
<div class="line"><a id="l00697" name="l00697"></a><span class="lineno"> 697</span> <span class="keywordflow">return</span> <span class="stringliteral">"ON STAIRS"</span>;</div>
|
|
||||||
<div class="line"><a id="l00698" name="l00698"></a><span class="lineno"> 698</span> <span class="keywordflow">case</span> <a class="code hl_enumvalue" href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3">BNO08xActivity::UNDEFINED</a>:</div>
|
|
||||||
<div class="line"><a id="l00699" name="l00699"></a><span class="lineno"> 699</span> <span class="keywordflow">return</span> <span class="stringliteral">"UNDEFINED"</span>;</div>
|
|
||||||
<div class="line"><a id="l00700" name="l00700"></a><span class="lineno"> 700</span> <span class="keywordflow">default</span>:</div>
|
|
||||||
<div class="line"><a id="l00701" name="l00701"></a><span class="lineno"> 701</span> <span class="keywordflow">return</span> <span class="stringliteral">"INVALID"</span>;</div>
|
|
||||||
<div class="line"><a id="l00702" name="l00702"></a><span class="lineno"> 702</span> }</div>
|
|
||||||
<div class="line"><a id="l00703" name="l00703"></a><span class="lineno"> 703</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00704" name="l00704"></a><span class="lineno"> 704</span>};</div>
|
|
||||||
</div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x_8hpp_html"><div class="ttname"><a href="_b_n_o08x_8hpp.html">BNO08x.hpp</a></div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_a498b35f9e00b24e51f8f60b029751ab5"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5">BNO08xStability</a></div><div class="ttdeci">BNO08xStability</div><div class="ttdoc">BNO08xStability states returned from get_stability_classifier()</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:65</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a0db45d2a4141101bdfe48e3314cfbca3">BNO08xStability::UNDEFINED</a></div><div class="ttdeci">@ UNDEFINED</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a4120eb7591bd0789af75a8973d5f9146">BNO08xStability::STATIONARY</a></div><div class="ttdeci">@ STATIONARY</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a696b031073e74bf2cb98e5ef201d4aa3">BNO08xStability::UNKNOWN</a></div><div class="ttdeci">@ UNKNOWN</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#a498b35f9e00b24e51f8f60b029751ab5a71149a62cd9fec4756e3538d1754486a">BNO08xStability::ON_TABLE</a></div><div class="ttdeci">@ ON_TABLE</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_abcc5d57e21ea6ed79e792deafcb62187"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187">BNO08xActivity</a></div><div class="ttdeci">BNO08xActivity</div><div class="ttdoc">BNO08xActivity states returned from get_activity_classifier()</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:50</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a0db45d2a4141101bdfe48e3314cfbca3">BNO08xActivity::UNDEFINED</a></div><div class="ttdeci">@ UNDEFINED</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a43491564ebcfd38568918efbd6e840fd">BNO08xActivity::RUNNING</a></div><div class="ttdeci">@ RUNNING</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a606c114184493a665cf1f6a12fbab9d3">BNO08xActivity::WALKING</a></div><div class="ttdeci">@ WALKING</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a696b031073e74bf2cb98e5ef201d4aa3">BNO08xActivity::UNKNOWN</a></div><div class="ttdeci">@ UNKNOWN</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a69909b62e08f212da31719aebf67b70c">BNO08xActivity::TILTING</a></div><div class="ttdeci">@ TILTING</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a7089542e0146a3499986c81e24924b58">BNO08xActivity::ON_FOOT</a></div><div class="ttdeci">@ ON_FOOT</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a8b572d218013b9626d59e6a2b38f18b6">BNO08xActivity::STILL</a></div><div class="ttdeci">@ STILL</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187a93d94a2f3a627533453a40e302fb35a4">BNO08xActivity::ON_BICYCLE</a></div><div class="ttdeci">@ ON_BICYCLE</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187ab166a3ce74dd5434e4a940dfa2af76e4">BNO08xActivity::IN_VEHICLE</a></div><div class="ttdeci">@ IN_VEHICLE</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#abcc5d57e21ea6ed79e792deafcb62187abbf2a614429826a84bd76b4a47fc7515">BNO08xActivity::ON_STAIRS</a></div><div class="ttdeci">@ ON_STAIRS</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_aed7bab8e55be415938e078ebe72562a0"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0">BNO08xAccuracy</a></div><div class="ttdeci">BNO08xAccuracy</div><div class="ttdoc">Sensor accuracy returned during sensor calibration.</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:13</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a0db45d2a4141101bdfe48e3314cfbca3">BNO08xAccuracy::UNDEFINED</a></div><div class="ttdeci">@ UNDEFINED</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a2ad6d5975c45da2e711c796f3a1b029c">BNO08xAccuracy::MED</a></div><div class="ttdeci">@ MED</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0a41bc94cbd8eebea13ce0491b2ac11b88">BNO08xAccuracy::LOW</a></div><div class="ttdeci">@ LOW</div></div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x__global__types_8hpp_html_aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c"><div class="ttname"><a href="_b_n_o08x__global__types_8hpp.html#aed7bab8e55be415938e078ebe72562a0ab89de3b4b81c4facfac906edf29aec8c">BNO08xAccuracy::HIGH</a></div><div class="ttdeci">@ HIGH</div></div>
|
|
||||||
<div class="ttc" id="a_callback_tests_8cpp_html_a22334b11e0558ec663d040de9b7db8c9"><div class="ttname"><a href="_callback_tests_8cpp.html#a22334b11e0558ec663d040de9b7db8c9">report_data</a></div><div class="ttdeci">BNO08xTestHelper::imu_report_data_t report_data</div><div class="ttdef"><b>Definition</b> CallbackTests.cpp:21</div></div>
|
|
||||||
<div class="ttc" id="a_callback_tests_8cpp_html_a5a4ba60143c31271df0f72bf0e503876"><div class="ttname"><a href="_callback_tests_8cpp.html#a5a4ba60143c31271df0f72bf0e503876">new_data</a></div><div class="ttdeci">bool new_data</div><div class="ttdef"><b>Definition</b> CallbackTests.cpp:25</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html"><div class="ttname"><a href="class_b_n_o08x.html">BNO08x</a></div><div class="ttdoc">BNO08x IMU driver class.</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:34</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a00b39e22ea9fe306e88aaed490ee0a51"><div class="ttname"><a href="class_b_n_o08x.html#a00b39e22ea9fe306e88aaed490ee0a51">BNO08x::integrated_gyro_velocity_Y</a></div><div class="ttdeci">uint16_t integrated_gyro_velocity_Y</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:399</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a033d6cb1aa137743b69cc3e401df67b7"><div class="ttname"><a href="class_b_n_o08x.html#a033d6cb1aa137743b69cc3e401df67b7">BNO08x::raw_quat_radian_accuracy</a></div><div class="ttdeci">uint16_t raw_quat_radian_accuracy</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:397</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a067678914e928a6691625b17c40237a0"><div class="ttname"><a href="class_b_n_o08x.html#a067678914e928a6691625b17c40237a0">BNO08x::get_gravity</a></div><div class="ttdeci">void get_gravity(float &x, float &y, float &z, BNO08xAccuracy &accuracy)</div><div class="ttdoc">Get full reported gravity vector, units in m/s^2.</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:2806</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a06f99a6b2182b49a0e61e2107f2be6be"><div class="ttname"><a href="class_b_n_o08x.html#a06f99a6b2182b49a0e61e2107f2be6be">BNO08x::launch_tasks</a></div><div class="ttdeci">esp_err_t launch_tasks()</div><div class="ttdoc">Launches spi_task and data_proc_task on constructor call.</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:4003</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a0968eaed9b3d979a2caa1aba6e6b417a"><div class="ttname"><a href="class_b_n_o08x.html#a0968eaed9b3d979a2caa1aba6e6b417a">BNO08x::raw_bias_Z</a></div><div class="ttdeci">uint16_t raw_bias_Z</div><div class="ttdoc">Uncalibrated gyro reading (See SH-2 Ref. Manual 6.5.14)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:404</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a1171a5738a4e6831ec7fa32a29f15554"><div class="ttname"><a href="class_b_n_o08x.html#a1171a5738a4e6831ec7fa32a29f15554">BNO08x::tap_detector</a></div><div class="ttdeci">uint8_t tap_detector</div><div class="ttdoc">Tap detector reading (See SH-2 Ref. Manual 6.5.27)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:407</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a1b12471e92536a79d0c425d77676f2e1"><div class="ttname"><a href="class_b_n_o08x.html#a1b12471e92536a79d0c425d77676f2e1">BNO08x::stability_classifier</a></div><div class="ttdeci">uint8_t stability_classifier</div><div class="ttdoc">BNO08xStability status reading (See SH-2 Ref. Manual 6.5.31)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:409</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a248544b262582d10d917a687190cb454"><div class="ttname"><a href="class_b_n_o08x.html#a248544b262582d10d917a687190cb454">BNO08x::get_stability_classifier</a></div><div class="ttdeci">BNO08xStability get_stability_classifier()</div><div class="ttdoc">Get the current stability classifier (Seee Ref. Manual 6.5.31)</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:3508</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a3365b7ebde01e284274e655c60343df9"><div class="ttname"><a href="class_b_n_o08x.html#a3365b7ebde01e284274e655c60343df9">BNO08x::accel_accuracy</a></div><div class="ttdeci">uint16_t accel_accuracy</div><div class="ttdoc">Raw acceleration readings (See SH-2 Ref. Manual 6.5.8)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:393</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a35e1635ef5edde8fc8640f978c6f2e3c"><div class="ttname"><a href="class_b_n_o08x.html#a35e1635ef5edde8fc8640f978c6f2e3c">BNO08x::accel_lin_accuracy</a></div><div class="ttdeci">uint16_t accel_lin_accuracy</div><div class="ttdoc">Raw linear acceleration (See SH-2 Ref. Manual 6.5.10)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:395</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a36223f7124751fa71e860b2ef55dd2ac"><div class="ttname"><a href="class_b_n_o08x.html#a36223f7124751fa71e860b2ef55dd2ac">BNO08x::quat_accuracy</a></div><div class="ttdeci">uint16_t quat_accuracy</div><div class="ttdoc">Raw quaternion reading (See SH-2 Ref. Manual 6.5.44)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:398</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a3c9797a2a2be14ee6e8126f1295fa885"><div class="ttname"><a href="class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885">BNO08x::get_accel</a></div><div class="ttdeci">void get_accel(float &x, float &y, float &z, BNO08xAccuracy &accuracy)</div><div class="ttdoc">Get full acceleration (total acceleration of device, units in m/s^2).</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:3064</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a3d6b6257462951ea023af7076c80f6dd"><div class="ttname"><a href="class_b_n_o08x.html#a3d6b6257462951ea023af7076c80f6dd">BNO08x::mems_raw_gyro_X</a></div><div class="ttdeci">uint16_t mems_raw_gyro_X</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:415</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a4a72489c56960d83050ae9c4b9ab75ed"><div class="ttname"><a href="class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed">BNO08x::get_activity_classifier</a></div><div class="ttdeci">BNO08xActivity get_activity_classifier()</div><div class="ttdoc">Get the current activity classifier (Seee Ref. Manual 6.5.36)</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:3527</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a4bef64b34cbff3922848c7a93aa21e46"><div class="ttname"><a href="class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46">BNO08x::get_linear_accel</a></div><div class="ttdeci">void get_linear_accel(float &x, float &y, float &z, BNO08xAccuracy &accuracy)</div><div class="ttdoc">Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2).</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:3122</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a589eb9780f5bf613bbd447ef5b9ade3d"><div class="ttname"><a href="class_b_n_o08x.html#a589eb9780f5bf613bbd447ef5b9ade3d">BNO08x::init_config_args</a></div><div class="ttdeci">esp_err_t init_config_args()</div><div class="ttdoc">Initializes required esp-idf SPI data structures with values from user passed bno08x_config_t struct.</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:124</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a58f43c8bb1e7fe8560ce442d46240e81"><div class="ttname"><a href="class_b_n_o08x.html#a58f43c8bb1e7fe8560ce442d46240e81">BNO08x::init_spi</a></div><div class="ttdeci">esp_err_t init_spi()</div><div class="ttdoc">Initializes SPI.</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:372</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a59a4d75f1302ab693b1b26e9ccaa5341"><div class="ttname"><a href="class_b_n_o08x.html#a59a4d75f1302ab693b1b26e9ccaa5341">BNO08x::mems_raw_accel_Z</a></div><div class="ttdeci">uint16_t mems_raw_accel_Z</div><div class="ttdoc">Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.5.8)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:414</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a61ae05dc5572b326541bf8099f0c2a54"><div class="ttname"><a href="class_b_n_o08x.html#a61ae05dc5572b326541bf8099f0c2a54">BNO08x::raw_quat_J</a></div><div class="ttdeci">uint16_t raw_quat_J</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:397</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a6537ed69245cf71cad6a6a44480dddaa"><div class="ttname"><a href="class_b_n_o08x.html#a6537ed69245cf71cad6a6a44480dddaa">BNO08x::integrated_gyro_velocity_X</a></div><div class="ttdeci">uint16_t integrated_gyro_velocity_X</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:399</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a66c48af1d4162a9ec25c3a1c95660fe4"><div class="ttname"><a href="class_b_n_o08x.html#a66c48af1d4162a9ec25c3a1c95660fe4">BNO08x::raw_calib_gyro_Y</a></div><div class="ttdeci">uint16_t raw_calib_gyro_Y</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:396</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a69dc7e97875060213085ba964b3bd987"><div class="ttname"><a href="class_b_n_o08x.html#a69dc7e97875060213085ba964b3bd987">BNO08x::raw_quat_I</a></div><div class="ttdeci">uint16_t raw_quat_I</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:397</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a75cea49c1c08ca28d9fa7e5ed61c6e7b"><div class="ttname"><a href="class_b_n_o08x.html#a75cea49c1c08ca28d9fa7e5ed61c6e7b">BNO08x::activity_classifier</a></div><div class="ttdeci">uint8_t activity_classifier</div><div class="ttdoc">BNO08xActivity status reading (See SH-2 Ref. Manual 6.5.36)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:410</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a75fb2f06c5bbe26e3f3c794934ef954c"><div class="ttname"><a href="class_b_n_o08x.html#a75fb2f06c5bbe26e3f3c794934ef954c">BNO08x::raw_accel_X</a></div><div class="ttdeci">uint16_t raw_accel_X</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:392</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a7720c44ed1c0f1a0663d2adc5e1a1ea1"><div class="ttname"><a href="class_b_n_o08x.html#a7720c44ed1c0f1a0663d2adc5e1a1ea1">BNO08x::raw_quat_K</a></div><div class="ttdeci">uint16_t raw_quat_K</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:397</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a867354267253ae828be4fae15c062db3"><div class="ttname"><a href="class_b_n_o08x.html#a867354267253ae828be4fae15c062db3">BNO08x::raw_quat_real</a></div><div class="ttdeci">uint16_t raw_quat_real</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:397</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a86ff710f2b359e905c7154bfb7d5b104"><div class="ttname"><a href="class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104">BNO08x::get_uncalibrated_gyro_velocity</a></div><div class="ttdeci">void get_uncalibrated_gyro_velocity(float &x, float &y, float &z, float &bx, float &by, float &bz)</div><div class="ttdoc">Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv...</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:3367</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a87faca2c8c71ff46bf2e6ad4ba271b3a"><div class="ttname"><a href="class_b_n_o08x.html#a87faca2c8c71ff46bf2e6ad4ba271b3a">BNO08x::raw_calib_gyro_X</a></div><div class="ttdeci">uint16_t raw_calib_gyro_X</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:396</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a8a2667f668317cee0a9fc4ef0accc3f5"><div class="ttname"><a href="class_b_n_o08x.html#a8a2667f668317cee0a9fc4ef0accc3f5">BNO08x::raw_bias_X</a></div><div class="ttdeci">uint16_t raw_bias_X</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:403</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a8f4a10a8427a266fa28fc1c85c8e850f"><div class="ttname"><a href="class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f">BNO08x::get_integrated_gyro_velocity</a></div><div class="ttdeci">void get_integrated_gyro_velocity(float &x, float &y, float &z)</div><div class="ttdoc">Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5....</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:3446</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a90f0cdf11decc276006f76a494d42ce3"><div class="ttname"><a href="class_b_n_o08x.html#a90f0cdf11decc276006f76a494d42ce3">BNO08x::mems_raw_magf_Z</a></div><div class="ttdeci">uint16_t mems_raw_magf_Z</div><div class="ttdoc">Raw magnetometer (compass) readings from MEMS sensor (See SH-2 Ref. Manual 6.5.15)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:418</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_a937cbdc4edaac72c8cad041d79de5701"><div class="ttname"><a href="class_b_n_o08x.html#a937cbdc4edaac72c8cad041d79de5701">BNO08x::mems_raw_accel_X</a></div><div class="ttdeci">uint16_t mems_raw_accel_X</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:413</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_aa27026da2c52b4aca49b78863f10ec61"><div class="ttname"><a href="class_b_n_o08x.html#aa27026da2c52b4aca49b78863f10ec61">BNO08x::init_hint_isr</a></div><div class="ttdeci">esp_err_t init_hint_isr()</div><div class="ttdoc">Initializes host interrupt ISR.</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:321</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_aa5bdf740161b7c37adcac0154a410118"><div class="ttname"><a href="class_b_n_o08x.html#aa5bdf740161b7c37adcac0154a410118">BNO08x::raw_magf_X</a></div><div class="ttdeci">uint16_t raw_magf_X</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:405</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_aa9291dec6c05a3786fe58221e6856e8f"><div class="ttname"><a href="class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f">BNO08x::get_calibrated_gyro_velocity</a></div><div class="ttdeci">void get_calibrated_gyro_velocity(float &x, float &y, float &z)</div><div class="ttdoc">Get full rotational velocity with drift compensation (units in Rad/s).</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:3317</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_aad926054c81818fff611e10ed913706a"><div class="ttname"><a href="class_b_n_o08x.html#aad926054c81818fff611e10ed913706a">BNO08x::mems_raw_magf_Y</a></div><div class="ttdeci">uint16_t mems_raw_magf_Y</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:417</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ab4862de31d0874b44b6745678e1c905e"><div class="ttname"><a href="class_b_n_o08x.html#ab4862de31d0874b44b6745678e1c905e">BNO08x::raw_magf_Z</a></div><div class="ttdeci">uint16_t raw_magf_Z</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:405</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ab56e2ba505fa293d03e955137625c562"><div class="ttname"><a href="class_b_n_o08x.html#ab56e2ba505fa293d03e955137625c562">BNO08x::raw_accel_Y</a></div><div class="ttdeci">uint16_t raw_accel_Y</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:392</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ab587cdf991342b69b7fff3b33f537eb5"><div class="ttname"><a href="class_b_n_o08x.html#ab587cdf991342b69b7fff3b33f537eb5">BNO08x::mems_raw_magf_X</a></div><div class="ttdeci">uint16_t mems_raw_magf_X</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:417</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ab6b142416912a096886dd63ad0beb865"><div class="ttname"><a href="class_b_n_o08x.html#ab6b142416912a096886dd63ad0beb865">BNO08x::mems_raw_gyro_Y</a></div><div class="ttdeci">uint16_t mems_raw_gyro_Y</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:415</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_abc8add47f1babc66c812a015614143d3"><div class="ttname"><a href="class_b_n_o08x.html#abc8add47f1babc66c812a015614143d3">BNO08x::raw_lin_accel_Z</a></div><div class="ttdeci">uint16_t raw_lin_accel_Z</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:394</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_abc972db20affbd0040b4e6c4892dd57b"><div class="ttname"><a href="class_b_n_o08x.html#abc972db20affbd0040b4e6c4892dd57b">BNO08x::time_stamp</a></div><div class="ttdeci">uint32_t time_stamp</div><div class="ttdoc">Report timestamp (see datasheet 1.3.5.3)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:391</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ac2118c4da6631d3b9806353ca2cbba27"><div class="ttname"><a href="class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27">BNO08x::get_raw_mems_gyro</a></div><div class="ttdeci">void get_raw_mems_gyro(uint16_t &x, uint16_t &y, uint16_t &z)</div><div class="ttdoc">Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6....</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:3225</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ac35d5b12721ab876eaeb1f714a9b3b1d"><div class="ttname"><a href="class_b_n_o08x.html#ac35d5b12721ab876eaeb1f714a9b3b1d">BNO08x::mems_raw_gyro_Z</a></div><div class="ttdeci">uint16_t mems_raw_gyro_Z</div><div class="ttdoc">Raw gyro readings from MEMS sensor (See SH-2 Ref. Manual 6.5.12)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:416</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ac38ff5eb93d3c3db0af2504ba02fd93c"><div class="ttname"><a href="class_b_n_o08x.html#ac38ff5eb93d3c3db0af2504ba02fd93c">BNO08x::raw_bias_Y</a></div><div class="ttdeci">uint16_t raw_bias_Y</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:403</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ac5d4e151690774687efa951ca41c16ae"><div class="ttname"><a href="class_b_n_o08x.html#ac5d4e151690774687efa951ca41c16ae">BNO08x::magf_accuracy</a></div><div class="ttdeci">uint16_t magf_accuracy</div><div class="ttdoc">Calibrated magnetic field reading in uTesla (See SH-2 Ref. Manual 6.5.16)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:406</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_acc2c66e2985975266a286385ea855117"><div class="ttname"><a href="class_b_n_o08x.html#acc2c66e2985975266a286385ea855117">BNO08x::raw_uncalib_gyro_Y</a></div><div class="ttdeci">uint16_t raw_uncalib_gyro_Y</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:403</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_acd365418f24a6da61122c66d82086639"><div class="ttname"><a href="class_b_n_o08x.html#acd365418f24a6da61122c66d82086639">BNO08x::raw_magf_Y</a></div><div class="ttdeci">uint16_t raw_magf_Y</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:405</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ad112beb64badd22a2e1d717e1ee921c8"><div class="ttname"><a href="class_b_n_o08x.html#ad112beb64badd22a2e1d717e1ee921c8">BNO08x::integrated_gyro_velocity_Z</a></div><div class="ttdeci">uint16_t integrated_gyro_velocity_Z</div><div class="ttdoc">Raw gyro angular velocity reading from integrated gyro rotation vector (See SH-2 Ref....</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:400</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ad80a77973371b12d722ea39063c648be"><div class="ttname"><a href="class_b_n_o08x.html#ad80a77973371b12d722ea39063c648be">BNO08x::step_count</a></div><div class="ttdeci">uint16_t step_count</div><div class="ttdoc">Step counter reading (See SH-2 Ref. Manual 6.5.29)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:408</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ad83cecb8a5d2be01db6792755b6057e9"><div class="ttname"><a href="class_b_n_o08x.html#ad83cecb8a5d2be01db6792755b6057e9">BNO08x::mems_raw_accel_Y</a></div><div class="ttdeci">uint16_t mems_raw_accel_Y</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:413</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_adaff49f3d80fdd19fd4210f0c56d41ef"><div class="ttname"><a href="class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef">BNO08x::get_step_count</a></div><div class="ttdeci">uint16_t get_step_count()</div><div class="ttdoc">Get the counted amount of steps.</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:3498</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ae01698d287ea999179a11e2244902022"><div class="ttname"><a href="class_b_n_o08x.html#ae01698d287ea999179a11e2244902022">BNO08x::gravity_accuracy</a></div><div class="ttdeci">uint16_t gravity_accuracy</div><div class="ttdoc">Gravity reading in m/s^2 (See SH-2 Ref. Manual 6.5.11)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:402</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ae0dab25557befcf62bf384fdc241ef10"><div class="ttname"><a href="class_b_n_o08x.html#ae0dab25557befcf62bf384fdc241ef10">BNO08x::init_gpio</a></div><div class="ttdeci">esp_err_t init_gpio()</div><div class="ttdoc">Initializes required gpio.</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:293</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ae1f71a432cb15e75f522fa18f29f4d50"><div class="ttname"><a href="class_b_n_o08x.html#ae1f71a432cb15e75f522fa18f29f4d50">BNO08x::raw_lin_accel_X</a></div><div class="ttdeci">uint16_t raw_lin_accel_X</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:394</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_ae766248440e76fb26bbadc6ee0b54ddb"><div class="ttname"><a href="class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb">BNO08x::get_magf</a></div><div class="ttdeci">void get_magf(float &x, float &y, float &z, BNO08xAccuracy &accuracy)</div><div class="ttdoc">Get the full magnetic field vector.</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:2745</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_af20dcd487a9fe8fa6243817d51e37be5"><div class="ttname"><a href="class_b_n_o08x.html#af20dcd487a9fe8fa6243817d51e37be5">BNO08x::gravity_Y</a></div><div class="ttdeci">uint16_t gravity_Y</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:401</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_af254d245b368027df6952b7d7522bd35"><div class="ttname"><a href="class_b_n_o08x.html#af254d245b368027df6952b7d7522bd35">BNO08x::raw_accel_Z</a></div><div class="ttdeci">uint16_t raw_accel_Z</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:392</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_af45016be9ea523d80be8467b2907b499"><div class="ttname"><a href="class_b_n_o08x.html#af45016be9ea523d80be8467b2907b499">BNO08x::gravity_X</a></div><div class="ttdeci">uint16_t gravity_X</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:401</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_af5450d1a9c20c2a5c62c960e3df11c0e"><div class="ttname"><a href="class_b_n_o08x.html#af5450d1a9c20c2a5c62c960e3df11c0e">BNO08x::raw_calib_gyro_Z</a></div><div class="ttdeci">uint16_t raw_calib_gyro_Z</div><div class="ttdoc">Raw gyro reading (See SH-2 Ref. Manual 6.5.13)</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:396</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_af5d6dae7c0f8d36b6ac91adff614ab3a"><div class="ttname"><a href="class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a">BNO08x::get_quat</a></div><div class="ttdeci">void get_quat(float &i, float &j, float &k, float &real, float &rad_accuracy, BNO08xAccuracy &accuracy)</div><div class="ttdoc">Get the full quaternion reading.</div><div class="ttdef"><b>Definition</b> BNO08x.cpp:2979</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_afa1cf5c3afbb258d97c55c5fb187f2d6"><div class="ttname"><a href="class_b_n_o08x.html#afa1cf5c3afbb258d97c55c5fb187f2d6">BNO08x::gravity_Z</a></div><div class="ttdeci">uint16_t gravity_Z</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:401</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_afac9dd4161f4c0051255293680c9082b"><div class="ttname"><a href="class_b_n_o08x.html#afac9dd4161f4c0051255293680c9082b">BNO08x::raw_uncalib_gyro_Z</a></div><div class="ttdeci">uint16_t raw_uncalib_gyro_Z</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:403</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_afdc5cdb65bd0b36528b5b671b9d27053"><div class="ttname"><a href="class_b_n_o08x.html#afdc5cdb65bd0b36528b5b671b9d27053">BNO08x::raw_uncalib_gyro_X</a></div><div class="ttdeci">uint16_t raw_uncalib_gyro_X</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:403</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_html_aff3a5590471d1c9fc485a5610433915f"><div class="ttname"><a href="class_b_n_o08x.html#aff3a5590471d1c9fc485a5610433915f">BNO08x::raw_lin_accel_Y</a></div><div class="ttdeci">uint16_t raw_lin_accel_Y</div><div class="ttdef"><b>Definition</b> BNO08x.hpp:394</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html"><div class="ttname"><a href="class_b_n_o08x_test_helper.html">BNO08xTestHelper</a></div><div class="ttdoc">BNO08x unit test helper class.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:16</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a008b268f705b9d2925230cb8193c9f28"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a008b268f705b9d2925230cb8193c9f28">BNO08xTestHelper::imu_cfg</a></div><div class="ttdeci">static bno08x_config_t imu_cfg</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:19</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a066f8389fd1c682ec9565ebc3060d885"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885">BNO08xTestHelper::print_test_start_banner</a></div><div class="ttdeci">static void print_test_start_banner(const char *TEST_TAG)</div><div class="ttdoc">Prints test begin banner.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:88</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a084e65ff5c0e2f429b39ebb53b0e03c9"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a084e65ff5c0e2f429b39ebb53b0e03c9">BNO08xTestHelper::calibrated_gyro_data_is_new</a></div><div class="ttdeci">static bool calibrated_gyro_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)</div><div class="ttdoc">Checks if report_data matches the default states stored within prev_report_data data for respective r...</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:343</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a0b3d9379e670b0c532ba76801cfb7580"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a0b3d9379e670b0c532ba76801cfb7580">BNO08xTestHelper::imu_report_data_t</a></div><div class="ttdeci">struct BNO08xTestHelper::imu_report_data_t imu_report_data_t</div><div class="ttdoc">IMU configuration settings passed into constructor.</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a157342da2def8b659d27ae4d24063cb5"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a157342da2def8b659d27ae4d24063cb5">BNO08xTestHelper::magnetometer_data_is_new</a></div><div class="ttdeci">static bool magnetometer_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)</div><div class="ttdoc">Checks if report_data matches the default states stored within prev_report_data data for respective r...</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:448</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a16423fc3250e88eb5392800022f82919"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919">BNO08xTestHelper::print_test_end_banner</a></div><div class="ttdeci">static void print_test_end_banner(const char *TEST_TAG)</div><div class="ttdoc">Prints end begin banner.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:100</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a2da34e5d5e353cd37fa458fcfe7cf243"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a2da34e5d5e353cd37fa458fcfe7cf243">BNO08xTestHelper::test_imu</a></div><div class="ttdeci">static BNO08x * test_imu</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:18</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a3c2514f3bad3f091de4646c5798f487a"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a3c2514f3bad3f091de4646c5798f487a">BNO08xTestHelper::gravity_data_is_new</a></div><div class="ttdeci">static bool gravity_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)</div><div class="ttdoc">Checks if report_data matches the default states stored within prev_report_data data for respective r...</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:421</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a41a432a3fe288e45b6ab139a00bd7d6b"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b">BNO08xTestHelper::get_test_imu</a></div><div class="ttdeci">static BNO08x * get_test_imu()</div><div class="ttdoc">Deletes test IMU calling deconstructor and releases heap allocated memory.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:162</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a504749533ccd91890d73440809d38161"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a504749533ccd91890d73440809d38161">BNO08xTestHelper::call_init_gpio</a></div><div class="ttdeci">static esp_err_t call_init_gpio()</div><div class="ttdoc">Used to call private BNO08x::init_gpio() member for tests.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:185</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a6bd040c7d670a9713f2ab8a8a3913518"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a6bd040c7d670a9713f2ab8a8a3913518">BNO08xTestHelper::create_test_imu</a></div><div class="ttdeci">static void create_test_imu()</div><div class="ttdoc">Calls BNO08x constructor and creates new test IMU on heap.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:135</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a71d9fd7d459a98a7e9089a8587a21f8d"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a71d9fd7d459a98a7e9089a8587a21f8d">BNO08xTestHelper::call_init_config_args</a></div><div class="ttdeci">static esp_err_t call_init_config_args()</div><div class="ttdoc">Used to call private BNO08x::init_config_args() member for tests.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:172</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a7d2d784da1e850dab41154b35d7cdab5"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a7d2d784da1e850dab41154b35d7cdab5">BNO08xTestHelper::call_init_spi</a></div><div class="ttdeci">static esp_err_t call_init_spi()</div><div class="ttdoc">Used to call private BNO08x::init_spi() member for tests.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:211</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a7fbfc48c0fff306ab81e2320bc171002"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002">BNO08xTestHelper::print_test_msg</a></div><div class="ttdeci">static void print_test_msg(const char *TEST_TAG, const char *msg)</div><div class="ttdoc">Prints a message during a test.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:113</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a836c928981ac85d34668c9b97af17a15"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a836c928981ac85d34668c9b97af17a15">BNO08xTestHelper::call_init_hint_isr</a></div><div class="ttdeci">static esp_err_t call_init_hint_isr()</div><div class="ttdoc">Used to call private BNO08x::init_hint_isr() member for tests.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:198</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a857b66c12c231af0d546c026ec017ab3"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3">BNO08xTestHelper::BNO08xAccuracy_to_str</a></div><div class="ttdeci">static const char * BNO08xAccuracy_to_str(BNO08xAccuracy accuracy)</div><div class="ttdoc">Converts BNO08xAccuracy enum class object to string.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:628</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a95ed21657224358877a66d010eeefad3"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a95ed21657224358877a66d010eeefad3">BNO08xTestHelper::stability_classifier_data_is_new</a></div><div class="ttdeci">static bool stability_classifier_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)</div><div class="ttdoc">Checks if report_data matches the default states stored within prev_report_data data for respective r...</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:493</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_a9e2f9bf13f28f1a6ba87e86bc5947cf1"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#a9e2f9bf13f28f1a6ba87e86bc5947cf1">BNO08xTestHelper::set_test_imu_cfg</a></div><div class="ttdeci">static void set_test_imu_cfg(bno08x_config_t cfg)</div><div class="ttdoc">Set test imu configuration used with create_test_imu()</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:125</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_aa09d388a5da3a925ac25125b9c5c3a90"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#aa09d388a5da3a925ac25125b9c5c3a90">BNO08xTestHelper::TAG</a></div><div class="ttdeci">static const constexpr char * TAG</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:21</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_aa7eb152d4192c3949bb3443ef6221782"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#aa7eb152d4192c3949bb3443ef6221782">BNO08xTestHelper::step_counter_data_is_new</a></div><div class="ttdeci">static bool step_counter_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)</div><div class="ttdoc">Checks if report_data matches the default states stored within prev_report_data data for respective r...</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:475</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_ac5b0ac4c70bbfcba9f2e8f353b35f9f6"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#ac5b0ac4c70bbfcba9f2e8f353b35f9f6">BNO08xTestHelper::gyro_integrated_rotation_vector_data_is_new</a></div><div class="ttdeci">static bool gyro_integrated_rotation_vector_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)</div><div class="ttdoc">Checks if report_data matches the default states stored within prev_report_data data for respective r...</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:274</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_ac81c63583b19e5c7b3233324aaea98e2"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2">BNO08xTestHelper::update_report_data</a></div><div class="ttdeci">static void update_report_data(imu_report_data_t *report_data)</div><div class="ttdoc">Updates report data with calls relevant test_imu methods.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:528</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_ac95ba2892d54e6219123ad3ca0104750"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#ac95ba2892d54e6219123ad3ca0104750">BNO08xTestHelper::BNO08xActivity_to_str</a></div><div class="ttdeci">static const char * BNO08xActivity_to_str(BNO08xActivity activity)</div><div class="ttdoc">Converts BNO08xActivity enum class object to string.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:676</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_ad398739ce46400c1ac35e1cf7603d590"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#ad398739ce46400c1ac35e1cf7603d590">BNO08xTestHelper::linear_accelerometer_data_is_new</a></div><div class="ttdeci">static bool linear_accelerometer_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)</div><div class="ttdoc">Checks if report_data matches the default states stored within prev_report_data data for respective r...</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:394</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_adb5952b2b96b553024b6a841e30adad2"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#adb5952b2b96b553024b6a841e30adad2">BNO08xTestHelper::uncalibrated_gyro_data_is_new</a></div><div class="ttdeci">static bool uncalibrated_gyro_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)</div><div class="ttdoc">Checks if report_data matches the default states stored within prev_report_data data for respective r...</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:310</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_ade6be1fd8ef3a99e0edae4cbf25eb528"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#ade6be1fd8ef3a99e0edae4cbf25eb528">BNO08xTestHelper::reset_all_imu_data_to_test_defaults</a></div><div class="ttdeci">static void reset_all_imu_data_to_test_defaults()</div><div class="ttdoc">Resets internal test imu data with test defaults.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:554</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_ade97098806c8779b26f9c166c4b03eea"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea">BNO08xTestHelper::accelerometer_data_is_new</a></div><div class="ttdeci">static bool accelerometer_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)</div><div class="ttdoc">Checks if report_data matches the default states stored within prev_report_data data for respective r...</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:367</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_adf2488d1f7e3dec21a0d0c99417c181a"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#adf2488d1f7e3dec21a0d0c99417c181a">BNO08xTestHelper::call_launch_tasks</a></div><div class="ttdeci">static esp_err_t call_launch_tasks()</div><div class="ttdoc">Used to call private BNO08x::launch_tasks() member for tests.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:224</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_ae2d6df7dcfdbd106c2247803461bbc40"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40">BNO08xTestHelper::destroy_test_imu</a></div><div class="ttdeci">static void destroy_test_imu()</div><div class="ttdoc">Deletes test IMU calling deconstructor and releases heap allocated memory.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:148</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_ae922f36719ab085550ef270d5a149059"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#ae922f36719ab085550ef270d5a149059">BNO08xTestHelper::BNO08xStability_to_str</a></div><div class="ttdeci">static const char * BNO08xStability_to_str(BNO08xStability stability)</div><div class="ttdoc">Converts BNO08xStability enum class object to string.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:652</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_aeb8cd985faf8e403f62b60fced9cb2fd"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#aeb8cd985faf8e403f62b60fced9cb2fd">BNO08xTestHelper::rotation_vector_data_is_new</a></div><div class="ttdeci">static bool rotation_vector_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)</div><div class="ttdoc">Checks if report_data matches the default states stored within prev_report_data data for respective r...</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:240</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_helper_html_afc6cc734ad843aca30a7cb76ad6dedb9"><div class="ttname"><a href="class_b_n_o08x_test_helper.html#afc6cc734ad843aca30a7cb76ad6dedb9">BNO08xTestHelper::activity_classifier_data_is_new</a></div><div class="ttdeci">static bool activity_classifier_data_is_new(imu_report_data_t *report_data, imu_report_data_t *default_report_data)</div><div class="ttdoc">Checks if report_data matches the default states stored within prev_report_data data for respective r...</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:511</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">BNO08xTestHelper::imu_report_data_t</a></div><div class="ttdoc">IMU configuration settings passed into constructor.</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:26</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a0455033deba9570f248e8059cf6a3ce1"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0455033deba9570f248e8059cf6a3ce1">BNO08xTestHelper::imu_report_data_t::activity_classifier</a></div><div class="ttdeci">BNO08xActivity activity_classifier</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:77</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a077a94b4de0b5c280d69611325208cf7"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a077a94b4de0b5c280d69611325208cf7">BNO08xTestHelper::imu_report_data_t::integrated_gyro_vel_x</a></div><div class="ttdeci">float integrated_gyro_vel_x</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:36</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a0c962609a3bf7927204542521e9c5113"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0c962609a3bf7927204542521e9c5113">BNO08xTestHelper::imu_report_data_t::magf_accuracy</a></div><div class="ttdeci">BNO08xAccuracy magf_accuracy</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:69</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a0e72f6dde1411e4aa1c616cedcc556c1"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a0e72f6dde1411e4aa1c616cedcc556c1">BNO08xTestHelper::imu_report_data_t::magf_x</a></div><div class="ttdeci">float magf_x</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:66</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a19fc4af8a26c10a027cbd859d67dba4a"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a19fc4af8a26c10a027cbd859d67dba4a">BNO08xTestHelper::imu_report_data_t::grav_y</a></div><div class="ttdeci">float grav_y</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:51</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a1aa67da9c3c6449dfce361a528c418d3"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a1aa67da9c3c6449dfce361a528c418d3">BNO08xTestHelper::imu_report_data_t::integrated_gyro_vel_z</a></div><div class="ttdeci">float integrated_gyro_vel_z</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:38</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a20a09d197d5128aae64b7449df576c27"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a20a09d197d5128aae64b7449df576c27">BNO08xTestHelper::imu_report_data_t::quat_J</a></div><div class="ttdeci">float quat_J</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:30</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a27b52e2d96cb948c4257de4553053f72"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a27b52e2d96cb948c4257de4553053f72">BNO08xTestHelper::imu_report_data_t::uncalib_gyro_drift_z</a></div><div class="ttdeci">float uncalib_gyro_drift_z</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:64</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a292b1c36fed6a9c9742edf730299c4f4"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a292b1c36fed6a9c9742edf730299c4f4">BNO08xTestHelper::imu_report_data_t::uncalib_gyro_vel_x</a></div><div class="ttdeci">float uncalib_gyro_vel_x</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:59</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a29d5ae3e0ed3463cb9297f9cdc0e8472"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a29d5ae3e0ed3463cb9297f9cdc0e8472">BNO08xTestHelper::imu_report_data_t::uncalib_gyro_drift_y</a></div><div class="ttdeci">float uncalib_gyro_drift_y</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:63</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a3a62ed280657cd409d723e64f0c313b5"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3a62ed280657cd409d723e64f0c313b5">BNO08xTestHelper::imu_report_data_t::lin_accel_x</a></div><div class="ttdeci">float lin_accel_x</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:45</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a3c74d4c93fc4390f52b75e6ff2bea95b"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a3c74d4c93fc4390f52b75e6ff2bea95b">BNO08xTestHelper::imu_report_data_t::quat_K</a></div><div class="ttdeci">float quat_K</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:31</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a48a249994c27f59ca4167b56bdda311a"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a48a249994c27f59ca4167b56bdda311a">BNO08xTestHelper::imu_report_data_t::lin_accel_accuracy</a></div><div class="ttdeci">BNO08xAccuracy lin_accel_accuracy</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:48</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a55187ebe06fa77def93681bcdf62595c"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a55187ebe06fa77def93681bcdf62595c">BNO08xTestHelper::imu_report_data_t::magf_z</a></div><div class="ttdeci">float magf_z</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:68</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a553942aa784c35c833543ecc9a05f606"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a553942aa784c35c833543ecc9a05f606">BNO08xTestHelper::imu_report_data_t::lin_accel_y</a></div><div class="ttdeci">float lin_accel_y</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:46</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a5bf43fc0daf3a86954924e066cad3a9b"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5bf43fc0daf3a86954924e066cad3a9b">BNO08xTestHelper::imu_report_data_t::lin_accel_z</a></div><div class="ttdeci">float lin_accel_z</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:47</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a5c01b349cc9e4e45c78c576882d633fd"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a5c01b349cc9e4e45c78c576882d633fd">BNO08xTestHelper::imu_report_data_t::accel_x</a></div><div class="ttdeci">float accel_x</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:40</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a735d099f3dd0ead4b8d986fd139af43d"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a735d099f3dd0ead4b8d986fd139af43d">BNO08xTestHelper::imu_report_data_t::grav_accuracy</a></div><div class="ttdeci">BNO08xAccuracy grav_accuracy</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:53</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a769ddae74a6c89a2d319c28f95ed6479"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a769ddae74a6c89a2d319c28f95ed6479">BNO08xTestHelper::imu_report_data_t::calib_gyro_vel_z</a></div><div class="ttdeci">float calib_gyro_vel_z</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:57</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a7e594d0a1e86fb575f72c6f330c8983c"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e594d0a1e86fb575f72c6f330c8983c">BNO08xTestHelper::imu_report_data_t::accel_y</a></div><div class="ttdeci">float accel_y</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:41</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a7e9cd7e43d70932c5f84e3cfadf8bb47"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a7e9cd7e43d70932c5f84e3cfadf8bb47">BNO08xTestHelper::imu_report_data_t::raw_mems_gyro_y</a></div><div class="ttdeci">uint16_t raw_mems_gyro_y</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:72</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a80525c4943154f825a62539b10337976"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a80525c4943154f825a62539b10337976">BNO08xTestHelper::imu_report_data_t::quat_real</a></div><div class="ttdeci">float quat_real</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:32</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a86473c2bd8cbe2c76276393ee20d568b"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a86473c2bd8cbe2c76276393ee20d568b">BNO08xTestHelper::imu_report_data_t::stability_classifier</a></div><div class="ttdeci">BNO08xStability stability_classifier</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:76</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a8738f60a2b9bd49d2b8dd0487db7ac97"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8738f60a2b9bd49d2b8dd0487db7ac97">BNO08xTestHelper::imu_report_data_t::magf_y</a></div><div class="ttdeci">float magf_y</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:67</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a89b427579a281440ab94a340c0ec8443"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a89b427579a281440ab94a340c0ec8443">BNO08xTestHelper::imu_report_data_t::calib_gyro_vel_x</a></div><div class="ttdeci">float calib_gyro_vel_x</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:55</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a8d2c3cd33943cb1b4fd0e800f822607e"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a8d2c3cd33943cb1b4fd0e800f822607e">BNO08xTestHelper::imu_report_data_t::quat_I</a></div><div class="ttdeci">float quat_I</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:29</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a94befe7132d3a6a6ce2a7890e96ec091"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a94befe7132d3a6a6ce2a7890e96ec091">BNO08xTestHelper::imu_report_data_t::raw_mems_gyro_x</a></div><div class="ttdeci">uint16_t raw_mems_gyro_x</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:71</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_a9df84179bd44a7febfa1058afe3dad6c"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#a9df84179bd44a7febfa1058afe3dad6c">BNO08xTestHelper::imu_report_data_t::raw_mems_gyro_z</a></div><div class="ttdeci">uint16_t raw_mems_gyro_z</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:73</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_aac84ad10b65403ae1ee21dab5cdc77db"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#aac84ad10b65403ae1ee21dab5cdc77db">BNO08xTestHelper::imu_report_data_t::quat_accuracy</a></div><div class="ttdeci">BNO08xAccuracy quat_accuracy</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:34</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_ab39fd6f409288bb35fb1542ff4b9cbe4"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ab39fd6f409288bb35fb1542ff4b9cbe4">BNO08xTestHelper::imu_report_data_t::uncalib_gyro_vel_z</a></div><div class="ttdeci">float uncalib_gyro_vel_z</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:61</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_ac5d393de0f15176ba81bc63a80b49ca3"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac5d393de0f15176ba81bc63a80b49ca3">BNO08xTestHelper::imu_report_data_t::accel_accuracy</a></div><div class="ttdeci">BNO08xAccuracy accel_accuracy</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:43</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_ac70a65027c3e740eca2b1f172b7cefa3"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ac70a65027c3e740eca2b1f172b7cefa3">BNO08xTestHelper::imu_report_data_t::uncalib_gyro_drift_x</a></div><div class="ttdeci">float uncalib_gyro_drift_x</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:62</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_ad2c17ea111250ebc1a4a763dae3c072a"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ad2c17ea111250ebc1a4a763dae3c072a">BNO08xTestHelper::imu_report_data_t::grav_x</a></div><div class="ttdeci">float grav_x</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:50</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_adfd6bf2e2264cf25bd02814446600ab4"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#adfd6bf2e2264cf25bd02814446600ab4">BNO08xTestHelper::imu_report_data_t::uncalib_gyro_vel_y</a></div><div class="ttdeci">float uncalib_gyro_vel_y</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:60</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_ae0a8fef0227dd4304d08466c43d901a5"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae0a8fef0227dd4304d08466c43d901a5">BNO08xTestHelper::imu_report_data_t::quat_radian_accuracy</a></div><div class="ttdeci">float quat_radian_accuracy</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:33</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_ae5e8705ad014ed3f70e5de527cb2cb66"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae5e8705ad014ed3f70e5de527cb2cb66">BNO08xTestHelper::imu_report_data_t::time_stamp</a></div><div class="ttdeci">uint32_t time_stamp</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:27</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_ae8435a931eac7f4376a94acfcbf6a784"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#ae8435a931eac7f4376a94acfcbf6a784">BNO08xTestHelper::imu_report_data_t::step_count</a></div><div class="ttdeci">uint16_t step_count</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:75</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_af134cb789c29120033d81916e0c100d4"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af134cb789c29120033d81916e0c100d4">BNO08xTestHelper::imu_report_data_t::accel_z</a></div><div class="ttdeci">float accel_z</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:42</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_af1887bdfef4fc2c683fe2134cb5cfb50"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af1887bdfef4fc2c683fe2134cb5cfb50">BNO08xTestHelper::imu_report_data_t::grav_z</a></div><div class="ttdeci">float grav_z</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:52</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_af4b75b320bc390c90656905711f1c791"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af4b75b320bc390c90656905711f1c791">BNO08xTestHelper::imu_report_data_t::integrated_gyro_vel_y</a></div><div class="ttdeci">float integrated_gyro_vel_y</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:37</div></div>
|
|
||||||
<div class="ttc" id="astruct_b_n_o08x_test_helper_1_1imu__report__data__t_html_af9e11fd749123f5723b2e281c8d2fd16"><div class="ttname"><a href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html#af9e11fd749123f5723b2e281c8d2fd16">BNO08xTestHelper::imu_report_data_t::calib_gyro_vel_y</a></div><div class="ttdeci">float calib_gyro_vel_y</div><div class="ttdef"><b>Definition</b> BNO08xTestHelper.hpp:56</div></div>
|
|
||||||
<div class="ttc" id="astructbno08x__config__t_html"><div class="ttname"><a href="structbno08x__config__t.html">bno08x_config_t</a></div><div class="ttdoc">IMU configuration settings passed into constructor.</div><div class="ttdef"><b>Definition</b> BNO08x_global_types.hpp:74</div></div>
|
|
||||||
</div><!-- fragment --></div><!-- contents -->
|
|
||||||
</div><!-- doc-content -->
|
|
||||||
<!-- start footer part -->
|
|
||||||
<div id="nav-path" class="navpath"><!-- id is needed for treeview function! -->
|
|
||||||
<ul>
|
|
||||||
<li class="navelem"><a class="el" href="dir_85e9385bd83516731053aadc7da3c8af.html">imu_update</a></li><li class="navelem"><a class="el" href="dir_c60d9bf80716f90f729fd65c40ec81f7.html">bno08x_update</a></li><li class="navelem"><a class="el" href="dir_fd670e5d11b8bb731501003ff6578ae1.html">components</a></li><li class="navelem"><a class="el" href="dir_a6718ce9703adf4789a693642ffedf7f.html">esp32_BNO08x</a></li><li class="navelem"><a class="el" href="dir_9667f1a5b10a5222433e41df91e1bf5d.html">include</a></li><li class="navelem"><a class="el" href="_b_n_o08x_test_helper_8hpp.html">BNO08xTestHelper.hpp</a></li>
|
|
||||||
<li class="footer">Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.10.0 </li>
|
|
||||||
</ul>
|
|
||||||
</div>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
||||||
|
|
@ -1,182 +0,0 @@
|
||||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
|
||||||
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US">
|
|
||||||
<head>
|
|
||||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
|
||||||
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
|
|
||||||
<meta name="generator" content="Doxygen 1.10.0"/>
|
|
||||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
|
||||||
<title>esp32_BNO08x: BNO08xTestSuite.hpp File Reference</title>
|
|
||||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="jquery.js"></script>
|
|
||||||
<script type="text/javascript" src="dynsections.js"></script>
|
|
||||||
<script type="text/javascript" src="clipboard.js"></script>
|
|
||||||
<link href="navtree.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="resize.js"></script>
|
|
||||||
<script type="text/javascript" src="navtreedata.js"></script>
|
|
||||||
<script type="text/javascript" src="navtree.js"></script>
|
|
||||||
<script type="text/javascript" src="cookie.js"></script>
|
|
||||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
|
||||||
<script type="text/javascript" src="search/search.js"></script>
|
|
||||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
|
||||||
<div id="titlearea">
|
|
||||||
<table cellspacing="0" cellpadding="0">
|
|
||||||
<tbody>
|
|
||||||
<tr id="projectrow">
|
|
||||||
<td id="projectalign">
|
|
||||||
<div id="projectname">esp32_BNO08x<span id="projectnumber"> 1.2</span>
|
|
||||||
</div>
|
|
||||||
<div id="projectbrief">C++ BNO08x IMU driver component for esp-idf.</div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
</div>
|
|
||||||
<!-- end header part -->
|
|
||||||
<!-- Generated by Doxygen 1.10.0 -->
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
var searchBox = new SearchBox("searchBox", "search/",'.html');
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<script type="text/javascript" src="menudata.js"></script>
|
|
||||||
<script type="text/javascript" src="menu.js"></script>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() {
|
|
||||||
initMenu('',true,false,'search.php','Search');
|
|
||||||
$(function() { init_search(); });
|
|
||||||
});
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="main-nav"></div>
|
|
||||||
</div><!-- top -->
|
|
||||||
<div id="side-nav" class="ui-resizable side-nav-resizable">
|
|
||||||
<div id="nav-tree">
|
|
||||||
<div id="nav-tree-contents">
|
|
||||||
<div id="nav-sync" class="sync"></div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div id="splitbar" style="-moz-user-select:none;"
|
|
||||||
class="ui-resizable-handle">
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function(){initNavTree('_b_n_o08x_test_suite_8hpp.html',''); initResizable(); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="doc-content">
|
|
||||||
<!-- window showing the filter options -->
|
|
||||||
<div id="MSearchSelectWindow"
|
|
||||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
|
||||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
|
||||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<!-- iframe showing the search results (closed by default) -->
|
|
||||||
<div id="MSearchResultsWindow">
|
|
||||||
<div id="MSearchResults">
|
|
||||||
<div class="SRPage">
|
|
||||||
<div id="SRIndex">
|
|
||||||
<div id="SRResults"></div>
|
|
||||||
<div class="SRStatus" id="Loading">Loading...</div>
|
|
||||||
<div class="SRStatus" id="Searching">Searching...</div>
|
|
||||||
<div class="SRStatus" id="NoMatches">No Matches</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="header">
|
|
||||||
<div class="summary">
|
|
||||||
<a href="#nested-classes">Classes</a> </div>
|
|
||||||
<div class="headertitle"><div class="title">BNO08xTestSuite.hpp File Reference</div></div>
|
|
||||||
</div><!--header-->
|
|
||||||
<div class="contents">
|
|
||||||
<div class="textblock"><code>#include <stdio.h></code><br />
|
|
||||||
<code>#include <string.h></code><br />
|
|
||||||
<code>#include "unity.h"</code><br />
|
|
||||||
<code>#include "<a class="el" href="_b_n_o08x_test_helper_8hpp_source.html">BNO08xTestHelper.hpp</a>"</code><br />
|
|
||||||
</div><div class="textblock"><div class="dynheader">
|
|
||||||
Include dependency graph for BNO08xTestSuite.hpp:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_b_n_o08x_test_suite_8hpp__incl.png" border="0" usemap="#a_b_n_o08x_test_suite_8hpp" alt=""/></div>
|
|
||||||
<map name="a_b_n_o08x_test_suite_8hpp" id="a_b_n_o08x_test_suite_8hpp">
|
|
||||||
<area shape="rect" title=" " alt="" coords="72,5,223,32"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,229,66,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="120,35,89,54,63,81,48,114,40,150,36,214,31,214,34,149,43,113,59,79,86,50,117,30"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="73,80,137,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="142,34,122,68,118,65,138,31"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="161,80,222,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="157,31,178,65,174,68,153,34"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_test_helper_8hpp.html" title=" " alt="" coords="246,80,404,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="179,30,281,71,279,76,177,35"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="301,110,75,224,72,220,299,105"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_8hpp.html" title=" " alt="" coords="652,155,747,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="391,105,637,152,636,157,390,110"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,174,410,189,249,207,81,232,80,227,248,201,410,184,651,168"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="90,229,168,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="651,176,451,195,320,211,184,231,183,226,319,206,451,189,651,170"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="192,229,253,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,176,486,196,379,211,268,232,267,226,378,206,485,190,651,171"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="277,229,338,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,178,521,199,354,231,352,226,520,193,651,173"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="361,229,438,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,183,454,231,452,226,651,178"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="461,229,517,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="664,184,532,229,530,224,662,179"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="541,229,618,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="680,184,615,223,612,219,677,180"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="643,229,756,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="702,182,702,214,697,214,697,182"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="780,229,870,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="723,180,791,219,789,224,720,184"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="893,229,1034,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="746,179,904,222,902,227,745,184"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1058,229,1162,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,175,1043,226,1042,231,747,180"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1186,229,1341,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,173,1171,226,1170,232,747,178"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1365,229,1479,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,170,1001,189,1172,206,1350,226,1349,232,1172,211,1000,195,747,175"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1504,229,1626,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,169,1055,187,1268,204,1488,226,1488,232,1267,209,1055,192,747,174"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1650,229,1754,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,168,1112,182,1369,200,1635,226,1634,232,1368,205,1112,188,747,173"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x__global__types_8hpp.html" title=" " alt="" coords="1779,229,1954,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,168,1161,186,1456,203,1763,226,1763,232,1456,209,1160,192,747,174"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1681,304,1771,331"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1843,259,1766,299,1763,294,1841,254"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1796,304,1936,331"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1869,257,1869,288,1864,288,1864,257"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1961,304,2091,331"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1895,254,1986,295,1983,300,1893,259"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<p><a href="_b_n_o08x_test_suite_8hpp_source.html">Go to the source code of this file.</a></p>
|
|
||||||
<table class="memberdecls">
|
|
||||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a id="nested-classes" name="nested-classes"></a>
|
|
||||||
Classes</h2></td></tr>
|
|
||||||
<tr class="memitem:"><td class="memItemLeft" align="right" valign="top">class  </td><td class="memItemRight" valign="bottom"><a class="el" href="class_b_n_o08x_test_suite.html">BNO08xTestSuite</a></td></tr>
|
|
||||||
<tr class="memdesc:"><td class="mdescLeft"> </td><td class="mdescRight"><a class="el" href="class_b_n_o08x.html" title="BNO08x IMU driver class.">BNO08x</a> unit test launch point class. <a href="class_b_n_o08x_test_suite.html#details">More...</a><br /></td></tr>
|
|
||||||
<tr class="separator:"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
</table>
|
|
||||||
<a name="details" id="details"></a><h2 class="groupheader">Detailed Description</h2>
|
|
||||||
<div class="textblock"><dl class="section author"><dt>Author</dt><dd>Myles Parfeniuk</dd></dl>
|
|
||||||
<dl class="section warning"><dt>Warning</dt><dd>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.") </dd></dl>
|
|
||||||
</div></div><!-- contents -->
|
|
||||||
</div><!-- doc-content -->
|
|
||||||
<!-- start footer part -->
|
|
||||||
<div id="nav-path" class="navpath"><!-- id is needed for treeview function! -->
|
|
||||||
<ul>
|
|
||||||
<li class="navelem"><a class="el" href="dir_85e9385bd83516731053aadc7da3c8af.html">imu_update</a></li><li class="navelem"><a class="el" href="dir_c60d9bf80716f90f729fd65c40ec81f7.html">bno08x_update</a></li><li class="navelem"><a class="el" href="dir_fd670e5d11b8bb731501003ff6578ae1.html">components</a></li><li class="navelem"><a class="el" href="dir_a6718ce9703adf4789a693642ffedf7f.html">esp32_BNO08x</a></li><li class="navelem"><a class="el" href="dir_9667f1a5b10a5222433e41df91e1bf5d.html">include</a></li><li class="navelem"><a class="el" href="_b_n_o08x_test_suite_8hpp.html">BNO08xTestSuite.hpp</a></li>
|
|
||||||
<li class="footer">Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.10.0 </li>
|
|
||||||
</ul>
|
|
||||||
</div>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
||||||
|
|
@ -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" ]
|
|
||||||
];
|
|
||||||
|
|
@ -1,51 +0,0 @@
|
||||||
<map id="BNO08xTestSuite.hpp" name="BNO08xTestSuite.hpp">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="72,5,223,32"/>
|
|
||||||
<area shape="rect" id="Node000002" title=" " alt="" coords="5,229,66,256"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="120,35,89,54,63,81,48,114,40,150,36,214,31,214,34,149,43,113,59,79,86,50,117,30"/>
|
|
||||||
<area shape="rect" id="Node000003" title=" " alt="" coords="73,80,137,107"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="142,34,122,68,118,65,138,31"/>
|
|
||||||
<area shape="rect" id="Node000004" title=" " alt="" coords="161,80,222,107"/>
|
|
||||||
<area shape="poly" id="edge3_Node000001_Node000004" title=" " alt="" coords="157,31,178,65,174,68,153,34"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$_b_n_o08x_test_helper_8hpp.html" title=" " alt="" coords="246,80,404,107"/>
|
|
||||||
<area shape="poly" id="edge4_Node000001_Node000005" title=" " alt="" coords="179,30,281,71,279,76,177,35"/>
|
|
||||||
<area shape="poly" id="edge5_Node000005_Node000002" title=" " alt="" coords="301,110,75,224,72,220,299,105"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$_b_n_o08x_8hpp.html" title=" " alt="" coords="652,155,747,181"/>
|
|
||||||
<area shape="poly" id="edge6_Node000005_Node000006" title=" " alt="" coords="391,105,637,152,636,157,390,110"/>
|
|
||||||
<area shape="poly" id="edge9_Node000006_Node000002" title=" " alt="" coords="652,174,410,189,249,207,81,232,80,227,248,201,410,184,651,168"/>
|
|
||||||
<area shape="rect" id="Node000007" title=" " alt="" coords="90,229,168,256"/>
|
|
||||||
<area shape="poly" id="edge7_Node000006_Node000007" title=" " alt="" coords="651,176,451,195,320,211,184,231,183,226,319,206,451,189,651,170"/>
|
|
||||||
<area shape="rect" id="Node000008" title=" " alt="" coords="192,229,253,256"/>
|
|
||||||
<area shape="poly" id="edge8_Node000006_Node000008" title=" " alt="" coords="652,176,486,196,379,211,268,232,267,226,378,206,485,190,651,171"/>
|
|
||||||
<area shape="rect" id="Node000009" title=" " alt="" coords="277,229,338,256"/>
|
|
||||||
<area shape="poly" id="edge10_Node000006_Node000009" title=" " alt="" coords="652,178,521,199,354,231,352,226,520,193,651,173"/>
|
|
||||||
<area shape="rect" id="Node000010" title=" " alt="" coords="361,229,438,256"/>
|
|
||||||
<area shape="poly" id="edge11_Node000006_Node000010" title=" " alt="" coords="652,183,454,231,452,226,651,178"/>
|
|
||||||
<area shape="rect" id="Node000011" title=" " alt="" coords="461,229,517,256"/>
|
|
||||||
<area shape="poly" id="edge12_Node000006_Node000011" title=" " alt="" coords="664,184,532,229,530,224,662,179"/>
|
|
||||||
<area shape="rect" id="Node000012" title=" " alt="" coords="541,229,618,256"/>
|
|
||||||
<area shape="poly" id="edge13_Node000006_Node000012" title=" " alt="" coords="680,184,615,223,612,219,677,180"/>
|
|
||||||
<area shape="rect" id="Node000013" title=" " alt="" coords="643,229,756,256"/>
|
|
||||||
<area shape="poly" id="edge14_Node000006_Node000013" title=" " alt="" coords="702,182,702,214,697,214,697,182"/>
|
|
||||||
<area shape="rect" id="Node000014" title=" " alt="" coords="780,229,870,256"/>
|
|
||||||
<area shape="poly" id="edge15_Node000006_Node000014" title=" " alt="" coords="723,180,791,219,789,224,720,184"/>
|
|
||||||
<area shape="rect" id="Node000015" title=" " alt="" coords="893,229,1034,256"/>
|
|
||||||
<area shape="poly" id="edge16_Node000006_Node000015" title=" " alt="" coords="746,179,904,222,902,227,745,184"/>
|
|
||||||
<area shape="rect" id="Node000016" title=" " alt="" coords="1058,229,1162,256"/>
|
|
||||||
<area shape="poly" id="edge17_Node000006_Node000016" title=" " alt="" coords="748,175,1043,226,1042,231,747,180"/>
|
|
||||||
<area shape="rect" id="Node000017" title=" " alt="" coords="1186,229,1341,256"/>
|
|
||||||
<area shape="poly" id="edge18_Node000006_Node000017" title=" " alt="" coords="748,173,1171,226,1170,232,747,178"/>
|
|
||||||
<area shape="rect" id="Node000018" title=" " alt="" coords="1365,229,1479,256"/>
|
|
||||||
<area shape="poly" id="edge19_Node000006_Node000018" title=" " alt="" coords="748,170,1001,189,1172,206,1350,226,1349,232,1172,211,1000,195,747,175"/>
|
|
||||||
<area shape="rect" id="Node000019" title=" " alt="" coords="1504,229,1626,256"/>
|
|
||||||
<area shape="poly" id="edge20_Node000006_Node000019" title=" " alt="" coords="748,169,1055,187,1268,204,1488,226,1488,232,1267,209,1055,192,747,174"/>
|
|
||||||
<area shape="rect" id="Node000020" title=" " alt="" coords="1650,229,1754,256"/>
|
|
||||||
<area shape="poly" id="edge21_Node000006_Node000020" title=" " alt="" coords="748,168,1112,182,1369,200,1635,226,1634,232,1368,205,1112,188,747,173"/>
|
|
||||||
<area shape="rect" id="Node000021" href="$_b_n_o08x__global__types_8hpp.html" title=" " alt="" coords="1779,229,1954,256"/>
|
|
||||||
<area shape="poly" id="edge22_Node000006_Node000021" title=" " alt="" coords="748,168,1161,186,1456,203,1763,226,1763,232,1456,209,1160,192,747,174"/>
|
|
||||||
<area shape="rect" id="Node000022" title=" " alt="" coords="1681,304,1771,331"/>
|
|
||||||
<area shape="poly" id="edge23_Node000021_Node000022" title=" " alt="" coords="1843,259,1766,299,1763,294,1841,254"/>
|
|
||||||
<area shape="rect" id="Node000023" title=" " alt="" coords="1796,304,1936,331"/>
|
|
||||||
<area shape="poly" id="edge24_Node000021_Node000023" title=" " alt="" coords="1869,257,1869,288,1864,288,1864,257"/>
|
|
||||||
<area shape="rect" id="Node000024" title=" " alt="" coords="1961,304,2091,331"/>
|
|
||||||
<area shape="poly" id="edge25_Node000021_Node000024" title=" " alt="" coords="1895,254,1986,295,1983,300,1893,259"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
cbe15c59e2c01479a472681297f79770
|
|
||||||
|
Before Width: | Height: | Size: 55 KiB |
|
|
@ -1,231 +0,0 @@
|
||||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
|
||||||
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US">
|
|
||||||
<head>
|
|
||||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
|
||||||
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
|
|
||||||
<meta name="generator" content="Doxygen 1.10.0"/>
|
|
||||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
|
||||||
<title>esp32_BNO08x: BNO08xTestSuite.hpp Source File</title>
|
|
||||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="jquery.js"></script>
|
|
||||||
<script type="text/javascript" src="dynsections.js"></script>
|
|
||||||
<script type="text/javascript" src="clipboard.js"></script>
|
|
||||||
<link href="navtree.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="resize.js"></script>
|
|
||||||
<script type="text/javascript" src="navtreedata.js"></script>
|
|
||||||
<script type="text/javascript" src="navtree.js"></script>
|
|
||||||
<script type="text/javascript" src="cookie.js"></script>
|
|
||||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
|
||||||
<script type="text/javascript" src="search/search.js"></script>
|
|
||||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
|
||||||
<div id="titlearea">
|
|
||||||
<table cellspacing="0" cellpadding="0">
|
|
||||||
<tbody>
|
|
||||||
<tr id="projectrow">
|
|
||||||
<td id="projectalign">
|
|
||||||
<div id="projectname">esp32_BNO08x<span id="projectnumber"> 1.2</span>
|
|
||||||
</div>
|
|
||||||
<div id="projectbrief">C++ BNO08x IMU driver component for esp-idf.</div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
</div>
|
|
||||||
<!-- end header part -->
|
|
||||||
<!-- Generated by Doxygen 1.10.0 -->
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
var searchBox = new SearchBox("searchBox", "search/",'.html');
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<script type="text/javascript" src="menudata.js"></script>
|
|
||||||
<script type="text/javascript" src="menu.js"></script>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() {
|
|
||||||
initMenu('',true,false,'search.php','Search');
|
|
||||||
$(function() { init_search(); });
|
|
||||||
});
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="main-nav"></div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() { codefold.init(0); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
</div><!-- top -->
|
|
||||||
<div id="side-nav" class="ui-resizable side-nav-resizable">
|
|
||||||
<div id="nav-tree">
|
|
||||||
<div id="nav-tree-contents">
|
|
||||||
<div id="nav-sync" class="sync"></div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div id="splitbar" style="-moz-user-select:none;"
|
|
||||||
class="ui-resizable-handle">
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function(){initNavTree('_b_n_o08x_test_suite_8hpp_source.html',''); initResizable(); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="doc-content">
|
|
||||||
<!-- window showing the filter options -->
|
|
||||||
<div id="MSearchSelectWindow"
|
|
||||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
|
||||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
|
||||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<!-- iframe showing the search results (closed by default) -->
|
|
||||||
<div id="MSearchResultsWindow">
|
|
||||||
<div id="MSearchResults">
|
|
||||||
<div class="SRPage">
|
|
||||||
<div id="SRIndex">
|
|
||||||
<div id="SRResults"></div>
|
|
||||||
<div class="SRStatus" id="Loading">Loading...</div>
|
|
||||||
<div class="SRStatus" id="Searching">Searching...</div>
|
|
||||||
<div class="SRStatus" id="NoMatches">No Matches</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="header">
|
|
||||||
<div class="headertitle"><div class="title">BNO08xTestSuite.hpp</div></div>
|
|
||||||
</div><!--header-->
|
|
||||||
<div class="contents">
|
|
||||||
<a href="_b_n_o08x_test_suite_8hpp.html">Go to the documentation of this file.</a><div class="fragment"><div class="line"><a id="l00001" name="l00001"></a><span class="lineno"> 1</span> </div>
|
|
||||||
<div class="line"><a id="l00009" name="l00009"></a><span class="lineno"> 9</span><span class="preprocessor">#pragma once</span></div>
|
|
||||||
<div class="line"><a id="l00010" name="l00010"></a><span class="lineno"> 10</span> </div>
|
|
||||||
<div class="line"><a id="l00011" name="l00011"></a><span class="lineno"> 11</span><span class="preprocessor">#include <stdio.h></span></div>
|
|
||||||
<div class="line"><a id="l00012" name="l00012"></a><span class="lineno"> 12</span><span class="preprocessor">#include <string.h></span></div>
|
|
||||||
<div class="line"><a id="l00013" name="l00013"></a><span class="lineno"> 13</span><span class="preprocessor">#include "unity.h"</span></div>
|
|
||||||
<div class="line"><a id="l00014" name="l00014"></a><span class="lineno"> 14</span><span class="preprocessor">#include "<a class="code" href="_b_n_o08x_test_helper_8hpp.html">BNO08xTestHelper.hpp</a>"</span></div>
|
|
||||||
<div class="line"><a id="l00015" name="l00015"></a><span class="lineno"> 15</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00021" data-start="{" data-end="};">
|
|
||||||
<div class="line"><a id="l00021" name="l00021"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_suite.html"> 21</a></span><span class="keyword">class </span><a class="code hl_class" href="class_b_n_o08x_test_suite.html">BNO08xTestSuite</a></div>
|
|
||||||
<div class="line"><a id="l00022" name="l00022"></a><span class="lineno"> 22</span>{</div>
|
|
||||||
<div class="line"><a id="l00023" name="l00023"></a><span class="lineno"> 23</span> <span class="keyword">private</span>:</div>
|
|
||||||
<div class="foldopen" id="foldopen00024" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00024" name="l00024"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_suite.html#a2fea3ea192a63c9573c774e772f5c085"> 24</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a2fea3ea192a63c9573c774e772f5c085">print_begin_tests_banner</a>(<span class="keyword">const</span> <span class="keywordtype">char</span>* test_set_name)</div>
|
|
||||||
<div class="line"><a id="l00025" name="l00025"></a><span class="lineno"> 25</span> {</div>
|
|
||||||
<div class="line"><a id="l00026" name="l00026"></a><span class="lineno"> 26</span> printf(<span class="stringliteral">"####################### BEGIN TESTS: %s #######################\n\r"</span>, test_set_name);</div>
|
|
||||||
<div class="line"><a id="l00027" name="l00027"></a><span class="lineno"> 27</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00028" name="l00028"></a><span class="lineno"> 28</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00029" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00029" name="l00029"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_suite.html#a5a9b6538773911afed92b16c435ebceb"> 29</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a5a9b6538773911afed92b16c435ebceb">print_end_tests_banner</a>(<span class="keyword">const</span> <span class="keywordtype">char</span>* test_set_name)</div>
|
|
||||||
<div class="line"><a id="l00030" name="l00030"></a><span class="lineno"> 30</span> {</div>
|
|
||||||
<div class="line"><a id="l00031" name="l00031"></a><span class="lineno"> 31</span> printf(<span class="stringliteral">"####################### END TESTS: %s #######################\n\r"</span>, test_set_name);</div>
|
|
||||||
<div class="line"><a id="l00032" name="l00032"></a><span class="lineno"> 32</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00033" name="l00033"></a><span class="lineno"> 33</span> </div>
|
|
||||||
<div class="line"><a id="l00034" name="l00034"></a><span class="lineno"> 34</span> <span class="keyword">public</span>:</div>
|
|
||||||
<div class="foldopen" id="foldopen00035" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00035" name="l00035"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_suite.html#ac12545fe311a98e9c0ae6fea77da95fd"> 35</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#ac12545fe311a98e9c0ae6fea77da95fd">run_all_tests</a>()</div>
|
|
||||||
<div class="line"><a id="l00036" name="l00036"></a><span class="lineno"> 36</span> {</div>
|
|
||||||
<div class="line"><a id="l00037" name="l00037"></a><span class="lineno"> 37</span> UNITY_BEGIN();</div>
|
|
||||||
<div class="line"><a id="l00038" name="l00038"></a><span class="lineno"> 38</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a53de9b0fe1b28c18e3a1ca4c68a06f16">run_init_deinit_tests</a>(<span class="keyword">false</span>);</div>
|
|
||||||
<div class="line"><a id="l00039" name="l00039"></a><span class="lineno"> 39</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a37899d7bf67fce5c3dd77dd5647f8ecb">run_single_report_tests</a>(<span class="keyword">false</span>);</div>
|
|
||||||
<div class="line"><a id="l00040" name="l00040"></a><span class="lineno"> 40</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a916cff374791381de61f1035f9935ac5">run_multi_report_tests</a>(<span class="keyword">false</span>);</div>
|
|
||||||
<div class="line"><a id="l00041" name="l00041"></a><span class="lineno"> 41</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a8e294955bf512e2e88c086f04f6030a8">run_callback_tests</a>(<span class="keyword">false</span>);</div>
|
|
||||||
<div class="line"><a id="l00042" name="l00042"></a><span class="lineno"> 42</span> UNITY_END();</div>
|
|
||||||
<div class="line"><a id="l00043" name="l00043"></a><span class="lineno"> 43</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00044" name="l00044"></a><span class="lineno"> 44</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00045" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00045" name="l00045"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_suite.html#a53de9b0fe1b28c18e3a1ca4c68a06f16"> 45</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a53de9b0fe1b28c18e3a1ca4c68a06f16">run_init_deinit_tests</a>(<span class="keywordtype">bool</span> call_unity_end_begin = <span class="keyword">true</span>)</div>
|
|
||||||
<div class="line"><a id="l00046" name="l00046"></a><span class="lineno"> 46</span> {</div>
|
|
||||||
<div class="line"><a id="l00047" name="l00047"></a><span class="lineno"> 47</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a2fea3ea192a63c9573c774e772f5c085">print_begin_tests_banner</a>(<span class="stringliteral">"init_denit_tests"</span>);</div>
|
|
||||||
<div class="line"><a id="l00048" name="l00048"></a><span class="lineno"> 48</span> </div>
|
|
||||||
<div class="line"><a id="l00049" name="l00049"></a><span class="lineno"> 49</span> <span class="keywordflow">if</span> (call_unity_end_begin)</div>
|
|
||||||
<div class="line"><a id="l00050" name="l00050"></a><span class="lineno"> 50</span> UNITY_BEGIN();</div>
|
|
||||||
<div class="line"><a id="l00051" name="l00051"></a><span class="lineno"> 51</span> </div>
|
|
||||||
<div class="line"><a id="l00052" name="l00052"></a><span class="lineno"> 52</span> unity_run_tests_by_tag(<span class="stringliteral">"[InitComprehensive]"</span>, <span class="keyword">false</span>);</div>
|
|
||||||
<div class="line"><a id="l00053" name="l00053"></a><span class="lineno"> 53</span> unity_run_tests_by_tag(<span class="stringliteral">"[InitDenit]"</span>, <span class="keyword">false</span>);</div>
|
|
||||||
<div class="line"><a id="l00054" name="l00054"></a><span class="lineno"> 54</span> </div>
|
|
||||||
<div class="line"><a id="l00055" name="l00055"></a><span class="lineno"> 55</span> <span class="keywordflow">if</span> (call_unity_end_begin)</div>
|
|
||||||
<div class="line"><a id="l00056" name="l00056"></a><span class="lineno"> 56</span> UNITY_END();</div>
|
|
||||||
<div class="line"><a id="l00057" name="l00057"></a><span class="lineno"> 57</span> </div>
|
|
||||||
<div class="line"><a id="l00058" name="l00058"></a><span class="lineno"> 58</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a5a9b6538773911afed92b16c435ebceb">print_end_tests_banner</a>(<span class="stringliteral">"init_denit_tests"</span>);</div>
|
|
||||||
<div class="line"><a id="l00059" name="l00059"></a><span class="lineno"> 59</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00060" name="l00060"></a><span class="lineno"> 60</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00061" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00061" name="l00061"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_suite.html#a37899d7bf67fce5c3dd77dd5647f8ecb"> 61</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a37899d7bf67fce5c3dd77dd5647f8ecb">run_single_report_tests</a>(<span class="keywordtype">bool</span> call_unity_end_begin = <span class="keyword">true</span>)</div>
|
|
||||||
<div class="line"><a id="l00062" name="l00062"></a><span class="lineno"> 62</span> {</div>
|
|
||||||
<div class="line"><a id="l00063" name="l00063"></a><span class="lineno"> 63</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a2fea3ea192a63c9573c774e772f5c085">print_begin_tests_banner</a>(<span class="stringliteral">"single_report_tests"</span>);</div>
|
|
||||||
<div class="line"><a id="l00064" name="l00064"></a><span class="lineno"> 64</span> </div>
|
|
||||||
<div class="line"><a id="l00065" name="l00065"></a><span class="lineno"> 65</span> <span class="keywordflow">if</span> (call_unity_end_begin)</div>
|
|
||||||
<div class="line"><a id="l00066" name="l00066"></a><span class="lineno"> 66</span> UNITY_BEGIN();</div>
|
|
||||||
<div class="line"><a id="l00067" name="l00067"></a><span class="lineno"> 67</span> </div>
|
|
||||||
<div class="line"><a id="l00068" name="l00068"></a><span class="lineno"> 68</span> unity_run_tests_by_tag(<span class="stringliteral">"[SingleReportEnableDisable]"</span>, <span class="keyword">false</span>);</div>
|
|
||||||
<div class="line"><a id="l00069" name="l00069"></a><span class="lineno"> 69</span> </div>
|
|
||||||
<div class="line"><a id="l00070" name="l00070"></a><span class="lineno"> 70</span> <span class="keywordflow">if</span> (call_unity_end_begin)</div>
|
|
||||||
<div class="line"><a id="l00071" name="l00071"></a><span class="lineno"> 71</span> UNITY_END();</div>
|
|
||||||
<div class="line"><a id="l00072" name="l00072"></a><span class="lineno"> 72</span> </div>
|
|
||||||
<div class="line"><a id="l00073" name="l00073"></a><span class="lineno"> 73</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a5a9b6538773911afed92b16c435ebceb">print_end_tests_banner</a>(<span class="stringliteral">"single_report_tests"</span>);</div>
|
|
||||||
<div class="line"><a id="l00074" name="l00074"></a><span class="lineno"> 74</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00075" name="l00075"></a><span class="lineno"> 75</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00076" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00076" name="l00076"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_suite.html#a916cff374791381de61f1035f9935ac5"> 76</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a916cff374791381de61f1035f9935ac5">run_multi_report_tests</a>(<span class="keywordtype">bool</span> call_unity_end_begin = <span class="keyword">true</span>)</div>
|
|
||||||
<div class="line"><a id="l00077" name="l00077"></a><span class="lineno"> 77</span> {</div>
|
|
||||||
<div class="line"><a id="l00078" name="l00078"></a><span class="lineno"> 78</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a2fea3ea192a63c9573c774e772f5c085">print_begin_tests_banner</a>(<span class="stringliteral">"multi_report_tests"</span>);</div>
|
|
||||||
<div class="line"><a id="l00079" name="l00079"></a><span class="lineno"> 79</span> </div>
|
|
||||||
<div class="line"><a id="l00080" name="l00080"></a><span class="lineno"> 80</span> <span class="keywordflow">if</span> (call_unity_end_begin)</div>
|
|
||||||
<div class="line"><a id="l00081" name="l00081"></a><span class="lineno"> 81</span> UNITY_BEGIN();</div>
|
|
||||||
<div class="line"><a id="l00082" name="l00082"></a><span class="lineno"> 82</span> </div>
|
|
||||||
<div class="line"><a id="l00083" name="l00083"></a><span class="lineno"> 83</span> unity_run_tests_by_tag(<span class="stringliteral">"[MultiReportEnableDisable]"</span>, <span class="keyword">false</span>);</div>
|
|
||||||
<div class="line"><a id="l00084" name="l00084"></a><span class="lineno"> 84</span> </div>
|
|
||||||
<div class="line"><a id="l00085" name="l00085"></a><span class="lineno"> 85</span> <span class="keywordflow">if</span> (call_unity_end_begin)</div>
|
|
||||||
<div class="line"><a id="l00086" name="l00086"></a><span class="lineno"> 86</span> UNITY_END();</div>
|
|
||||||
<div class="line"><a id="l00087" name="l00087"></a><span class="lineno"> 87</span> </div>
|
|
||||||
<div class="line"><a id="l00088" name="l00088"></a><span class="lineno"> 88</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a5a9b6538773911afed92b16c435ebceb">print_end_tests_banner</a>(<span class="stringliteral">"multi_report_tests"</span>);</div>
|
|
||||||
<div class="line"><a id="l00089" name="l00089"></a><span class="lineno"> 89</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00090" name="l00090"></a><span class="lineno"> 90</span> </div>
|
|
||||||
<div class="foldopen" id="foldopen00091" data-start="{" data-end="}">
|
|
||||||
<div class="line"><a id="l00091" name="l00091"></a><span class="lineno"><a class="line" href="class_b_n_o08x_test_suite.html#a8e294955bf512e2e88c086f04f6030a8"> 91</a></span> <span class="keyword">static</span> <span class="keywordtype">void</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a8e294955bf512e2e88c086f04f6030a8">run_callback_tests</a>(<span class="keywordtype">bool</span> call_unity_end_begin = <span class="keyword">true</span>)</div>
|
|
||||||
<div class="line"><a id="l00092" name="l00092"></a><span class="lineno"> 92</span> {</div>
|
|
||||||
<div class="line"><a id="l00093" name="l00093"></a><span class="lineno"> 93</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a2fea3ea192a63c9573c774e772f5c085">print_begin_tests_banner</a>(<span class="stringliteral">"run_callback_tests"</span>);</div>
|
|
||||||
<div class="line"><a id="l00094" name="l00094"></a><span class="lineno"> 94</span> </div>
|
|
||||||
<div class="line"><a id="l00095" name="l00095"></a><span class="lineno"> 95</span> <span class="keywordflow">if</span> (call_unity_end_begin)</div>
|
|
||||||
<div class="line"><a id="l00096" name="l00096"></a><span class="lineno"> 96</span> UNITY_BEGIN();</div>
|
|
||||||
<div class="line"><a id="l00097" name="l00097"></a><span class="lineno"> 97</span> </div>
|
|
||||||
<div class="line"><a id="l00098" name="l00098"></a><span class="lineno"> 98</span> unity_run_tests_by_tag(<span class="stringliteral">"[CallbackTests]"</span>, <span class="keyword">false</span>);</div>
|
|
||||||
<div class="line"><a id="l00099" name="l00099"></a><span class="lineno"> 99</span> </div>
|
|
||||||
<div class="line"><a id="l00100" name="l00100"></a><span class="lineno"> 100</span> <span class="keywordflow">if</span> (call_unity_end_begin)</div>
|
|
||||||
<div class="line"><a id="l00101" name="l00101"></a><span class="lineno"> 101</span> UNITY_END();</div>
|
|
||||||
<div class="line"><a id="l00102" name="l00102"></a><span class="lineno"> 102</span> </div>
|
|
||||||
<div class="line"><a id="l00103" name="l00103"></a><span class="lineno"> 103</span> <a class="code hl_function" href="class_b_n_o08x_test_suite.html#a5a9b6538773911afed92b16c435ebceb">print_end_tests_banner</a>(<span class="stringliteral">"run_callback_tests"</span>);</div>
|
|
||||||
<div class="line"><a id="l00104" name="l00104"></a><span class="lineno"> 104</span> }</div>
|
|
||||||
</div>
|
|
||||||
<div class="line"><a id="l00105" name="l00105"></a><span class="lineno"> 105</span>};</div>
|
|
||||||
</div>
|
|
||||||
<div class="ttc" id="a_b_n_o08x_test_helper_8hpp_html"><div class="ttname"><a href="_b_n_o08x_test_helper_8hpp.html">BNO08xTestHelper.hpp</a></div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_suite_html"><div class="ttname"><a href="class_b_n_o08x_test_suite.html">BNO08xTestSuite</a></div><div class="ttdoc">BNO08x unit test launch point class.</div><div class="ttdef"><b>Definition</b> BNO08xTestSuite.hpp:22</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_suite_html_a2fea3ea192a63c9573c774e772f5c085"><div class="ttname"><a href="class_b_n_o08x_test_suite.html#a2fea3ea192a63c9573c774e772f5c085">BNO08xTestSuite::print_begin_tests_banner</a></div><div class="ttdeci">static void print_begin_tests_banner(const char *test_set_name)</div><div class="ttdef"><b>Definition</b> BNO08xTestSuite.hpp:24</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_suite_html_a37899d7bf67fce5c3dd77dd5647f8ecb"><div class="ttname"><a href="class_b_n_o08x_test_suite.html#a37899d7bf67fce5c3dd77dd5647f8ecb">BNO08xTestSuite::run_single_report_tests</a></div><div class="ttdeci">static void run_single_report_tests(bool call_unity_end_begin=true)</div><div class="ttdef"><b>Definition</b> BNO08xTestSuite.hpp:61</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_suite_html_a53de9b0fe1b28c18e3a1ca4c68a06f16"><div class="ttname"><a href="class_b_n_o08x_test_suite.html#a53de9b0fe1b28c18e3a1ca4c68a06f16">BNO08xTestSuite::run_init_deinit_tests</a></div><div class="ttdeci">static void run_init_deinit_tests(bool call_unity_end_begin=true)</div><div class="ttdef"><b>Definition</b> BNO08xTestSuite.hpp:45</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_suite_html_a5a9b6538773911afed92b16c435ebceb"><div class="ttname"><a href="class_b_n_o08x_test_suite.html#a5a9b6538773911afed92b16c435ebceb">BNO08xTestSuite::print_end_tests_banner</a></div><div class="ttdeci">static void print_end_tests_banner(const char *test_set_name)</div><div class="ttdef"><b>Definition</b> BNO08xTestSuite.hpp:29</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_suite_html_a8e294955bf512e2e88c086f04f6030a8"><div class="ttname"><a href="class_b_n_o08x_test_suite.html#a8e294955bf512e2e88c086f04f6030a8">BNO08xTestSuite::run_callback_tests</a></div><div class="ttdeci">static void run_callback_tests(bool call_unity_end_begin=true)</div><div class="ttdef"><b>Definition</b> BNO08xTestSuite.hpp:91</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_suite_html_a916cff374791381de61f1035f9935ac5"><div class="ttname"><a href="class_b_n_o08x_test_suite.html#a916cff374791381de61f1035f9935ac5">BNO08xTestSuite::run_multi_report_tests</a></div><div class="ttdeci">static void run_multi_report_tests(bool call_unity_end_begin=true)</div><div class="ttdef"><b>Definition</b> BNO08xTestSuite.hpp:76</div></div>
|
|
||||||
<div class="ttc" id="aclass_b_n_o08x_test_suite_html_ac12545fe311a98e9c0ae6fea77da95fd"><div class="ttname"><a href="class_b_n_o08x_test_suite.html#ac12545fe311a98e9c0ae6fea77da95fd">BNO08xTestSuite::run_all_tests</a></div><div class="ttdeci">static void run_all_tests()</div><div class="ttdef"><b>Definition</b> BNO08xTestSuite.hpp:35</div></div>
|
|
||||||
</div><!-- fragment --></div><!-- contents -->
|
|
||||||
</div><!-- doc-content -->
|
|
||||||
<!-- start footer part -->
|
|
||||||
<div id="nav-path" class="navpath"><!-- id is needed for treeview function! -->
|
|
||||||
<ul>
|
|
||||||
<li class="navelem"><a class="el" href="dir_85e9385bd83516731053aadc7da3c8af.html">imu_update</a></li><li class="navelem"><a class="el" href="dir_c60d9bf80716f90f729fd65c40ec81f7.html">bno08x_update</a></li><li class="navelem"><a class="el" href="dir_fd670e5d11b8bb731501003ff6578ae1.html">components</a></li><li class="navelem"><a class="el" href="dir_a6718ce9703adf4789a693642ffedf7f.html">esp32_BNO08x</a></li><li class="navelem"><a class="el" href="dir_9667f1a5b10a5222433e41df91e1bf5d.html">include</a></li><li class="navelem"><a class="el" href="_b_n_o08x_test_suite_8hpp.html">BNO08xTestSuite.hpp</a></li>
|
|
||||||
<li class="footer">Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.10.0 </li>
|
|
||||||
</ul>
|
|
||||||
</div>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
||||||
|
|
@ -1,936 +0,0 @@
|
||||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
|
||||||
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US">
|
|
||||||
<head>
|
|
||||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
|
||||||
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
|
|
||||||
<meta name="generator" content="Doxygen 1.10.0"/>
|
|
||||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
|
||||||
<title>esp32_BNO08x: CallbackTests.cpp File Reference</title>
|
|
||||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="jquery.js"></script>
|
|
||||||
<script type="text/javascript" src="dynsections.js"></script>
|
|
||||||
<script type="text/javascript" src="clipboard.js"></script>
|
|
||||||
<link href="navtree.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="resize.js"></script>
|
|
||||||
<script type="text/javascript" src="navtreedata.js"></script>
|
|
||||||
<script type="text/javascript" src="navtree.js"></script>
|
|
||||||
<script type="text/javascript" src="cookie.js"></script>
|
|
||||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
|
||||||
<script type="text/javascript" src="search/search.js"></script>
|
|
||||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
|
||||||
<div id="titlearea">
|
|
||||||
<table cellspacing="0" cellpadding="0">
|
|
||||||
<tbody>
|
|
||||||
<tr id="projectrow">
|
|
||||||
<td id="projectalign">
|
|
||||||
<div id="projectname">esp32_BNO08x<span id="projectnumber"> 1.2</span>
|
|
||||||
</div>
|
|
||||||
<div id="projectbrief">C++ BNO08x IMU driver component for esp-idf.</div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
</div>
|
|
||||||
<!-- end header part -->
|
|
||||||
<!-- Generated by Doxygen 1.10.0 -->
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
var searchBox = new SearchBox("searchBox", "search/",'.html');
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<script type="text/javascript" src="menudata.js"></script>
|
|
||||||
<script type="text/javascript" src="menu.js"></script>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() {
|
|
||||||
initMenu('',true,false,'search.php','Search');
|
|
||||||
$(function() { init_search(); });
|
|
||||||
});
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="main-nav"></div>
|
|
||||||
</div><!-- top -->
|
|
||||||
<div id="side-nav" class="ui-resizable side-nav-resizable">
|
|
||||||
<div id="nav-tree">
|
|
||||||
<div id="nav-tree-contents">
|
|
||||||
<div id="nav-sync" class="sync"></div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div id="splitbar" style="-moz-user-select:none;"
|
|
||||||
class="ui-resizable-handle">
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function(){initNavTree('_callback_tests_8cpp.html',''); initResizable(); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="doc-content">
|
|
||||||
<!-- window showing the filter options -->
|
|
||||||
<div id="MSearchSelectWindow"
|
|
||||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
|
||||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
|
||||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<!-- iframe showing the search results (closed by default) -->
|
|
||||||
<div id="MSearchResultsWindow">
|
|
||||||
<div id="MSearchResults">
|
|
||||||
<div class="SRPage">
|
|
||||||
<div id="SRIndex">
|
|
||||||
<div id="SRResults"></div>
|
|
||||||
<div class="SRStatus" id="Loading">Loading...</div>
|
|
||||||
<div class="SRStatus" id="Searching">Searching...</div>
|
|
||||||
<div class="SRStatus" id="NoMatches">No Matches</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="header">
|
|
||||||
<div class="summary">
|
|
||||||
<a href="#func-members">Functions</a> |
|
|
||||||
<a href="#var-members">Variables</a> </div>
|
|
||||||
<div class="headertitle"><div class="title">CallbackTests.cpp File Reference</div></div>
|
|
||||||
</div><!--header-->
|
|
||||||
<div class="contents">
|
|
||||||
<div class="textblock"><code>#include "unity.h"</code><br />
|
|
||||||
<code>#include "<a class="el" href="_b_n_o08x_test_helper_8hpp_source.html">../include/BNO08xTestHelper.hpp</a>"</code><br />
|
|
||||||
</div><div class="textblock"><div class="dynheader">
|
|
||||||
Include dependency graph for CallbackTests.cpp:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_callback_tests_8cpp__incl.png" border="0" usemap="#a_callback_tests_8cpp" alt=""/></div>
|
|
||||||
<map name="a_callback_tests_8cpp" id="a_callback_tests_8cpp">
|
|
||||||
<area shape="rect" title=" " alt="" coords="367,5,496,32"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="321,80,382,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="419,35,378,72,375,68,416,31"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_test_helper_8hpp.html" title=" " alt="" coords="406,80,620,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="447,31,489,68,486,72,444,35"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,229,66,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="473,110,81,230,79,225,471,105"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_8hpp.html" title=" " alt="" coords="652,155,747,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="546,105,654,146,652,151,544,110"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,174,410,189,249,207,81,232,80,227,248,201,410,184,651,168"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="90,229,168,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="651,176,451,195,320,211,184,231,183,226,319,206,451,189,651,170"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="192,229,253,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,176,486,196,379,211,268,232,267,226,378,206,485,190,651,171"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="277,229,338,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,178,521,199,354,231,352,226,520,193,651,173"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="361,229,438,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,183,454,231,452,226,651,178"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="461,229,517,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="664,184,532,229,530,224,662,179"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="541,229,618,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="680,184,615,223,612,219,677,180"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="643,229,756,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="702,182,702,214,697,214,697,182"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="780,229,870,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="723,180,791,219,789,224,720,184"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="893,229,1034,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="746,179,904,222,902,227,745,184"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1058,229,1162,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,175,1043,226,1042,231,747,180"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1186,229,1341,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,173,1171,226,1170,232,747,178"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1365,229,1479,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,170,1001,189,1172,206,1350,226,1349,232,1172,211,1000,195,747,175"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1504,229,1626,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,169,1055,187,1268,204,1488,226,1488,232,1267,209,1055,192,747,174"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1650,229,1754,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,168,1112,182,1369,200,1635,226,1634,232,1368,205,1112,188,747,173"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x__global__types_8hpp.html" title=" " alt="" coords="1779,229,1954,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,168,1161,186,1456,203,1763,226,1763,232,1456,209,1160,192,747,174"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1681,304,1771,331"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1843,259,1766,299,1763,294,1841,254"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1796,304,1936,331"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1869,257,1869,288,1864,288,1864,257"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1961,304,2091,331"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1895,254,1986,295,1983,300,1893,259"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
</div><table class="memberdecls">
|
|
||||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a id="func-members" name="func-members"></a>
|
|
||||||
Functions</h2></td></tr>
|
|
||||||
<tr class="memitem:ac18b9cb122499f587331d82a538f23aa" id="r_ac18b9cb122499f587331d82a538f23aa"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="#ac18b9cb122499f587331d82a538f23aa">TEST_CASE</a> ("BNO08x Driver Creation <a class="el" href="#a4ac223c58b5ab6a6c5203661fafa1caa">for</a> [CallbackTests] Tests", "[CallbackTests]")</td></tr>
|
|
||||||
<tr class="separator:ac18b9cb122499f587331d82a538f23aa"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a6df8508e34beaeb28f34554ce0e20573" id="r_a6df8508e34beaeb28f34554ce0e20573"><td class="memItemLeft" align="right" valign="top"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a6df8508e34beaeb28f34554ce0e20573">register_cb</a> ([&<a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a>, &<a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a>, &<a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, &<a class="el" href="#a8c57d66969fed0b55bdee9b57f6ed0a7">prev_report_data</a>, &<a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>]() { static int cb_execution_cnt=0;cb_execution_cnt++;<a class="el" href="class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2">BNO08xTestHelper::update_report_data</a>(&<a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a>);if(<a class="el" href="class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea">BNO08xTestHelper::accelerometer_data_is_new</a>(&<a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, &<a class="el" href="#a8c57d66969fed0b55bdee9b57f6ed0a7">prev_report_data</a>)) { <a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a>=true;sprintf(<a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>, "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, <a class="el" href="class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3">BNO08xTestHelper::BNO08xAccuracy_to_str</a>(report_data.accel_accuracy));<a class="el" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002">BNO08xTestHelper::print_test_msg</a>(TEST_TAG, <a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>);} })</td></tr>
|
|
||||||
<tr class="separator:a6df8508e34beaeb28f34554ce0e20573"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a0f2cacda77ab92640f739aca52b1f99f" id="r_a0f2cacda77ab92640f739aca52b1f99f"><td class="memItemLeft" align="right" valign="top"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a0f2cacda77ab92640f739aca52b1f99f">enable_accelerometer</a> (<a class="el" href="#a4b80e39a1f48d801615a1f7baa210071">REPORT_PERIOD</a>)</td></tr>
|
|
||||||
<tr class="separator:a0f2cacda77ab92640f739aca52b1f99f"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a4ac223c58b5ab6a6c5203661fafa1caa" id="r_a4ac223c58b5ab6a6c5203661fafa1caa"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a4ac223c58b5ab6a6c5203661fafa1caa">for</a> (int i=0;i< <a class="el" href="#a20cd776c25ed6d39b2dcb95d155cfbda">RX_REPORT_TRIAL_CNT</a>;i++)</td></tr>
|
|
||||||
<tr class="separator:a4ac223c58b5ab6a6c5203661fafa1caa"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a79547a2396efd083faeba3e54d94360d" id="r_a79547a2396efd083faeba3e54d94360d"><td class="memItemLeft" align="right" valign="top"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a79547a2396efd083faeba3e54d94360d">disable_accelerometer</a> ()</td></tr>
|
|
||||||
<tr class="separator:a79547a2396efd083faeba3e54d94360d"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a8dba989b01b464871f3232223050ec73" id="r_a8dba989b01b464871f3232223050ec73"><td class="memItemLeft" align="right" valign="top"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a8dba989b01b464871f3232223050ec73">register_cb</a> ([&<a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a>, &<a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a>, &<a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, &<a class="el" href="#a8c57d66969fed0b55bdee9b57f6ed0a7">prev_report_data</a>, &<a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>]() { static int cb_execution_cnt=0;cb_execution_cnt++;<a class="el" href="class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2">BNO08xTestHelper::update_report_data</a>(&<a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a>);if(<a class="el" href="class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea">BNO08xTestHelper::accelerometer_data_is_new</a>(&<a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, &<a class="el" href="#a8c57d66969fed0b55bdee9b57f6ed0a7">prev_report_data</a>)) { <a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a>[0]=true;sprintf(<a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>, "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, <a class="el" href="class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3">BNO08xTestHelper::BNO08xAccuracy_to_str</a>(report_data.accel_accuracy));<a class="el" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002">BNO08xTestHelper::print_test_msg</a>(TEST_TAG, <a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>);} if(<a class="el" href="class_b_n_o08x_test_helper.html#ad398739ce46400c1ac35e1cf7603d590">BNO08xTestHelper::linear_accelerometer_data_is_new</a>(&<a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, &<a class="el" href="#a8c57d66969fed0b55bdee9b57f6ed0a7">prev_report_data</a>)) { <a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a>[1]=true;sprintf(<a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>, "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, <a class="el" href="class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3">BNO08xTestHelper::BNO08xAccuracy_to_str</a>(report_data.lin_accel_accuracy));<a class="el" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002">BNO08xTestHelper::print_test_msg</a>(TEST_TAG, <a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>);} })</td></tr>
|
|
||||||
<tr class="separator:a8dba989b01b464871f3232223050ec73"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a3e937c8c4a4c07b81fb20077ee984fc0" id="r_a3e937c8c4a4c07b81fb20077ee984fc0"><td class="memItemLeft" align="right" valign="top"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a3e937c8c4a4c07b81fb20077ee984fc0">enable_linear_accelerometer</a> (<a class="el" href="#a4b80e39a1f48d801615a1f7baa210071">REPORT_PERIOD</a>)</td></tr>
|
|
||||||
<tr class="separator:a3e937c8c4a4c07b81fb20077ee984fc0"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a9091949d4ea860523915687536d5c4d3" id="r_a9091949d4ea860523915687536d5c4d3"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a9091949d4ea860523915687536d5c4d3">TEST_ASSERT_EQUAL</a> (true, <a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a>[0])</td></tr>
|
|
||||||
<tr class="separator:a9091949d4ea860523915687536d5c4d3"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:aa6754207db4cfba956441680c7a6a97d" id="r_aa6754207db4cfba956441680c7a6a97d"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="#aa6754207db4cfba956441680c7a6a97d">TEST_ASSERT_EQUAL</a> (true, <a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a>[1])</td></tr>
|
|
||||||
<tr class="separator:aa6754207db4cfba956441680c7a6a97d"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a5cc5f7e6658e3b1634d99b73dbfd06ab" id="r_a5cc5f7e6658e3b1634d99b73dbfd06ab"><td class="memItemLeft" align="right" valign="top"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a5cc5f7e6658e3b1634d99b73dbfd06ab">disable_linear_accelerometer</a> ()</td></tr>
|
|
||||||
<tr class="separator:a5cc5f7e6658e3b1634d99b73dbfd06ab"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a574f179a8295301510bc8b5475f02ba8" id="r_a574f179a8295301510bc8b5475f02ba8"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a574f179a8295301510bc8b5475f02ba8">TEST_CASE</a> ("BNO08x Driver Cleanup <a class="el" href="#a4ac223c58b5ab6a6c5203661fafa1caa">for</a> [CallbackTests] Tests", "[CallbackTests]")</td></tr>
|
|
||||||
<tr class="separator:a574f179a8295301510bc8b5475f02ba8"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
</table><table class="memberdecls">
|
|
||||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a id="var-members" name="var-members"></a>
|
|
||||||
Variables</h2></td></tr>
|
|
||||||
<tr class="memitem:ac36e56130d5d806898f3545d4cdf0f70" id="r_ac36e56130d5d806898f3545d4cdf0f70"><td class="memItemLeft" align="right" valign="top"><a class="el" href="class_b_n_o08x.html">BNO08x</a> * </td><td class="memItemRight" valign="bottom"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> = nullptr</td></tr>
|
|
||||||
<tr class="separator:ac36e56130d5d806898f3545d4cdf0f70"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a22334b11e0558ec663d040de9b7db8c9" id="r_a22334b11e0558ec663d040de9b7db8c9"><td class="memItemLeft" align="right" valign="top"><a class="el" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">BNO08xTestHelper::imu_report_data_t</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a></td></tr>
|
|
||||||
<tr class="separator:a22334b11e0558ec663d040de9b7db8c9"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a8c57d66969fed0b55bdee9b57f6ed0a7" id="r_a8c57d66969fed0b55bdee9b57f6ed0a7"><td class="memItemLeft" align="right" valign="top"><a class="el" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">BNO08xTestHelper::imu_report_data_t</a> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a8c57d66969fed0b55bdee9b57f6ed0a7">prev_report_data</a></td></tr>
|
|
||||||
<tr class="separator:a8c57d66969fed0b55bdee9b57f6ed0a7"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a20cd776c25ed6d39b2dcb95d155cfbda" id="r_a20cd776c25ed6d39b2dcb95d155cfbda"><td class="memItemLeft" align="right" valign="top">const constexpr uint8_t </td><td class="memItemRight" valign="bottom"><a class="el" href="#a20cd776c25ed6d39b2dcb95d155cfbda">RX_REPORT_TRIAL_CNT</a> = 5</td></tr>
|
|
||||||
<tr class="separator:a20cd776c25ed6d39b2dcb95d155cfbda"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a4b80e39a1f48d801615a1f7baa210071" id="r_a4b80e39a1f48d801615a1f7baa210071"><td class="memItemLeft" align="right" valign="top">const constexpr uint32_t </td><td class="memItemRight" valign="bottom"><a class="el" href="#a4b80e39a1f48d801615a1f7baa210071">REPORT_PERIOD</a> = 100000UL</td></tr>
|
|
||||||
<tr class="separator:a4b80e39a1f48d801615a1f7baa210071"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a5a4ba60143c31271df0f72bf0e503876" id="r_a5a4ba60143c31271df0f72bf0e503876"><td class="memItemLeft" align="right" valign="top">bool </td><td class="memItemRight" valign="bottom"><a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a> = false</td></tr>
|
|
||||||
<tr class="separator:a5a4ba60143c31271df0f72bf0e503876"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a4e7be0e1e700243053709d7544201596" id="r_a4e7be0e1e700243053709d7544201596"><td class="memItemLeft" align="right" valign="top">char </td><td class="memItemRight" valign="bottom"><a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a> [200] = {}</td></tr>
|
|
||||||
<tr class="separator:a4e7be0e1e700243053709d7544201596"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:aafbc34af64f3c93123dce5a8238efd38" id="r_aafbc34af64f3c93123dce5a8238efd38"><td class="memItemLeft" align="right" valign="top">const constexpr uint8_t </td><td class="memItemRight" valign="bottom"><a class="el" href="#aafbc34af64f3c93123dce5a8238efd38">ENABLED_REPORT_CNT</a> = 2</td></tr>
|
|
||||||
<tr class="separator:aafbc34af64f3c93123dce5a8238efd38"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
</table>
|
|
||||||
<h2 class="groupheader">Function Documentation</h2>
|
|
||||||
<a id="a79547a2396efd083faeba3e54d94360d" name="a79547a2396efd083faeba3e54d94360d"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a79547a2396efd083faeba3e54d94360d">◆ </a></span>disable_accelerometer()</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> disable_accelerometer </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramname"><span class="paramname"></span></td><td>)</td>
|
|
||||||
<td></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a5cc5f7e6658e3b1634d99b73dbfd06ab" name="a5cc5f7e6658e3b1634d99b73dbfd06ab"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a5cc5f7e6658e3b1634d99b73dbfd06ab">◆ </a></span>disable_linear_accelerometer()</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> disable_linear_accelerometer </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramname"><span class="paramname"></span></td><td>)</td>
|
|
||||||
<td></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a0f2cacda77ab92640f739aca52b1f99f" name="a0f2cacda77ab92640f739aca52b1f99f"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a0f2cacda77ab92640f739aca52b1f99f">◆ </a></span>enable_accelerometer()</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> enable_accelerometer </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype"><a class="el" href="#a4b80e39a1f48d801615a1f7baa210071">REPORT_PERIOD</a></td> <td class="paramname"><span class="paramname"></span></td><td>)</td>
|
|
||||||
<td></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a3e937c8c4a4c07b81fb20077ee984fc0" name="a3e937c8c4a4c07b81fb20077ee984fc0"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a3e937c8c4a4c07b81fb20077ee984fc0">◆ </a></span>enable_linear_accelerometer()</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> enable_linear_accelerometer </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype"><a class="el" href="#a4b80e39a1f48d801615a1f7baa210071">REPORT_PERIOD</a></td> <td class="paramname"><span class="paramname"></span></td><td>)</td>
|
|
||||||
<td></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph.png" border="0" usemap="#a_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph" alt=""/></div>
|
|
||||||
<map name="a_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph" id="a_callback_tests_8cpp_a3e937c8c4a4c07b81fb20077ee984fc0_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,181,192,208"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ab56b185d6c9e972a2b28c2621387bb86" title="Checks if BNO08x has asserted interrupt and sent data." alt="" coords="250,60,409,87"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="125,178,287,92,290,97,127,183"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ade6be1fd8ef3a99e0edae4cbf25eb528" title="Resets internal test imu data with test defaults." alt="" coords="245,165,414,224"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="192,192,229,192,229,197,192,197"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2" title="Updates report data with calls relevant test_imu methods." alt="" coords="240,357,419,400"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="119,206,291,346,288,350,115,211"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4f12de628073f44b2a3fab2688cf1caf" title="Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse." alt="" coords="489,5,643,32"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="390,57,490,33,491,39,391,62"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885" title="Get full acceleration (total acceleration of device, units in m/s^2)." alt="" coords="499,56,633,83"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="344,355,380,302,417,235,429,194,433,159,440,126,450,110,465,93,483,80,486,85,469,97,454,113,445,128,438,160,434,195,421,237,384,304,349,358"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed" title="Get the current activity classifier (Seee Ref. Manual 6.5.36)" alt="" coords="495,107,638,149"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="342,355,465,159,479,150,482,155,469,163,346,358"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f" title="Get full rotational velocity with drift compensation (units in Rad/s)." alt="" coords="487,173,646,216"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="343,355,392,292,427,256,465,226,473,221,476,226,469,230,430,260,396,295,347,359"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a067678914e928a6691625b17c40237a0" title="Get full reported gravity vector, units in m/s^2." alt="" coords="496,240,636,267"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="353,355,403,315,466,276,482,270,484,275,468,281,406,319,356,359"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f" title="Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5...." alt="" coords="486,291,646,333"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="407,354,473,335,474,341,408,359"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46" title="Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2)." alt="" coords="499,357,633,400"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="420,376,484,376,484,381,420,381"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb" title="Get the full magnetic field vector." alt="" coords="501,424,632,451"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="419,398,495,417,493,422,418,403"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a" title="Get the full quaternion reading." alt="" coords="502,475,630,501"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="362,398,410,430,468,460,488,468,486,473,466,465,408,435,359,403"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27" title="Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6...." alt="" coords="467,525,665,552"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="349,399,398,455,431,485,468,511,480,517,478,522,466,516,428,490,394,459,345,402"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a248544b262582d10d917a687190cb454" title="Get the current stability classifier (Seee Ref. Manual 6.5.31)" alt="" coords="492,576,640,619"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="343,399,363,434,390,478,426,523,469,562,480,569,477,573,465,566,422,527,386,481,358,437,339,402"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef" title="Get the counted amount of steps." alt="" coords="483,643,650,669"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="339,400,354,448,379,510,417,574,441,603,469,629,475,633,472,637,465,633,437,607,413,577,375,512,349,449,333,401"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104" title="Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv..." alt="" coords="480,693,653,736"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="337,400,350,456,374,531,392,571,413,610,439,647,469,679,472,682,468,686,465,683,435,650,409,613,387,573,369,533,345,457,332,401"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9" title="Converts a register value to a float using its associated Q point. (See https://en...." alt="" coords="713,332,848,359"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="635,75,667,93,692,117,713,145,745,207,766,267,777,316,772,317,760,269,740,209,708,148,688,121,664,97,632,80"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="645,214,667,226,695,247,722,271,762,318,758,321,718,275,692,251,664,230,642,219"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="633,265,666,276,710,298,748,321,745,325,707,302,664,281,631,270"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="647,322,698,330,697,335,647,327"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="633,366,697,355,698,361,634,371"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="631,421,664,410,707,388,745,365,748,370,710,393,666,414,633,426"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="630,475,664,460,693,440,718,417,759,370,763,373,722,420,696,445,667,465,632,480"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="649,691,663,679,693,644,716,604,735,562,750,519,768,437,775,374,780,375,773,438,755,520,740,564,721,607,697,647,667,683,653,695"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a4ac223c58b5ab6a6c5203661fafa1caa" name="a4ac223c58b5ab6a6c5203661fafa1caa"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a4ac223c58b5ab6a6c5203661fafa1caa">◆ </a></span>for()</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">for </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramname"><span class="paramname"></span></td><td>)</td>
|
|
||||||
<td></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph.png" border="0" usemap="#a_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph" alt=""/></div>
|
|
||||||
<map name="a_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph" id="a_callback_tests_8cpp_a4ac223c58b5ab6a6c5203661fafa1caa_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,189,44,216"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ab56b185d6c9e972a2b28c2621387bb86" title="Checks if BNO08x has asserted interrupt and sent data." alt="" coords="102,48,261,75"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="35,187,90,126,145,82,149,86,94,130,39,190"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ade6be1fd8ef3a99e0edae4cbf25eb528" title="Resets internal test imu data with test defaults." alt="" coords="97,140,266,199"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="44,196,81,188,82,193,45,201"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="100,223,263,249"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="45,204,101,216,100,221,44,209"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2" title="Updates report data with calls relevant test_imu methods." alt="" coords="92,357,271,400"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="40,215,153,344,149,347,36,218"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4f12de628073f44b2a3fab2688cf1caf" title="Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse." alt="" coords="341,5,495,32"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="259,45,325,33,326,38,260,50"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885" title="Get full acceleration (total acceleration of device, units in m/s^2)." alt="" coords="351,56,485,83"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="201,355,235,313,269,260,278,236,283,213,285,172,291,133,300,113,317,93,335,80,338,84,321,97,305,116,296,134,290,173,288,214,283,237,273,263,240,316,205,359"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed" title="Get the current activity classifier (Seee Ref. Manual 6.5.36)" alt="" coords="347,107,490,149"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="199,355,233,312,269,260,282,232,288,207,297,183,317,159,331,149,334,153,321,163,302,186,293,209,287,233,273,263,237,315,203,358"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f" title="Get full rotational velocity with drift compensation (units in Rad/s)." alt="" coords="339,173,498,216"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="195,355,244,292,279,256,318,226,325,221,328,226,321,230,282,260,248,295,199,359"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a067678914e928a6691625b17c40237a0" title="Get full reported gravity vector, units in m/s^2." alt="" coords="348,240,488,267"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="205,355,255,315,318,276,334,270,336,275,320,281,258,319,208,359"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f" title="Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5...." alt="" coords="338,291,498,333"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="259,354,325,335,326,341,260,359"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46" title="Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2)." alt="" coords="351,357,485,400"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="272,376,336,376,336,381,272,381"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb" title="Get the full magnetic field vector." alt="" coords="353,424,484,451"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="271,398,347,417,346,422,270,403"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a" title="Get the full quaternion reading." alt="" coords="354,475,482,501"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="214,398,262,430,320,460,340,468,339,473,318,465,260,435,211,403"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27" title="Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6...." alt="" coords="319,525,517,552"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="201,399,250,455,283,485,320,511,332,517,330,522,318,516,280,490,246,459,197,402"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a248544b262582d10d917a687190cb454" title="Get the current stability classifier (Seee Ref. Manual 6.5.31)" alt="" coords="344,576,492,619"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="195,399,215,434,243,478,278,523,321,562,332,569,329,573,317,566,274,527,238,481,210,437,191,402"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef" title="Get the counted amount of steps." alt="" coords="335,643,502,669"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="191,400,206,448,232,510,270,574,293,603,321,629,327,633,324,637,317,633,289,607,265,577,227,512,201,449,186,401"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104" title="Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv..." alt="" coords="332,693,505,736"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="189,400,202,456,226,531,244,571,265,610,291,647,321,679,324,682,321,686,317,683,287,650,261,613,239,573,221,533,197,457,184,401"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9" title="Converts a register value to a float using its associated Q point. (See https://en...." alt="" coords="565,332,700,359"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="487,75,519,93,544,117,565,145,597,207,618,267,629,316,624,317,612,269,592,209,560,148,540,121,516,97,484,80"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="497,214,519,226,547,247,574,271,614,318,610,321,570,275,544,251,516,230,494,219"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="485,265,518,276,562,298,600,321,598,325,559,302,516,281,483,270"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="499,322,550,330,549,335,499,327"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="486,366,550,355,550,361,486,371"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="483,421,516,410,559,388,598,365,600,370,562,393,518,414,485,426"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="482,475,516,460,545,440,570,417,611,370,615,373,574,420,548,445,519,465,484,480"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="501,691,516,679,545,644,569,604,587,562,602,519,620,437,627,374,632,375,625,438,607,520,592,564,573,607,549,647,519,683,505,695"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a6df8508e34beaeb28f34554ce0e20573" name="a6df8508e34beaeb28f34554ce0e20573"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a6df8508e34beaeb28f34554ce0e20573">◆ </a></span>register_cb() <span class="overload">[1/2]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> register_cb </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">[&imu, &new_data, &report_data, &prev_report_data, &msg_buff] () { static int cb_execution_cnt=0;cb_execution_cnt++;<a class="el" href="class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2">BNO08xTestHelper::update_report_data</a>(&<a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a>);if(<a class="el" href="class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea">BNO08xTestHelper::accelerometer_data_is_new</a>(&<a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, &<a class="el" href="#a8c57d66969fed0b55bdee9b57f6ed0a7">prev_report_data</a>)) { <a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a>=true;sprintf(<a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>, "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, <a class="el" href="class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3">BNO08xTestHelper::BNO08xAccuracy_to_str</a>(report_data.accel_accuracy));<a class="el" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002">BNO08xTestHelper::print_test_msg</a>(TEST_TAG, <a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>);} }</td> <td class="paramname"><span class="paramname"></span></td><td>)</td>
|
|
||||||
<td></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph.png" border="0" usemap="#a_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph" alt=""/></div>
|
|
||||||
<map name="a_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph" id="a_callback_tests_8cpp_a6df8508e34beaeb28f34554ce0e20573_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,244,91,271"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea" title="Checks if report_data matches the default states stored within prev_report_data data for respective r..." alt="" coords="139,136,361,179"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="62,242,95,215,137,188,150,182,152,187,140,193,98,219,66,246"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3" title="Converts BNO08xAccuracy enum class object to string." alt="" coords="155,203,345,245"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="91,248,140,240,140,245,92,253"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="167,269,333,312"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="92,262,152,272,151,277,91,267"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2" title="Updates report data with calls relevant test_imu methods." alt="" coords="160,336,340,379"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="66,269,98,295,140,322,152,327,150,332,137,326,95,300,62,273"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885" title="Get full acceleration (total acceleration of device, units in m/s^2)." alt="" coords="441,5,575,32"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="338,338,359,322,381,288,389,253,388,219,382,184,376,149,375,113,383,78,407,42,425,29,428,33,411,46,388,80,380,114,381,148,387,183,393,218,394,254,386,290,363,326,342,343"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed" title="Get the current activity classifier (Seee Ref. Manual 6.5.36)" alt="" coords="437,56,580,99"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="338,338,359,322,377,296,385,270,385,244,383,218,380,191,381,164,389,137,407,109,421,97,425,101,411,112,393,139,386,165,385,191,388,217,391,244,390,271,382,299,363,326,342,342"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f" title="Get full rotational velocity with drift compensation (units in Rad/s)." alt="" coords="429,123,588,165"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="338,337,359,322,373,305,380,287,383,251,385,214,393,194,407,176,414,169,417,173,411,179,397,197,391,215,388,251,385,288,377,307,363,326,342,341"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a067678914e928a6691625b17c40237a0" title="Get full reported gravity vector, units in m/s^2." alt="" coords="438,189,578,216"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="338,335,359,322,370,311,376,299,382,275,389,250,396,238,407,226,422,216,425,221,411,230,400,241,393,252,387,276,381,301,374,314,363,326,341,340"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f" title="Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5...." alt="" coords="428,240,588,283"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="331,333,360,322,384,307,408,292,421,286,424,291,410,297,386,312,362,326,333,338"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46" title="Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2)." alt="" coords="441,307,575,349"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="340,345,425,335,426,340,340,350"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb" title="Get the full magnetic field vector." alt="" coords="443,373,574,400"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="340,365,427,375,427,380,340,370"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a" title="Get the full quaternion reading." alt="" coords="444,424,572,451"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="312,377,410,409,436,417,434,422,408,415,310,382"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27" title="Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6...." alt="" coords="409,475,607,501"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="279,377,337,419,410,460,427,467,425,472,408,465,334,424,276,381"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a248544b262582d10d917a687190cb454" title="Get the current stability classifier (Seee Ref. Manual 6.5.31)" alt="" coords="434,525,582,568"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="270,377,328,443,367,479,410,511,421,517,418,522,408,516,364,483,324,447,266,381"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef" title="Get the counted amount of steps." alt="" coords="425,592,592,619"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="263,378,284,421,316,475,358,531,383,556,411,578,419,583,416,587,407,582,380,560,354,534,311,478,279,423,258,380"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104" title="Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv..." alt="" coords="422,643,595,685"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="260,378,279,429,310,497,354,567,381,600,411,629,415,632,412,636,407,633,377,604,349,571,305,499,274,431,255,380"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9" title="Converts a register value to a float using its associated Q point. (See https://en...." alt="" coords="655,281,790,308"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="577,25,609,42,634,67,655,95,687,156,708,217,719,265,714,267,702,218,682,159,650,98,630,70,606,46,574,30"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="587,163,609,175,637,196,664,221,704,267,700,271,660,224,634,200,606,180,584,168"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="575,214,608,226,652,247,690,270,687,275,649,252,606,230,573,219"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="589,271,640,279,639,284,589,276"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="575,315,639,305,640,310,576,320"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="573,370,606,359,649,338,687,315,690,319,652,342,608,364,575,375"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="572,424,606,410,635,390,660,366,701,319,705,323,664,370,638,394,609,414,574,429"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="591,640,605,629,635,594,658,554,677,511,692,468,710,386,717,323,722,324,715,387,697,469,682,513,663,556,639,597,609,633,595,644"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a8dba989b01b464871f3232223050ec73" name="a8dba989b01b464871f3232223050ec73"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a8dba989b01b464871f3232223050ec73">◆ </a></span>register_cb() <span class="overload">[2/2]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname"><a class="el" href="#ac36e56130d5d806898f3545d4cdf0f70">imu</a> register_cb </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">[&imu, &new_data, &report_data, &prev_report_data, &msg_buff] () { static int cb_execution_cnt=0;cb_execution_cnt++;<a class="el" href="class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2">BNO08xTestHelper::update_report_data</a>(&<a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a>);if(<a class="el" href="class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea">BNO08xTestHelper::accelerometer_data_is_new</a>(&<a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, &<a class="el" href="#a8c57d66969fed0b55bdee9b57f6ed0a7">prev_report_data</a>)) { <a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a>[0]=true;sprintf(<a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>, "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, <a class="el" href="class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3">BNO08xTestHelper::BNO08xAccuracy_to_str</a>(report_data.accel_accuracy));<a class="el" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002">BNO08xTestHelper::print_test_msg</a>(TEST_TAG, <a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>);} if(<a class="el" href="class_b_n_o08x_test_helper.html#ad398739ce46400c1ac35e1cf7603d590">BNO08xTestHelper::linear_accelerometer_data_is_new</a>(&<a class="el" href="#a22334b11e0558ec663d040de9b7db8c9">report_data</a>, &<a class="el" href="#a8c57d66969fed0b55bdee9b57f6ed0a7">prev_report_data</a>)) { <a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a>[1]=true;sprintf(<a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>, "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, <a class="el" href="class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3">BNO08xTestHelper::BNO08xAccuracy_to_str</a>(report_data.lin_accel_accuracy));<a class="el" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002">BNO08xTestHelper::print_test_msg</a>(TEST_TAG, <a class="el" href="#a4e7be0e1e700243053709d7544201596">msg_buff</a>);} }</td> <td class="paramname"><span class="paramname"></span></td><td>)</td>
|
|
||||||
<td></td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph.png" border="0" usemap="#a_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph" alt=""/></div>
|
|
||||||
<map name="a_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph" id="a_callback_tests_8cpp_a8dba989b01b464871f3232223050ec73_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,211,91,237"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea" title="Checks if report_data matches the default states stored within prev_report_data data for respective r..." alt="" coords="139,69,361,112"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="56,209,88,166,111,142,137,122,145,117,148,122,140,126,115,146,92,169,60,212"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3" title="Converts BNO08xAccuracy enum class object to string." alt="" coords="155,136,345,179"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="84,208,138,188,159,181,160,186,140,193,86,213"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ad398739ce46400c1ac35e1cf7603d590" title="Checks if report_data matches the default states stored within prev_report_data data for respective r..." alt="" coords="155,203,345,245"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="91,221,140,221,140,227,91,227"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="167,269,333,312"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="86,235,140,255,160,262,159,267,138,260,84,240"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2" title="Updates report data with calls relevant test_imu methods." alt="" coords="160,336,340,379"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="60,236,92,279,115,302,140,322,148,326,145,331,137,326,111,306,88,282,56,239"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885" title="Get full acceleration (total acceleration of device, units in m/s^2)." alt="" coords="441,5,575,32"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="338,338,359,322,381,288,389,253,388,219,382,184,376,149,375,113,383,78,407,42,425,29,428,33,411,46,388,80,380,114,381,148,387,183,393,218,394,254,386,290,363,326,342,343"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed" title="Get the current activity classifier (Seee Ref. Manual 6.5.36)" alt="" coords="437,56,580,99"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="338,338,359,322,377,296,385,270,385,244,383,218,380,191,381,164,389,137,407,109,421,97,425,101,411,112,393,139,386,165,385,191,388,217,391,244,390,271,382,299,363,326,342,342"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f" title="Get full rotational velocity with drift compensation (units in Rad/s)." alt="" coords="429,123,588,165"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="338,337,359,322,373,305,380,287,383,251,385,214,393,194,407,176,414,169,417,173,411,179,397,197,391,215,388,251,385,288,377,307,363,326,342,341"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a067678914e928a6691625b17c40237a0" title="Get full reported gravity vector, units in m/s^2." alt="" coords="438,189,578,216"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="338,335,359,322,370,311,376,299,382,275,389,250,396,238,407,226,422,216,425,221,411,230,400,241,393,252,387,276,381,301,374,314,363,326,341,340"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f" title="Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5...." alt="" coords="428,240,588,283"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="331,333,360,322,384,307,408,292,421,286,424,291,410,297,386,312,362,326,333,338"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46" title="Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2)." alt="" coords="441,307,575,349"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="340,345,425,335,426,340,340,350"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb" title="Get the full magnetic field vector." alt="" coords="443,373,574,400"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="340,365,427,375,427,380,340,370"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a" title="Get the full quaternion reading." alt="" coords="444,424,572,451"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="312,377,410,409,436,417,434,422,408,415,310,382"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27" title="Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6...." alt="" coords="409,475,607,501"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="279,377,337,419,410,460,427,467,425,472,408,465,334,424,276,381"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a248544b262582d10d917a687190cb454" title="Get the current stability classifier (Seee Ref. Manual 6.5.31)" alt="" coords="434,525,582,568"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="270,377,328,443,367,479,410,511,421,517,418,522,408,516,364,483,324,447,266,381"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef" title="Get the counted amount of steps." alt="" coords="425,592,592,619"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="263,378,284,421,316,475,358,531,383,556,411,578,419,583,416,587,407,582,380,560,354,534,311,478,279,423,258,380"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104" title="Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv..." alt="" coords="422,643,595,685"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="260,378,279,429,310,497,354,567,381,600,411,629,415,632,412,636,407,633,377,604,349,571,305,499,274,431,255,380"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9" title="Converts a register value to a float using its associated Q point. (See https://en...." alt="" coords="655,281,790,308"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="577,25,609,42,634,67,655,95,687,156,708,217,719,265,714,267,702,218,682,159,650,98,630,70,606,46,574,30"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="587,163,609,175,637,196,664,221,704,267,700,271,660,224,634,200,606,180,584,168"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="575,214,608,226,652,247,690,270,687,275,649,252,606,230,573,219"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="589,271,640,279,639,284,589,276"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="575,315,639,305,640,310,576,320"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="573,370,606,359,649,338,687,315,690,319,652,342,608,364,575,375"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="572,424,606,410,635,390,660,366,701,319,705,323,664,370,638,394,609,414,574,429"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="591,640,605,629,635,594,658,554,677,511,692,468,710,386,717,323,722,324,715,387,697,469,682,513,663,556,639,597,609,633,595,644"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a9091949d4ea860523915687536d5c4d3" name="a9091949d4ea860523915687536d5c4d3"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a9091949d4ea860523915687536d5c4d3">◆ </a></span>TEST_ASSERT_EQUAL() <span class="overload">[1/2]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">TEST_ASSERT_EQUAL </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">true</td> <td class="paramname"><span class="paramname">, </span></td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
|
||||||
<td class="paramkey"></td>
|
|
||||||
<td></td>
|
|
||||||
<td class="paramtype"><a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a></td> <td class="paramname"><span class="paramname">[0]</span> )</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the caller graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph.png" border="0" usemap="#a_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph" alt=""/></div>
|
|
||||||
<map name="a_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph" id="a_callback_tests_8cpp_a9091949d4ea860523915687536d5c4d3_icgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="150,715,313,741"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html#a4ac223c58b5ab6a6c5203661fafa1caa" title=" " alt="" coords="34,5,73,32"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="225,699,213,563,188,369,171,269,151,176,127,99,100,46,87,34,72,27,74,22,90,30,104,42,132,97,156,175,176,267,193,368,218,563,231,699"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html#ac18b9cb122499f587331d82a538f23aa" title=" " alt="" coords="5,56,102,83"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="225,699,211,572,185,393,168,301,148,216,125,146,100,96,88,85,91,81,104,93,130,143,153,215,173,300,191,392,216,572,230,699"/>
|
|
||||||
<area shape="rect" href="_multi_report_tests_8cpp.html#a1fd7b6a0d4dbb7f91fd5691b5b054bda" title=" " alt="" coords="5,107,102,133"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="224,699,209,581,183,417,165,333,146,256,124,192,100,147,87,136,91,132,104,144,128,190,151,254,171,332,188,416,214,581,229,699"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#aac644123799c1f836d379c9789a064ab" title=" " alt="" coords="5,157,102,184"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="228,699,226,607,220,544,210,475,194,403,171,330,140,261,100,198,87,186,91,182,104,194,145,258,176,329,199,402,215,474,225,544,231,606,233,699"/>
|
|
||||||
<area shape="rect" href="_multi_report_tests_8cpp.html#aa9e0389fa75046b52d13286af2c3b2a7" title=" " alt="" coords="5,208,102,235"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="227,699,222,614,204,496,188,431,166,367,137,305,100,248,87,237,90,233,104,245,141,302,171,365,193,430,210,495,227,614,233,699"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#aaefa1a1d4b3c190b7f46bb7f42512949" title=" " alt="" coords="5,259,102,285"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="226,700,219,623,199,518,183,461,161,403,134,349,100,299,87,288,90,284,104,296,138,346,166,401,188,459,204,517,224,622,231,699"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#a098111e0f361615318674b5b1b05ece4" title=" " alt="" coords="5,309,102,336"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="225,700,215,631,193,539,177,489,156,440,131,393,100,350,86,338,90,334,104,346,135,390,161,438,182,487,198,538,220,630,230,699"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#a35b0417a053d9fbf61a91a2110c3495c" title=" " alt="" coords="5,360,102,387"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="223,700,211,640,187,561,151,477,127,437,100,401,86,389,89,385,104,397,132,434,156,474,192,559,216,638,228,699"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#af9d07441bd8651bc21743664b7f99bb8" title=" " alt="" coords="5,411,102,437"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="221,700,206,649,181,583,146,514,124,481,100,451,85,440,89,436,104,447,129,478,151,511,186,581,211,647,226,699"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#ace1544ccc126d0b9eadd433f9cb41486" title=" " alt="" coords="5,461,102,488"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="218,701,200,659,175,606,141,551,100,502,85,491,88,486,104,498,145,548,179,604,205,657,223,699"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#a90980a9fc26b3a692ab2529c9f8e4747" title=" " alt="" coords="5,512,102,539"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="214,703,168,630,136,590,100,553,84,541,87,537,103,549,140,586,172,627,218,700"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#ab9b4ae43e33572d90c4c889452cd91ee" title=" " alt="" coords="5,563,102,589"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="207,705,160,655,100,603,82,592,85,588,103,599,163,651,210,701"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#a713376354af2a970230882e2a487050e" title=" " alt="" coords="5,613,102,640"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="193,709,100,654,79,643,82,638,103,650,196,704"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#ae4d70e11995e36808b6390b171aba0e8" title=" " alt="" coords="5,664,102,691"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="166,712,101,693,103,688,168,707"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#a429f6e7897a9609ddd093d66b6f7b1ff" title=" " alt="" coords="5,715,102,741"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="134,731,102,731,102,725,134,725"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#ae436161f7f0085f01ce63d9373944ae8" title=" " alt="" coords="5,765,102,792"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="168,749,103,768,101,763,166,744"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#acf249e215fca056266de6e833875925e" title=" " alt="" coords="5,816,102,843"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="196,752,103,806,82,818,79,813,100,802,193,747"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#a9f2e049a5b61721869c5f4757e313502" title=" " alt="" coords="5,867,102,893"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="210,755,163,805,103,857,85,868,82,864,100,853,160,801,207,751"/>
|
|
||||||
<area shape="rect" href="_single_report_tests_8cpp.html#a3cce613b379b768244a176a32b37667c" title=" " alt="" coords="5,917,102,944"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="218,756,172,829,140,870,103,907,87,919,84,915,100,903,136,866,168,826,214,753"/>
|
|
||||||
<area shape="rect" href="_init_deinit_tests_8cpp.html#a69680e2934e7ec3c6a1771270dc59f05" title=" " alt="" coords="5,968,102,995"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="223,757,205,799,179,852,145,908,104,958,88,970,85,965,100,954,141,905,175,850,200,797,218,755"/>
|
|
||||||
<area shape="rect" href="_multi_report_tests_8cpp.html#ad96cfd7c30e8693897688ce24bb53996" title=" " alt="" coords="5,1019,102,1045"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="226,757,211,809,186,875,151,945,129,978,104,1009,89,1020,85,1016,100,1005,124,975,146,942,181,873,206,807,221,756"/>
|
|
||||||
<area shape="rect" href="_init_deinit_tests_8cpp.html#ac4fb371054271d54830b58cc164dc0f6" title=" " alt="" coords="5,1069,102,1096"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="228,757,216,818,192,897,156,982,132,1022,104,1059,89,1071,86,1067,100,1055,127,1019,151,979,187,895,211,816,223,756"/>
|
|
||||||
<area shape="rect" href="_init_deinit_tests_8cpp.html#a6ed5310154fb7e7f290e619e6fbed708" title=" " alt="" coords="5,1120,102,1147"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="230,757,220,826,198,918,182,969,161,1018,135,1066,104,1110,90,1122,86,1118,100,1106,131,1063,156,1016,177,967,193,917,215,825,225,756"/>
|
|
||||||
<area shape="rect" href="_init_deinit_tests_8cpp.html#a96d79e5c8f3096a207d806be926af15b" title=" " alt="" coords="5,1171,102,1197"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="231,757,224,834,204,939,188,997,166,1055,138,1110,104,1160,90,1172,87,1168,100,1157,134,1107,161,1053,183,995,199,938,219,833,226,756"/>
|
|
||||||
<area shape="rect" href="_init_deinit_tests_8cpp.html#ab8015ecd4179bc39223921d6eef1165a" title=" " alt="" coords="5,1221,102,1248"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="233,757,227,842,210,961,193,1026,171,1091,141,1154,104,1211,90,1223,87,1219,100,1208,137,1151,166,1089,188,1025,204,960,222,842,227,757"/>
|
|
||||||
<area shape="rect" href="_init_deinit_tests_8cpp.html#ad71fea7e4a2e587d48d2bf7fadd711cc" title=" " alt="" coords="5,1272,102,1299"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="233,757,231,850,225,912,215,982,199,1054,176,1127,145,1198,104,1262,91,1274,87,1270,100,1258,140,1195,171,1126,194,1053,210,981,220,912,226,849,228,757"/>
|
|
||||||
<area shape="rect" href="_init_deinit_tests_8cpp.html#a9f7d58c894a252a5d5f4926f43c1da05" title=" " alt="" coords="5,1323,102,1349"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="229,757,214,875,188,1040,171,1124,151,1202,128,1266,104,1312,91,1324,87,1320,100,1309,124,1264,146,1200,165,1123,183,1039,209,875,224,757"/>
|
|
||||||
<area shape="rect" href="_multi_report_tests_8cpp.html#a1438f6b8587b635b6096dda2927fa9a1" title=" " alt="" coords="5,1373,102,1400"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="230,757,216,884,191,1064,173,1156,153,1241,130,1313,104,1363,91,1375,88,1371,100,1360,125,1310,148,1240,168,1155,185,1063,211,884,225,757"/>
|
|
||||||
<area shape="rect" href="_multi_report_tests_8cpp.html#a915d6c272bf95057a8bb22abfb307882" title=" " alt="" coords="5,1424,102,1451"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="231,757,218,893,193,1088,176,1189,156,1281,132,1359,104,1414,91,1425,88,1421,100,1410,127,1357,151,1280,171,1187,188,1087,213,893,225,757"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="aa6754207db4cfba956441680c7a6a97d" name="aa6754207db4cfba956441680c7a6a97d"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#aa6754207db4cfba956441680c7a6a97d">◆ </a></span>TEST_ASSERT_EQUAL() <span class="overload">[2/2]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">TEST_ASSERT_EQUAL </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">true</td> <td class="paramname"><span class="paramname">, </span></td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
|
||||||
<td class="paramkey"></td>
|
|
||||||
<td></td>
|
|
||||||
<td class="paramtype"><a class="el" href="#a5a4ba60143c31271df0f72bf0e503876">new_data</a></td> <td class="paramname"><span class="paramname">[1]</span> )</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a574f179a8295301510bc8b5475f02ba8" name="a574f179a8295301510bc8b5475f02ba8"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a574f179a8295301510bc8b5475f02ba8">◆ </a></span>TEST_CASE() <span class="overload">[1/2]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">TEST_CASE </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">"BNO08x Driver Cleanup <a class="el" href="#a4ac223c58b5ab6a6c5203661fafa1caa">for</a> Tests"</td> <td class="paramname"><span class="paramname">[CallbackTests], </span></td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
|
||||||
<td class="paramkey"></td>
|
|
||||||
<td></td>
|
|
||||||
<td class="paramtype">""</td> <td class="paramname"><span class="paramname">[CallbackTests]</span> )</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph.png" border="0" usemap="#a_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph" alt=""/></div>
|
|
||||||
<map name="a_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph" id="a_callback_tests_8cpp_a574f179a8295301510bc8b5475f02ba8_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,47,102,73"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="150,5,333,48"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="102,49,134,43,135,48,103,54"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="159,72,324,115"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="103,66,144,73,143,79,102,71"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="ac18b9cb122499f587331d82a538f23aa" name="ac18b9cb122499f587331d82a538f23aa"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#ac18b9cb122499f587331d82a538f23aa">◆ </a></span>TEST_CASE() <span class="overload">[2/2]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">TEST_CASE </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">"BNO08x Driver Creation <a class="el" href="#a4ac223c58b5ab6a6c5203661fafa1caa">for</a> Tests"</td> <td class="paramname"><span class="paramname">[CallbackTests], </span></td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
|
||||||
<td class="paramkey"></td>
|
|
||||||
<td></td>
|
|
||||||
<td class="paramtype">""</td> <td class="paramname"><span class="paramname">[CallbackTests]</span> )</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph.png" border="0" usemap="#a_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph" alt=""/></div>
|
|
||||||
<map name="a_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph" id="a_callback_tests_8cpp_ac18b9cb122499f587331d82a538f23aa_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,263,102,289"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a6bd040c7d670a9713f2ab8a8a3913518" title="Calls BNO08x constructor and creates new test IMU on heap." alt="" coords="150,93,326,136"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="66,261,148,182,194,144,198,148,151,186,70,264"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="159,196,317,239"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="97,260,154,241,155,246,99,265"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#aea8e2c6dd7a2c9899479a7f39fe94798" title="Initializes BNO08x sensor." alt="" coords="175,263,301,289"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="102,273,160,273,160,279,102,279"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="155,313,321,356"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="99,287,155,306,154,311,97,292"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="156,380,320,407"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="67,288,102,326,125,348,151,366,162,371,159,376,148,370,122,352,98,330,63,291"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="374,56,557,99"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="326,98,358,92,359,98,327,103"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a96d47dd0f9aedfbe3f731f8ae76b2e85" title="Requests product ID, prints the returned info over serial, and returns the reason for the most resent..." alt="" coords="377,123,555,149"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="300,262,324,249,341,229,348,208,355,186,372,165,388,154,391,158,376,169,360,189,353,210,345,231,328,253,302,267"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a28cd1c0b3477571d87133234e6358503" title="Hard resets BNO08x sensor." alt="" coords="396,179,535,205"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="293,260,325,248,349,235,373,222,405,209,407,213,375,226,351,240,327,253,295,265"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a589eb9780f5bf613bbd447ef5b9ade3d" title="Initializes required esp-idf SPI data structures with values from user passed bno08x_config_t struct." alt="" coords="382,236,550,263"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="300,266,365,258,366,264,301,271"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ae0dab25557befcf62bf384fdc241ef10" title="Initializes required gpio." alt="" coords="403,288,529,315"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="301,280,387,290,387,295,300,286"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#aa27026da2c52b4aca49b78863f10ec61" title="Initializes host interrupt ISR." alt="" coords="394,339,538,365"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="294,287,327,299,375,324,394,331,392,336,373,329,325,304,292,292"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a58f43c8bb1e7fe8560ce442d46240e81" title="Initializes SPI." alt="" coords="406,389,525,416"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="302,286,328,299,345,319,352,338,360,357,376,375,393,385,390,390,372,379,355,360,347,340,340,321,324,303,300,290"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a06f99a6b2182b49a0e61e2107f2be6be" title="Launches spi_task and data_proc_task on constructor call." alt="" coords="388,451,543,477"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="302,284,328,299,341,315,349,332,353,364,357,395,364,411,376,426,397,441,393,446,372,430,359,413,352,397,348,364,344,333,337,318,324,303,299,288"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ab5f200069a2f8cb74cb79c6f162da5a1" title="Queues a packet containing the request product ID command." alt="" coords="621,5,784,48"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="532,120,556,108,570,97,579,84,589,71,604,58,612,53,614,58,607,62,593,75,584,87,574,100,559,113,534,124"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4f12de628073f44b2a3fab2688cf1caf" title="Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse." alt="" coords="625,72,780,99"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="531,119,621,100,622,105,532,125"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a7cdeb849e728487de961cdfd4030c773" title="Waits for a queued packet to be sent or host_int_timeout_ms to elapse." alt="" coords="615,123,790,149"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="555,133,599,133,599,139,555,139"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a62c570ba96512f4d0d10b2594048de1f" title="Queues an SHTP packet to be sent via SPI." alt="" coords="852,13,1011,40"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="784,24,836,24,836,29,784,29"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a2897a178bf2c53cd99df0d4570edf72e" title="Waits for data to be received over SPI, or host_int_timeout_ms to elapse." alt="" coords="615,173,790,200"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="536,188,600,186,600,192,536,193"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a453ec8a70646651d4e5b10bf0b2e4d61" title="Resets all data returned by public getter APIs to initial values of 0 and low accuracy." alt="" coords="623,224,782,267"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="550,245,608,244,608,250,550,251"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8f34d5475474f00ae6a92f73c1fe14e4" title="Initializes required gpio inputs." alt="" coords="618,291,787,317"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="529,299,603,300,603,306,529,305"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ad0b9e8f8d051798bb1da9b19598dbd64" title="Initializes required gpio outputs." alt="" coords="614,341,791,368"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="529,313,626,335,625,340,527,318"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a804b95c58c30d36933fd251626b85bf7" title="HINT interrupt service routine, handles falling edge of BNO08x HINT pin." alt="" coords="628,392,777,419"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="529,363,626,385,625,391,527,368"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a0ae135d7bf7a5f047a1d1aa5cc07e520" title="Static function used to launch data processing task." alt="" coords="619,443,786,485"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="544,461,603,461,603,467,544,467"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a0ce6d9db873555f1ebe7e095251eab74" title="Static function used to launch spi task." alt="" coords="605,532,800,559"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="508,475,648,524,646,529,506,481"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ab4373e9b87837ea9fcbc0b536338c7b8" title="Task responsible parsing packets. Executed when SPI task sends a packet to be parsed,..." alt="" coords="848,440,1015,467"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="787,457,832,455,832,461,787,463"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a1c47d27917ae3b2876efa121b803f924" title="Parses a packet received from bno08x, updating any data according to received reports." alt="" coords="1067,377,1223,404"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="979,437,1081,406,1083,412,980,442"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a05e4cd5861b55fc0182d7dd13bb85e49" title="Prints the passed SHTP packet to serial console with ESP_LOG statement." alt="" coords="1071,440,1220,467"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1016,451,1055,451,1055,456,1016,456"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4f66045a0528a0c17c52421ea51612e7" title="Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)" alt="" coords="1288,161,1462,204"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1150,376,1168,343,1195,300,1230,254,1274,214,1280,209,1283,214,1277,218,1234,257,1199,303,1172,346,1155,378"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a206c0e3ddc3b745b56914976d6e69981" title="Parses get feature request report received from BNO08x." alt="" coords="1297,228,1453,271"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1158,375,1206,329,1239,303,1274,280,1284,275,1287,280,1277,285,1242,308,1210,333,1161,379"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a51b360d795563b55559f11efb40be36a" title="Sends packet to be parsed to meta data function call (FRS_read_data()) through queue." alt="" coords="1293,295,1457,337"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1188,374,1292,340,1294,345,1190,379"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a7be6047fef851a064c7cbc9eba092f6d" title="Parses received gyro integrated rotation vector report sent by BNO08x." alt="" coords="1304,361,1446,420"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1223,388,1288,388,1288,393,1223,393"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8d9db3e1b6208c2661e1c543deefa53d" title="Parses received input report sent by BNO08x." alt="" coords="1302,444,1448,487"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1190,402,1294,436,1292,441,1188,407"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a29cfd7fc2816483ebebe9d55b677a036" title="Parses product id report and prints device info." alt="" coords="1295,511,1455,553"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1189,402,1229,426,1245,445,1253,463,1261,480,1277,497,1283,501,1280,505,1274,501,1257,483,1248,465,1241,448,1226,430,1186,407"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ab02386f13caa446bab5921c1a71f92ab" title="Updates integrated gyro rotation vector data from SHTP channel 5 (CHANNEL_GYRO) special report data." alt="" coords="1551,151,1733,193"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1445,368,1473,347,1486,330,1492,312,1495,276,1498,240,1506,221,1521,203,1535,192,1539,196,1525,207,1511,224,1504,241,1500,276,1497,313,1490,332,1477,351,1448,372"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a002aa97c9af8f6df2d0c83034e4f7b55" title="Parses data from received input report." alt="" coords="1569,217,1715,260"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1447,448,1473,430,1487,411,1494,391,1495,351,1497,311,1505,290,1521,270,1536,258,1554,249,1556,254,1539,263,1525,274,1510,293,1503,312,1501,352,1499,392,1492,413,1477,434,1450,452"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#afe588fbd0055193d3bc08984d7732354" title="Updates accelerometer data from parsed input report." alt="" coords="1523,284,1761,311"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1447,447,1473,430,1484,417,1490,404,1495,376,1501,348,1508,334,1521,321,1526,317,1530,321,1524,325,1513,337,1506,350,1501,377,1495,405,1489,420,1476,434,1449,451"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a962b695ef4733d558c6f9684da0931ab" title="Updates linear gyro data from parsed input report." alt="" coords="1552,335,1732,377"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1447,442,1473,430,1487,419,1497,409,1506,398,1521,387,1536,380,1538,385,1524,392,1510,402,1501,412,1491,423,1476,434,1449,447"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#af971d82426740e62c1f05adcd2c9ce7c" title="Updates command data from parsed input report." alt="" coords="1535,401,1749,428"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1448,449,1552,429,1553,434,1449,454"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ad7de3999d4df19038e27c01f9b02010e" title="Updates gravity data from parsed input report." alt="" coords="1545,452,1739,479"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1448,463,1530,463,1530,468,1448,468"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a7416d844f6188c8d16f181d6d4431708" title="Updates linear accelerometer data from parsed input report." alt="" coords="1571,503,1713,545"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1449,479,1556,502,1555,508,1448,484"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a3abf4a199bc7a03ac7447c2781673d88" title="Updates magnetic field data from parsed input report." alt="" coords="1550,569,1734,596"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1449,482,1476,497,1492,512,1501,527,1509,542,1524,555,1536,562,1534,566,1521,560,1505,545,1496,530,1488,515,1473,501,1447,487"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a04489cf9a125495c7cf07c6ba5e9f6c0" title="Updates activity classifier data from parsed input report." alt="" coords="1555,620,1729,663"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1449,479,1476,497,1489,511,1496,525,1501,553,1506,580,1513,593,1524,606,1542,618,1539,623,1521,610,1509,596,1501,582,1496,554,1491,527,1484,514,1473,501,1447,484"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a83fed63c67957ec4338afd43087d6e22" title="Updates raw accelerometer data from parsed input report." alt="" coords="1570,687,1714,729"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1449,478,1477,497,1493,520,1500,543,1501,587,1502,631,1509,652,1525,673,1539,684,1556,693,1554,698,1536,689,1521,677,1504,654,1496,632,1495,587,1495,543,1488,522,1473,501,1446,482"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ad0f0fec4e53029b4ba907414a36ac5ea" title="Updates raw gyro data from parsed input report." alt="" coords="1570,753,1714,796"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1450,477,1477,497,1497,528,1505,560,1505,591,1501,621,1496,651,1497,681,1505,710,1525,740,1539,752,1556,760,1554,765,1536,756,1521,743,1500,712,1491,681,1491,651,1495,620,1499,590,1500,560,1492,531,1473,501,1446,482"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a2ecd4ed60f82730ae230c61687ec92bf" title="Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x." alt="" coords="868,577,995,604"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="774,557,853,572,852,578,773,562"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8d9f28d8857279a3c4b1f62f6dabb638" title="Receives a SHTP packet via SPI and sends it to data_proc_task()" alt="" coords="1063,577,1227,604"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="995,588,1047,588,1047,593,995,593"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a2c359a44a2c8e83ecb258a340e2d0e1a" title="Sends a queued SHTP packet via SPI." alt="" coords="1069,628,1221,655"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="992,602,1072,621,1071,626,990,607"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a9ee7e73f695af8965a9ede50136d5a8c" title="Receives a SHTP packet body via SPI." alt="" coords="1275,577,1475,604"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1228,588,1260,588,1260,593,1228,593"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#acb246769719351e02bf2aff06d039475" title="Receives a SHTP packet header via SPI." alt="" coords="1293,628,1457,671"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1201,602,1278,622,1277,627,1200,607"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<h2 class="groupheader">Variable Documentation</h2>
|
|
||||||
<a id="aafbc34af64f3c93123dce5a8238efd38" name="aafbc34af64f3c93123dce5a8238efd38"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#aafbc34af64f3c93123dce5a8238efd38">◆ </a></span>ENABLED_REPORT_CNT</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="mlabels">
|
|
||||||
<tr>
|
|
||||||
<td class="mlabels-left">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">const constexpr uint8_t ENABLED_REPORT_CNT = 2</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</td>
|
|
||||||
<td class="mlabels-right">
|
|
||||||
<span class="mlabels"><span class="mlabel">constexpr</span></span> </td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="ac36e56130d5d806898f3545d4cdf0f70" name="ac36e56130d5d806898f3545d4cdf0f70"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#ac36e56130d5d806898f3545d4cdf0f70">◆ </a></span>imu</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname"><a class="el" href="class_b_n_o08x.html">BNO08x</a> * imu = nullptr</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a4e7be0e1e700243053709d7544201596" name="a4e7be0e1e700243053709d7544201596"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a4e7be0e1e700243053709d7544201596">◆ </a></span>msg_buff</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">char msg_buff = {}</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a5a4ba60143c31271df0f72bf0e503876" name="a5a4ba60143c31271df0f72bf0e503876"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a5a4ba60143c31271df0f72bf0e503876">◆ </a></span>new_data</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">bool new_data = false</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a8c57d66969fed0b55bdee9b57f6ed0a7" name="a8c57d66969fed0b55bdee9b57f6ed0a7"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a8c57d66969fed0b55bdee9b57f6ed0a7">◆ </a></span>prev_report_data</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname"><a class="el" href="struct_b_n_o08x_test_helper_1_1imu__report__data__t.html">BNO08xTestHelper::imu_report_data_t</a> prev_report_data</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a22334b11e0558ec663d040de9b7db8c9" name="a22334b11e0558ec663d040de9b7db8c9"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a22334b11e0558ec663d040de9b7db8c9">◆ </a></span>report_data</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname"><a class="el" href="class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2">BNO08xTestHelper::update_report_data</a> & report_data</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a4b80e39a1f48d801615a1f7baa210071" name="a4b80e39a1f48d801615a1f7baa210071"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a4b80e39a1f48d801615a1f7baa210071">◆ </a></span>REPORT_PERIOD</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="mlabels">
|
|
||||||
<tr>
|
|
||||||
<td class="mlabels-left">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">const constexpr uint32_t REPORT_PERIOD = 100000UL</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</td>
|
|
||||||
<td class="mlabels-right">
|
|
||||||
<span class="mlabels"><span class="mlabel">constexpr</span></span> </td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a20cd776c25ed6d39b2dcb95d155cfbda" name="a20cd776c25ed6d39b2dcb95d155cfbda"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a20cd776c25ed6d39b2dcb95d155cfbda">◆ </a></span>RX_REPORT_TRIAL_CNT</h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="mlabels">
|
|
||||||
<tr>
|
|
||||||
<td class="mlabels-left">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">const constexpr uint8_t RX_REPORT_TRIAL_CNT = 5</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</td>
|
|
||||||
<td class="mlabels-right">
|
|
||||||
<span class="mlabels"><span class="mlabel">constexpr</span></span> </td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div><!-- contents -->
|
|
||||||
</div><!-- doc-content -->
|
|
||||||
<!-- start footer part -->
|
|
||||||
<div id="nav-path" class="navpath"><!-- id is needed for treeview function! -->
|
|
||||||
<ul>
|
|
||||||
<li class="navelem"><a class="el" href="dir_85e9385bd83516731053aadc7da3c8af.html">imu_update</a></li><li class="navelem"><a class="el" href="dir_c60d9bf80716f90f729fd65c40ec81f7.html">bno08x_update</a></li><li class="navelem"><a class="el" href="dir_fd670e5d11b8bb731501003ff6578ae1.html">components</a></li><li class="navelem"><a class="el" href="dir_a6718ce9703adf4789a693642ffedf7f.html">esp32_BNO08x</a></li><li class="navelem"><a class="el" href="dir_14dea6b744ab39100edf1f9916c217e0.html">test</a></li><li class="navelem"><a class="el" href="_callback_tests_8cpp.html">CallbackTests.cpp</a></li>
|
|
||||||
<li class="footer">Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.10.0 </li>
|
|
||||||
</ul>
|
|
||||||
</div>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
||||||
|
|
@ -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 ]
|
|
||||||
];
|
|
||||||
|
|
@ -1,48 +0,0 @@
|
||||||
<map id="CallbackTests.cpp" name="CallbackTests.cpp">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="367,5,496,32"/>
|
|
||||||
<area shape="rect" id="Node000002" title=" " alt="" coords="321,80,382,107"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="419,35,378,72,375,68,416,31"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$_b_n_o08x_test_helper_8hpp.html" title=" " alt="" coords="406,80,620,107"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="447,31,489,68,486,72,444,35"/>
|
|
||||||
<area shape="rect" id="Node000004" title=" " alt="" coords="5,229,66,256"/>
|
|
||||||
<area shape="poly" id="edge3_Node000003_Node000004" title=" " alt="" coords="473,110,81,230,79,225,471,105"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$_b_n_o08x_8hpp.html" title=" " alt="" coords="652,155,747,181"/>
|
|
||||||
<area shape="poly" id="edge4_Node000003_Node000005" title=" " alt="" coords="546,105,654,146,652,151,544,110"/>
|
|
||||||
<area shape="poly" id="edge7_Node000005_Node000004" title=" " alt="" coords="652,174,410,189,249,207,81,232,80,227,248,201,410,184,651,168"/>
|
|
||||||
<area shape="rect" id="Node000006" title=" " alt="" coords="90,229,168,256"/>
|
|
||||||
<area shape="poly" id="edge5_Node000005_Node000006" title=" " alt="" coords="651,176,451,195,320,211,184,231,183,226,319,206,451,189,651,170"/>
|
|
||||||
<area shape="rect" id="Node000007" title=" " alt="" coords="192,229,253,256"/>
|
|
||||||
<area shape="poly" id="edge6_Node000005_Node000007" title=" " alt="" coords="652,176,486,196,379,211,268,232,267,226,378,206,485,190,651,171"/>
|
|
||||||
<area shape="rect" id="Node000008" title=" " alt="" coords="277,229,338,256"/>
|
|
||||||
<area shape="poly" id="edge8_Node000005_Node000008" title=" " alt="" coords="652,178,521,199,354,231,352,226,520,193,651,173"/>
|
|
||||||
<area shape="rect" id="Node000009" title=" " alt="" coords="361,229,438,256"/>
|
|
||||||
<area shape="poly" id="edge9_Node000005_Node000009" title=" " alt="" coords="652,183,454,231,452,226,651,178"/>
|
|
||||||
<area shape="rect" id="Node000010" title=" " alt="" coords="461,229,517,256"/>
|
|
||||||
<area shape="poly" id="edge10_Node000005_Node000010" title=" " alt="" coords="664,184,532,229,530,224,662,179"/>
|
|
||||||
<area shape="rect" id="Node000011" title=" " alt="" coords="541,229,618,256"/>
|
|
||||||
<area shape="poly" id="edge11_Node000005_Node000011" title=" " alt="" coords="680,184,615,223,612,219,677,180"/>
|
|
||||||
<area shape="rect" id="Node000012" title=" " alt="" coords="643,229,756,256"/>
|
|
||||||
<area shape="poly" id="edge12_Node000005_Node000012" title=" " alt="" coords="702,182,702,214,697,214,697,182"/>
|
|
||||||
<area shape="rect" id="Node000013" title=" " alt="" coords="780,229,870,256"/>
|
|
||||||
<area shape="poly" id="edge13_Node000005_Node000013" title=" " alt="" coords="723,180,791,219,789,224,720,184"/>
|
|
||||||
<area shape="rect" id="Node000014" title=" " alt="" coords="893,229,1034,256"/>
|
|
||||||
<area shape="poly" id="edge14_Node000005_Node000014" title=" " alt="" coords="746,179,904,222,902,227,745,184"/>
|
|
||||||
<area shape="rect" id="Node000015" title=" " alt="" coords="1058,229,1162,256"/>
|
|
||||||
<area shape="poly" id="edge15_Node000005_Node000015" title=" " alt="" coords="748,175,1043,226,1042,231,747,180"/>
|
|
||||||
<area shape="rect" id="Node000016" title=" " alt="" coords="1186,229,1341,256"/>
|
|
||||||
<area shape="poly" id="edge16_Node000005_Node000016" title=" " alt="" coords="748,173,1171,226,1170,232,747,178"/>
|
|
||||||
<area shape="rect" id="Node000017" title=" " alt="" coords="1365,229,1479,256"/>
|
|
||||||
<area shape="poly" id="edge17_Node000005_Node000017" title=" " alt="" coords="748,170,1001,189,1172,206,1350,226,1349,232,1172,211,1000,195,747,175"/>
|
|
||||||
<area shape="rect" id="Node000018" title=" " alt="" coords="1504,229,1626,256"/>
|
|
||||||
<area shape="poly" id="edge18_Node000005_Node000018" title=" " alt="" coords="748,169,1055,187,1268,204,1488,226,1488,232,1267,209,1055,192,747,174"/>
|
|
||||||
<area shape="rect" id="Node000019" title=" " alt="" coords="1650,229,1754,256"/>
|
|
||||||
<area shape="poly" id="edge19_Node000005_Node000019" title=" " alt="" coords="748,168,1112,182,1369,200,1635,226,1634,232,1368,205,1112,188,747,173"/>
|
|
||||||
<area shape="rect" id="Node000020" href="$_b_n_o08x__global__types_8hpp.html" title=" " alt="" coords="1779,229,1954,256"/>
|
|
||||||
<area shape="poly" id="edge20_Node000005_Node000020" title=" " alt="" coords="748,168,1161,186,1456,203,1763,226,1763,232,1456,209,1160,192,747,174"/>
|
|
||||||
<area shape="rect" id="Node000021" title=" " alt="" coords="1681,304,1771,331"/>
|
|
||||||
<area shape="poly" id="edge21_Node000020_Node000021" title=" " alt="" coords="1843,259,1766,299,1763,294,1841,254"/>
|
|
||||||
<area shape="rect" id="Node000022" title=" " alt="" coords="1796,304,1936,331"/>
|
|
||||||
<area shape="poly" id="edge22_Node000020_Node000022" title=" " alt="" coords="1869,257,1869,288,1864,288,1864,257"/>
|
|
||||||
<area shape="rect" id="Node000023" title=" " alt="" coords="1961,304,2091,331"/>
|
|
||||||
<area shape="poly" id="edge23_Node000020_Node000023" title=" " alt="" coords="1895,254,1986,295,1983,300,1893,259"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
7b498e0d0ad77cc03801e11b287f9b0d
|
|
||||||
|
Before Width: | Height: | Size: 50 KiB |
|
|
@ -1,44 +0,0 @@
|
||||||
<map id="enable_linear_accelerometer" name="enable_linear_accelerometer">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="5,181,192,208"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$class_b_n_o08x.html#ab56b185d6c9e972a2b28c2621387bb86" title="Checks if BNO08x has asserted interrupt and sent data." alt="" coords="250,60,409,87"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="125,178,287,92,290,97,127,183"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$class_b_n_o08x_test_helper.html#ade6be1fd8ef3a99e0edae4cbf25eb528" title="Resets internal test imu data with test defaults." alt="" coords="245,165,414,224"/>
|
|
||||||
<area shape="poly" id="edge3_Node000001_Node000004" title=" " alt="" coords="192,192,229,192,229,197,192,197"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2" title="Updates report data with calls relevant test_imu methods." alt="" coords="240,357,419,400"/>
|
|
||||||
<area shape="poly" id="edge4_Node000001_Node000005" title=" " alt="" coords="119,206,291,346,288,350,115,211"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$class_b_n_o08x.html#a4f12de628073f44b2a3fab2688cf1caf" title="Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse." alt="" coords="489,5,643,32"/>
|
|
||||||
<area shape="poly" id="edge2_Node000002_Node000003" title=" " alt="" coords="390,57,490,33,491,39,391,62"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885" title="Get full acceleration (total acceleration of device, units in m/s^2)." alt="" coords="499,56,633,83"/>
|
|
||||||
<area shape="poly" id="edge5_Node000005_Node000006" title=" " alt="" coords="344,355,380,302,417,235,429,194,433,159,440,126,450,110,465,93,483,80,486,85,469,97,454,113,445,128,438,160,434,195,421,237,384,304,349,358"/>
|
|
||||||
<area shape="rect" id="Node000008" href="$class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed" title="Get the current activity classifier (Seee Ref. Manual 6.5.36)" alt="" coords="495,107,638,149"/>
|
|
||||||
<area shape="poly" id="edge7_Node000005_Node000008" title=" " alt="" coords="342,355,465,159,479,150,482,155,469,163,346,358"/>
|
|
||||||
<area shape="rect" id="Node000009" href="$class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f" title="Get full rotational velocity with drift compensation (units in Rad/s)." alt="" coords="487,173,646,216"/>
|
|
||||||
<area shape="poly" id="edge8_Node000005_Node000009" title=" " alt="" coords="343,355,392,292,427,256,465,226,473,221,476,226,469,230,430,260,396,295,347,359"/>
|
|
||||||
<area shape="rect" id="Node000010" href="$class_b_n_o08x.html#a067678914e928a6691625b17c40237a0" title="Get full reported gravity vector, units in m/s^2." alt="" coords="496,240,636,267"/>
|
|
||||||
<area shape="poly" id="edge10_Node000005_Node000010" title=" " alt="" coords="353,355,403,315,466,276,482,270,484,275,468,281,406,319,356,359"/>
|
|
||||||
<area shape="rect" id="Node000011" href="$class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f" title="Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5...." alt="" coords="486,291,646,333"/>
|
|
||||||
<area shape="poly" id="edge12_Node000005_Node000011" title=" " alt="" coords="407,354,473,335,474,341,408,359"/>
|
|
||||||
<area shape="rect" id="Node000012" href="$class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46" title="Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2)." alt="" coords="499,357,633,400"/>
|
|
||||||
<area shape="poly" id="edge14_Node000005_Node000012" title=" " alt="" coords="420,376,484,376,484,381,420,381"/>
|
|
||||||
<area shape="rect" id="Node000013" href="$class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb" title="Get the full magnetic field vector." alt="" coords="501,424,632,451"/>
|
|
||||||
<area shape="poly" id="edge16_Node000005_Node000013" title=" " alt="" coords="419,398,495,417,493,422,418,403"/>
|
|
||||||
<area shape="rect" id="Node000014" href="$class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a" title="Get the full quaternion reading." alt="" coords="502,475,630,501"/>
|
|
||||||
<area shape="poly" id="edge18_Node000005_Node000014" title=" " alt="" coords="362,398,410,430,468,460,488,468,486,473,466,465,408,435,359,403"/>
|
|
||||||
<area shape="rect" id="Node000015" href="$class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27" title="Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6...." alt="" coords="467,525,665,552"/>
|
|
||||||
<area shape="poly" id="edge20_Node000005_Node000015" title=" " alt="" coords="349,399,398,455,431,485,468,511,480,517,478,522,466,516,428,490,394,459,345,402"/>
|
|
||||||
<area shape="rect" id="Node000016" href="$class_b_n_o08x.html#a248544b262582d10d917a687190cb454" title="Get the current stability classifier (Seee Ref. Manual 6.5.31)" alt="" coords="492,576,640,619"/>
|
|
||||||
<area shape="poly" id="edge21_Node000005_Node000016" title=" " alt="" coords="343,399,363,434,390,478,426,523,469,562,480,569,477,573,465,566,422,527,386,481,358,437,339,402"/>
|
|
||||||
<area shape="rect" id="Node000017" href="$class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef" title="Get the counted amount of steps." alt="" coords="483,643,650,669"/>
|
|
||||||
<area shape="poly" id="edge22_Node000005_Node000017" title=" " alt="" coords="339,400,354,448,379,510,417,574,441,603,469,629,475,633,472,637,465,633,437,607,413,577,375,512,349,449,333,401"/>
|
|
||||||
<area shape="rect" id="Node000018" href="$class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104" title="Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv..." alt="" coords="480,693,653,736"/>
|
|
||||||
<area shape="poly" id="edge23_Node000005_Node000018" title=" " alt="" coords="337,400,350,456,374,531,392,571,413,610,439,647,469,679,472,682,468,686,465,683,435,650,409,613,387,573,369,533,345,457,332,401"/>
|
|
||||||
<area shape="rect" id="Node000007" href="$class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9" title="Converts a register value to a float using its associated Q point. (See https://en...." alt="" coords="713,332,848,359"/>
|
|
||||||
<area shape="poly" id="edge6_Node000006_Node000007" title=" " alt="" coords="635,75,667,93,692,117,713,145,745,207,766,267,777,316,772,317,760,269,740,209,708,148,688,121,664,97,632,80"/>
|
|
||||||
<area shape="poly" id="edge9_Node000009_Node000007" title=" " alt="" coords="645,214,667,226,695,247,722,271,762,318,758,321,718,275,692,251,664,230,642,219"/>
|
|
||||||
<area shape="poly" id="edge11_Node000010_Node000007" title=" " alt="" coords="633,265,666,276,710,298,748,321,745,325,707,302,664,281,631,270"/>
|
|
||||||
<area shape="poly" id="edge13_Node000011_Node000007" title=" " alt="" coords="647,322,698,330,697,335,647,327"/>
|
|
||||||
<area shape="poly" id="edge15_Node000012_Node000007" title=" " alt="" coords="633,366,697,355,698,361,634,371"/>
|
|
||||||
<area shape="poly" id="edge17_Node000013_Node000007" title=" " alt="" coords="631,421,664,410,707,388,745,365,748,370,710,393,666,414,633,426"/>
|
|
||||||
<area shape="poly" id="edge19_Node000014_Node000007" title=" " alt="" coords="630,475,664,460,693,440,718,417,759,370,763,373,722,420,696,445,667,465,632,480"/>
|
|
||||||
<area shape="poly" id="edge24_Node000018_Node000007" title=" " alt="" coords="649,691,663,679,693,644,716,604,735,562,750,519,768,437,775,374,780,375,773,438,755,520,740,564,721,607,697,647,667,683,653,695"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
835ac906ec53cdaad191e625af11ecab
|
|
||||||
|
Before Width: | Height: | Size: 65 KiB |
|
|
@ -1,46 +0,0 @@
|
||||||
<map id="for" name="for">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="5,189,44,216"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$class_b_n_o08x.html#ab56b185d6c9e972a2b28c2621387bb86" title="Checks if BNO08x has asserted interrupt and sent data." alt="" coords="102,48,261,75"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="35,187,90,126,145,82,149,86,94,130,39,190"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$class_b_n_o08x_test_helper.html#ade6be1fd8ef3a99e0edae4cbf25eb528" title="Resets internal test imu data with test defaults." alt="" coords="97,140,266,199"/>
|
|
||||||
<area shape="poly" id="edge3_Node000001_Node000004" title=" " alt="" coords="44,196,81,188,82,193,45,201"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="100,223,263,249"/>
|
|
||||||
<area shape="poly" id="edge4_Node000001_Node000005" title=" " alt="" coords="45,204,101,216,100,221,44,209"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2" title="Updates report data with calls relevant test_imu methods." alt="" coords="92,357,271,400"/>
|
|
||||||
<area shape="poly" id="edge5_Node000001_Node000006" title=" " alt="" coords="40,215,153,344,149,347,36,218"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$class_b_n_o08x.html#a4f12de628073f44b2a3fab2688cf1caf" title="Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse." alt="" coords="341,5,495,32"/>
|
|
||||||
<area shape="poly" id="edge2_Node000002_Node000003" title=" " alt="" coords="259,45,325,33,326,38,260,50"/>
|
|
||||||
<area shape="rect" id="Node000007" href="$class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885" title="Get full acceleration (total acceleration of device, units in m/s^2)." alt="" coords="351,56,485,83"/>
|
|
||||||
<area shape="poly" id="edge6_Node000006_Node000007" title=" " alt="" coords="201,355,235,313,269,260,278,236,283,213,285,172,291,133,300,113,317,93,335,80,338,84,321,97,305,116,296,134,290,173,288,214,283,237,273,263,240,316,205,359"/>
|
|
||||||
<area shape="rect" id="Node000009" href="$class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed" title="Get the current activity classifier (Seee Ref. Manual 6.5.36)" alt="" coords="347,107,490,149"/>
|
|
||||||
<area shape="poly" id="edge8_Node000006_Node000009" title=" " alt="" coords="199,355,233,312,269,260,282,232,288,207,297,183,317,159,331,149,334,153,321,163,302,186,293,209,287,233,273,263,237,315,203,358"/>
|
|
||||||
<area shape="rect" id="Node000010" href="$class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f" title="Get full rotational velocity with drift compensation (units in Rad/s)." alt="" coords="339,173,498,216"/>
|
|
||||||
<area shape="poly" id="edge9_Node000006_Node000010" title=" " alt="" coords="195,355,244,292,279,256,318,226,325,221,328,226,321,230,282,260,248,295,199,359"/>
|
|
||||||
<area shape="rect" id="Node000011" href="$class_b_n_o08x.html#a067678914e928a6691625b17c40237a0" title="Get full reported gravity vector, units in m/s^2." alt="" coords="348,240,488,267"/>
|
|
||||||
<area shape="poly" id="edge11_Node000006_Node000011" title=" " alt="" coords="205,355,255,315,318,276,334,270,336,275,320,281,258,319,208,359"/>
|
|
||||||
<area shape="rect" id="Node000012" href="$class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f" title="Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5...." alt="" coords="338,291,498,333"/>
|
|
||||||
<area shape="poly" id="edge13_Node000006_Node000012" title=" " alt="" coords="259,354,325,335,326,341,260,359"/>
|
|
||||||
<area shape="rect" id="Node000013" href="$class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46" title="Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2)." alt="" coords="351,357,485,400"/>
|
|
||||||
<area shape="poly" id="edge15_Node000006_Node000013" title=" " alt="" coords="272,376,336,376,336,381,272,381"/>
|
|
||||||
<area shape="rect" id="Node000014" href="$class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb" title="Get the full magnetic field vector." alt="" coords="353,424,484,451"/>
|
|
||||||
<area shape="poly" id="edge17_Node000006_Node000014" title=" " alt="" coords="271,398,347,417,346,422,270,403"/>
|
|
||||||
<area shape="rect" id="Node000015" href="$class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a" title="Get the full quaternion reading." alt="" coords="354,475,482,501"/>
|
|
||||||
<area shape="poly" id="edge19_Node000006_Node000015" title=" " alt="" coords="214,398,262,430,320,460,340,468,339,473,318,465,260,435,211,403"/>
|
|
||||||
<area shape="rect" id="Node000016" href="$class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27" title="Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6...." alt="" coords="319,525,517,552"/>
|
|
||||||
<area shape="poly" id="edge21_Node000006_Node000016" title=" " alt="" coords="201,399,250,455,283,485,320,511,332,517,330,522,318,516,280,490,246,459,197,402"/>
|
|
||||||
<area shape="rect" id="Node000017" href="$class_b_n_o08x.html#a248544b262582d10d917a687190cb454" title="Get the current stability classifier (Seee Ref. Manual 6.5.31)" alt="" coords="344,576,492,619"/>
|
|
||||||
<area shape="poly" id="edge22_Node000006_Node000017" title=" " alt="" coords="195,399,215,434,243,478,278,523,321,562,332,569,329,573,317,566,274,527,238,481,210,437,191,402"/>
|
|
||||||
<area shape="rect" id="Node000018" href="$class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef" title="Get the counted amount of steps." alt="" coords="335,643,502,669"/>
|
|
||||||
<area shape="poly" id="edge23_Node000006_Node000018" title=" " alt="" coords="191,400,206,448,232,510,270,574,293,603,321,629,327,633,324,637,317,633,289,607,265,577,227,512,201,449,186,401"/>
|
|
||||||
<area shape="rect" id="Node000019" href="$class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104" title="Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv..." alt="" coords="332,693,505,736"/>
|
|
||||||
<area shape="poly" id="edge24_Node000006_Node000019" title=" " alt="" coords="189,400,202,456,226,531,244,571,265,610,291,647,321,679,324,682,321,686,317,683,287,650,261,613,239,573,221,533,197,457,184,401"/>
|
|
||||||
<area shape="rect" id="Node000008" href="$class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9" title="Converts a register value to a float using its associated Q point. (See https://en...." alt="" coords="565,332,700,359"/>
|
|
||||||
<area shape="poly" id="edge7_Node000007_Node000008" title=" " alt="" coords="487,75,519,93,544,117,565,145,597,207,618,267,629,316,624,317,612,269,592,209,560,148,540,121,516,97,484,80"/>
|
|
||||||
<area shape="poly" id="edge10_Node000010_Node000008" title=" " alt="" coords="497,214,519,226,547,247,574,271,614,318,610,321,570,275,544,251,516,230,494,219"/>
|
|
||||||
<area shape="poly" id="edge12_Node000011_Node000008" title=" " alt="" coords="485,265,518,276,562,298,600,321,598,325,559,302,516,281,483,270"/>
|
|
||||||
<area shape="poly" id="edge14_Node000012_Node000008" title=" " alt="" coords="499,322,550,330,549,335,499,327"/>
|
|
||||||
<area shape="poly" id="edge16_Node000013_Node000008" title=" " alt="" coords="486,366,550,355,550,361,486,371"/>
|
|
||||||
<area shape="poly" id="edge18_Node000014_Node000008" title=" " alt="" coords="483,421,516,410,559,388,598,365,600,370,562,393,518,414,485,426"/>
|
|
||||||
<area shape="poly" id="edge20_Node000015_Node000008" title=" " alt="" coords="482,475,516,460,545,440,570,417,611,370,615,373,574,420,548,445,519,465,484,480"/>
|
|
||||||
<area shape="poly" id="edge25_Node000019_Node000008" title=" " alt="" coords="501,691,516,679,545,644,569,604,587,562,602,519,620,437,627,374,632,375,625,438,607,520,592,564,573,607,549,647,519,683,505,695"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
427cdc65693254a8f7d86d5c129973ba
|
|
||||||
|
Before Width: | Height: | Size: 64 KiB |
|
|
@ -1,7 +0,0 @@
|
||||||
<map id="TEST_CASE" name="TEST_CASE">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="5,47,102,73"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="150,5,333,48"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="102,49,134,43,135,48,103,54"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="159,72,324,115"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="103,66,144,73,143,79,102,71"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
20530a0195add9876a81f3eca1f08dca
|
|
||||||
|
Before Width: | Height: | Size: 3.3 KiB |
|
|
@ -1,44 +0,0 @@
|
||||||
<map id="register_cb" name="register_cb">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="5,244,91,271"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea" title="Checks if report_data matches the default states stored within prev_report_data data for respective r..." alt="" coords="139,136,361,179"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="62,242,95,215,137,188,150,182,152,187,140,193,98,219,66,246"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3" title="Converts BNO08xAccuracy enum class object to string." alt="" coords="155,203,345,245"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="91,248,140,240,140,245,92,253"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="167,269,333,312"/>
|
|
||||||
<area shape="poly" id="edge3_Node000001_Node000004" title=" " alt="" coords="92,262,152,272,151,277,91,267"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2" title="Updates report data with calls relevant test_imu methods." alt="" coords="160,336,340,379"/>
|
|
||||||
<area shape="poly" id="edge4_Node000001_Node000005" title=" " alt="" coords="66,269,98,295,140,322,152,327,150,332,137,326,95,300,62,273"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885" title="Get full acceleration (total acceleration of device, units in m/s^2)." alt="" coords="441,5,575,32"/>
|
|
||||||
<area shape="poly" id="edge5_Node000005_Node000006" title=" " alt="" coords="338,338,359,322,381,288,389,253,388,219,382,184,376,149,375,113,383,78,407,42,425,29,428,33,411,46,388,80,380,114,381,148,387,183,393,218,394,254,386,290,363,326,342,343"/>
|
|
||||||
<area shape="rect" id="Node000008" href="$class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed" title="Get the current activity classifier (Seee Ref. Manual 6.5.36)" alt="" coords="437,56,580,99"/>
|
|
||||||
<area shape="poly" id="edge7_Node000005_Node000008" title=" " alt="" coords="338,338,359,322,377,296,385,270,385,244,383,218,380,191,381,164,389,137,407,109,421,97,425,101,411,112,393,139,386,165,385,191,388,217,391,244,390,271,382,299,363,326,342,342"/>
|
|
||||||
<area shape="rect" id="Node000009" href="$class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f" title="Get full rotational velocity with drift compensation (units in Rad/s)." alt="" coords="429,123,588,165"/>
|
|
||||||
<area shape="poly" id="edge8_Node000005_Node000009" title=" " alt="" coords="338,337,359,322,373,305,380,287,383,251,385,214,393,194,407,176,414,169,417,173,411,179,397,197,391,215,388,251,385,288,377,307,363,326,342,341"/>
|
|
||||||
<area shape="rect" id="Node000010" href="$class_b_n_o08x.html#a067678914e928a6691625b17c40237a0" title="Get full reported gravity vector, units in m/s^2." alt="" coords="438,189,578,216"/>
|
|
||||||
<area shape="poly" id="edge10_Node000005_Node000010" title=" " alt="" coords="338,335,359,322,370,311,376,299,382,275,389,250,396,238,407,226,422,216,425,221,411,230,400,241,393,252,387,276,381,301,374,314,363,326,341,340"/>
|
|
||||||
<area shape="rect" id="Node000011" href="$class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f" title="Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5...." alt="" coords="428,240,588,283"/>
|
|
||||||
<area shape="poly" id="edge12_Node000005_Node000011" title=" " alt="" coords="331,333,360,322,384,307,408,292,421,286,424,291,410,297,386,312,362,326,333,338"/>
|
|
||||||
<area shape="rect" id="Node000012" href="$class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46" title="Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2)." alt="" coords="441,307,575,349"/>
|
|
||||||
<area shape="poly" id="edge14_Node000005_Node000012" title=" " alt="" coords="340,345,425,335,426,340,340,350"/>
|
|
||||||
<area shape="rect" id="Node000013" href="$class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb" title="Get the full magnetic field vector." alt="" coords="443,373,574,400"/>
|
|
||||||
<area shape="poly" id="edge16_Node000005_Node000013" title=" " alt="" coords="340,365,427,375,427,380,340,370"/>
|
|
||||||
<area shape="rect" id="Node000014" href="$class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a" title="Get the full quaternion reading." alt="" coords="444,424,572,451"/>
|
|
||||||
<area shape="poly" id="edge18_Node000005_Node000014" title=" " alt="" coords="312,377,410,409,436,417,434,422,408,415,310,382"/>
|
|
||||||
<area shape="rect" id="Node000015" href="$class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27" title="Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6...." alt="" coords="409,475,607,501"/>
|
|
||||||
<area shape="poly" id="edge20_Node000005_Node000015" title=" " alt="" coords="279,377,337,419,410,460,427,467,425,472,408,465,334,424,276,381"/>
|
|
||||||
<area shape="rect" id="Node000016" href="$class_b_n_o08x.html#a248544b262582d10d917a687190cb454" title="Get the current stability classifier (Seee Ref. Manual 6.5.31)" alt="" coords="434,525,582,568"/>
|
|
||||||
<area shape="poly" id="edge21_Node000005_Node000016" title=" " alt="" coords="270,377,328,443,367,479,410,511,421,517,418,522,408,516,364,483,324,447,266,381"/>
|
|
||||||
<area shape="rect" id="Node000017" href="$class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef" title="Get the counted amount of steps." alt="" coords="425,592,592,619"/>
|
|
||||||
<area shape="poly" id="edge22_Node000005_Node000017" title=" " alt="" coords="263,378,284,421,316,475,358,531,383,556,411,578,419,583,416,587,407,582,380,560,354,534,311,478,279,423,258,380"/>
|
|
||||||
<area shape="rect" id="Node000018" href="$class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104" title="Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv..." alt="" coords="422,643,595,685"/>
|
|
||||||
<area shape="poly" id="edge23_Node000005_Node000018" title=" " alt="" coords="260,378,279,429,310,497,354,567,381,600,411,629,415,632,412,636,407,633,377,604,349,571,305,499,274,431,255,380"/>
|
|
||||||
<area shape="rect" id="Node000007" href="$class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9" title="Converts a register value to a float using its associated Q point. (See https://en...." alt="" coords="655,281,790,308"/>
|
|
||||||
<area shape="poly" id="edge6_Node000006_Node000007" title=" " alt="" coords="577,25,609,42,634,67,655,95,687,156,708,217,719,265,714,267,702,218,682,159,650,98,630,70,606,46,574,30"/>
|
|
||||||
<area shape="poly" id="edge9_Node000009_Node000007" title=" " alt="" coords="587,163,609,175,637,196,664,221,704,267,700,271,660,224,634,200,606,180,584,168"/>
|
|
||||||
<area shape="poly" id="edge11_Node000010_Node000007" title=" " alt="" coords="575,214,608,226,652,247,690,270,687,275,649,252,606,230,573,219"/>
|
|
||||||
<area shape="poly" id="edge13_Node000011_Node000007" title=" " alt="" coords="589,271,640,279,639,284,589,276"/>
|
|
||||||
<area shape="poly" id="edge15_Node000012_Node000007" title=" " alt="" coords="575,315,639,305,640,310,576,320"/>
|
|
||||||
<area shape="poly" id="edge17_Node000013_Node000007" title=" " alt="" coords="573,370,606,359,649,338,687,315,690,319,652,342,608,364,575,375"/>
|
|
||||||
<area shape="poly" id="edge19_Node000014_Node000007" title=" " alt="" coords="572,424,606,410,635,390,660,366,701,319,705,323,664,370,638,394,609,414,574,429"/>
|
|
||||||
<area shape="poly" id="edge24_Node000018_Node000007" title=" " alt="" coords="591,640,605,629,635,594,658,554,677,511,692,468,710,386,717,323,722,324,715,387,697,469,682,513,663,556,639,597,609,633,595,644"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
2550d060896a16cbcdd8f86f8db4194b
|
|
||||||
|
Before Width: | Height: | Size: 60 KiB |
|
|
@ -1,46 +0,0 @@
|
||||||
<map id="register_cb" name="register_cb">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="5,211,91,237"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$class_b_n_o08x_test_helper.html#ade97098806c8779b26f9c166c4b03eea" title="Checks if report_data matches the default states stored within prev_report_data data for respective r..." alt="" coords="139,69,361,112"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="56,209,88,166,111,142,137,122,145,117,148,122,140,126,115,146,92,169,60,212"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$class_b_n_o08x_test_helper.html#a857b66c12c231af0d546c026ec017ab3" title="Converts BNO08xAccuracy enum class object to string." alt="" coords="155,136,345,179"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="84,208,138,188,159,181,160,186,140,193,86,213"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$class_b_n_o08x_test_helper.html#ad398739ce46400c1ac35e1cf7603d590" title="Checks if report_data matches the default states stored within prev_report_data data for respective r..." alt="" coords="155,203,345,245"/>
|
|
||||||
<area shape="poly" id="edge3_Node000001_Node000004" title=" " alt="" coords="91,221,140,221,140,227,91,227"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="167,269,333,312"/>
|
|
||||||
<area shape="poly" id="edge4_Node000001_Node000005" title=" " alt="" coords="86,235,140,255,160,262,159,267,138,260,84,240"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$class_b_n_o08x_test_helper.html#ac81c63583b19e5c7b3233324aaea98e2" title="Updates report data with calls relevant test_imu methods." alt="" coords="160,336,340,379"/>
|
|
||||||
<area shape="poly" id="edge5_Node000001_Node000006" title=" " alt="" coords="60,236,92,279,115,302,140,322,148,326,145,331,137,326,111,306,88,282,56,239"/>
|
|
||||||
<area shape="rect" id="Node000007" href="$class_b_n_o08x.html#a3c9797a2a2be14ee6e8126f1295fa885" title="Get full acceleration (total acceleration of device, units in m/s^2)." alt="" coords="441,5,575,32"/>
|
|
||||||
<area shape="poly" id="edge6_Node000006_Node000007" title=" " alt="" coords="338,338,359,322,381,288,389,253,388,219,382,184,376,149,375,113,383,78,407,42,425,29,428,33,411,46,388,80,380,114,381,148,387,183,393,218,394,254,386,290,363,326,342,343"/>
|
|
||||||
<area shape="rect" id="Node000009" href="$class_b_n_o08x.html#a4a72489c56960d83050ae9c4b9ab75ed" title="Get the current activity classifier (Seee Ref. Manual 6.5.36)" alt="" coords="437,56,580,99"/>
|
|
||||||
<area shape="poly" id="edge8_Node000006_Node000009" title=" " alt="" coords="338,338,359,322,377,296,385,270,385,244,383,218,380,191,381,164,389,137,407,109,421,97,425,101,411,112,393,139,386,165,385,191,388,217,391,244,390,271,382,299,363,326,342,342"/>
|
|
||||||
<area shape="rect" id="Node000010" href="$class_b_n_o08x.html#aa9291dec6c05a3786fe58221e6856e8f" title="Get full rotational velocity with drift compensation (units in Rad/s)." alt="" coords="429,123,588,165"/>
|
|
||||||
<area shape="poly" id="edge9_Node000006_Node000010" title=" " alt="" coords="338,337,359,322,373,305,380,287,383,251,385,214,393,194,407,176,414,169,417,173,411,179,397,197,391,215,388,251,385,288,377,307,363,326,342,341"/>
|
|
||||||
<area shape="rect" id="Node000011" href="$class_b_n_o08x.html#a067678914e928a6691625b17c40237a0" title="Get full reported gravity vector, units in m/s^2." alt="" coords="438,189,578,216"/>
|
|
||||||
<area shape="poly" id="edge11_Node000006_Node000011" title=" " alt="" coords="338,335,359,322,370,311,376,299,382,275,389,250,396,238,407,226,422,216,425,221,411,230,400,241,393,252,387,276,381,301,374,314,363,326,341,340"/>
|
|
||||||
<area shape="rect" id="Node000012" href="$class_b_n_o08x.html#a8f4a10a8427a266fa28fc1c85c8e850f" title="Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5...." alt="" coords="428,240,588,283"/>
|
|
||||||
<area shape="poly" id="edge13_Node000006_Node000012" title=" " alt="" coords="331,333,360,322,384,307,408,292,421,286,424,291,410,297,386,312,362,326,333,338"/>
|
|
||||||
<area shape="rect" id="Node000013" href="$class_b_n_o08x.html#a4bef64b34cbff3922848c7a93aa21e46" title="Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2)." alt="" coords="441,307,575,349"/>
|
|
||||||
<area shape="poly" id="edge15_Node000006_Node000013" title=" " alt="" coords="340,345,425,335,426,340,340,350"/>
|
|
||||||
<area shape="rect" id="Node000014" href="$class_b_n_o08x.html#ae766248440e76fb26bbadc6ee0b54ddb" title="Get the full magnetic field vector." alt="" coords="443,373,574,400"/>
|
|
||||||
<area shape="poly" id="edge17_Node000006_Node000014" title=" " alt="" coords="340,365,427,375,427,380,340,370"/>
|
|
||||||
<area shape="rect" id="Node000015" href="$class_b_n_o08x.html#af5d6dae7c0f8d36b6ac91adff614ab3a" title="Get the full quaternion reading." alt="" coords="444,424,572,451"/>
|
|
||||||
<area shape="poly" id="edge19_Node000006_Node000015" title=" " alt="" coords="312,377,410,409,436,417,434,422,408,415,310,382"/>
|
|
||||||
<area shape="rect" id="Node000016" href="$class_b_n_o08x.html#ac2118c4da6631d3b9806353ca2cbba27" title="Get raw gyroscope full reading from physical gyroscope MEMs sensor (See Ref. Manual 6...." alt="" coords="409,475,607,501"/>
|
|
||||||
<area shape="poly" id="edge21_Node000006_Node000016" title=" " alt="" coords="279,377,337,419,410,460,427,467,425,472,408,465,334,424,276,381"/>
|
|
||||||
<area shape="rect" id="Node000017" href="$class_b_n_o08x.html#a248544b262582d10d917a687190cb454" title="Get the current stability classifier (Seee Ref. Manual 6.5.31)" alt="" coords="434,525,582,568"/>
|
|
||||||
<area shape="poly" id="edge22_Node000006_Node000017" title=" " alt="" coords="270,377,328,443,367,479,410,511,421,517,418,522,408,516,364,483,324,447,266,381"/>
|
|
||||||
<area shape="rect" id="Node000018" href="$class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef" title="Get the counted amount of steps." alt="" coords="425,592,592,619"/>
|
|
||||||
<area shape="poly" id="edge23_Node000006_Node000018" title=" " alt="" coords="263,378,284,421,316,475,358,531,383,556,411,578,419,583,416,587,407,582,380,560,354,534,311,478,279,423,258,380"/>
|
|
||||||
<area shape="rect" id="Node000019" href="$class_b_n_o08x.html#a86ff710f2b359e905c7154bfb7d5b104" title="Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv..." alt="" coords="422,643,595,685"/>
|
|
||||||
<area shape="poly" id="edge24_Node000006_Node000019" title=" " alt="" coords="260,378,279,429,310,497,354,567,381,600,411,629,415,632,412,636,407,633,377,604,349,571,305,499,274,431,255,380"/>
|
|
||||||
<area shape="rect" id="Node000008" href="$class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9" title="Converts a register value to a float using its associated Q point. (See https://en...." alt="" coords="655,281,790,308"/>
|
|
||||||
<area shape="poly" id="edge7_Node000007_Node000008" title=" " alt="" coords="577,25,609,42,634,67,655,95,687,156,708,217,719,265,714,267,702,218,682,159,650,98,630,70,606,46,574,30"/>
|
|
||||||
<area shape="poly" id="edge10_Node000010_Node000008" title=" " alt="" coords="587,163,609,175,637,196,664,221,704,267,700,271,660,224,634,200,606,180,584,168"/>
|
|
||||||
<area shape="poly" id="edge12_Node000011_Node000008" title=" " alt="" coords="575,214,608,226,652,247,690,270,687,275,649,252,606,230,573,219"/>
|
|
||||||
<area shape="poly" id="edge14_Node000012_Node000008" title=" " alt="" coords="589,271,640,279,639,284,589,276"/>
|
|
||||||
<area shape="poly" id="edge16_Node000013_Node000008" title=" " alt="" coords="575,315,639,305,640,310,576,320"/>
|
|
||||||
<area shape="poly" id="edge18_Node000014_Node000008" title=" " alt="" coords="573,370,606,359,649,338,687,315,690,319,652,342,608,364,575,375"/>
|
|
||||||
<area shape="poly" id="edge20_Node000015_Node000008" title=" " alt="" coords="572,424,606,410,635,390,660,366,701,319,705,323,664,370,638,394,609,414,574,429"/>
|
|
||||||
<area shape="poly" id="edge25_Node000019_Node000008" title=" " alt="" coords="591,640,605,629,635,594,658,554,677,511,692,468,710,386,717,323,722,324,715,387,697,469,682,513,663,556,639,597,609,633,595,644"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
a1643d70149876d952e9f6ddc331bc7e
|
|
||||||
|
Before Width: | Height: | Size: 63 KiB |
|
|
@ -1,61 +0,0 @@
|
||||||
<map id="TEST_ASSERT_EQUAL" name="TEST_ASSERT_EQUAL">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="150,715,313,741"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$_callback_tests_8cpp.html#a4ac223c58b5ab6a6c5203661fafa1caa" title=" " alt="" coords="34,5,73,32"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="225,699,213,563,188,369,171,269,151,176,127,99,100,46,87,34,72,27,74,22,90,30,104,42,132,97,156,175,176,267,193,368,218,563,231,699"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$_callback_tests_8cpp.html#ac18b9cb122499f587331d82a538f23aa" title=" " alt="" coords="5,56,102,83"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="225,699,211,572,185,393,168,301,148,216,125,146,100,96,88,85,91,81,104,93,130,143,153,215,173,300,191,392,216,572,230,699"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$_multi_report_tests_8cpp.html#a1fd7b6a0d4dbb7f91fd5691b5b054bda" title=" " alt="" coords="5,107,102,133"/>
|
|
||||||
<area shape="poly" id="edge3_Node000001_Node000004" title=" " alt="" coords="224,699,209,581,183,417,165,333,146,256,124,192,100,147,87,136,91,132,104,144,128,190,151,254,171,332,188,416,214,581,229,699"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$_single_report_tests_8cpp.html#aac644123799c1f836d379c9789a064ab" title=" " alt="" coords="5,157,102,184"/>
|
|
||||||
<area shape="poly" id="edge4_Node000001_Node000005" title=" " alt="" coords="228,699,226,607,220,544,210,475,194,403,171,330,140,261,100,198,87,186,91,182,104,194,145,258,176,329,199,402,215,474,225,544,231,606,233,699"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$_multi_report_tests_8cpp.html#aa9e0389fa75046b52d13286af2c3b2a7" title=" " alt="" coords="5,208,102,235"/>
|
|
||||||
<area shape="poly" id="edge5_Node000001_Node000006" title=" " alt="" coords="227,699,222,614,204,496,188,431,166,367,137,305,100,248,87,237,90,233,104,245,141,302,171,365,193,430,210,495,227,614,233,699"/>
|
|
||||||
<area shape="rect" id="Node000007" href="$_single_report_tests_8cpp.html#aaefa1a1d4b3c190b7f46bb7f42512949" title=" " alt="" coords="5,259,102,285"/>
|
|
||||||
<area shape="poly" id="edge6_Node000001_Node000007" title=" " alt="" coords="226,700,219,623,199,518,183,461,161,403,134,349,100,299,87,288,90,284,104,296,138,346,166,401,188,459,204,517,224,622,231,699"/>
|
|
||||||
<area shape="rect" id="Node000008" href="$_single_report_tests_8cpp.html#a098111e0f361615318674b5b1b05ece4" title=" " alt="" coords="5,309,102,336"/>
|
|
||||||
<area shape="poly" id="edge7_Node000001_Node000008" title=" " alt="" coords="225,700,215,631,193,539,177,489,156,440,131,393,100,350,86,338,90,334,104,346,135,390,161,438,182,487,198,538,220,630,230,699"/>
|
|
||||||
<area shape="rect" id="Node000009" href="$_single_report_tests_8cpp.html#a35b0417a053d9fbf61a91a2110c3495c" title=" " alt="" coords="5,360,102,387"/>
|
|
||||||
<area shape="poly" id="edge8_Node000001_Node000009" title=" " alt="" coords="223,700,211,640,187,561,151,477,127,437,100,401,86,389,89,385,104,397,132,434,156,474,192,559,216,638,228,699"/>
|
|
||||||
<area shape="rect" id="Node000010" href="$_single_report_tests_8cpp.html#af9d07441bd8651bc21743664b7f99bb8" title=" " alt="" coords="5,411,102,437"/>
|
|
||||||
<area shape="poly" id="edge9_Node000001_Node000010" title=" " alt="" coords="221,700,206,649,181,583,146,514,124,481,100,451,85,440,89,436,104,447,129,478,151,511,186,581,211,647,226,699"/>
|
|
||||||
<area shape="rect" id="Node000011" href="$_single_report_tests_8cpp.html#ace1544ccc126d0b9eadd433f9cb41486" title=" " alt="" coords="5,461,102,488"/>
|
|
||||||
<area shape="poly" id="edge10_Node000001_Node000011" title=" " alt="" coords="218,701,200,659,175,606,141,551,100,502,85,491,88,486,104,498,145,548,179,604,205,657,223,699"/>
|
|
||||||
<area shape="rect" id="Node000012" href="$_single_report_tests_8cpp.html#a90980a9fc26b3a692ab2529c9f8e4747" title=" " alt="" coords="5,512,102,539"/>
|
|
||||||
<area shape="poly" id="edge11_Node000001_Node000012" title=" " alt="" coords="214,703,168,630,136,590,100,553,84,541,87,537,103,549,140,586,172,627,218,700"/>
|
|
||||||
<area shape="rect" id="Node000013" href="$_single_report_tests_8cpp.html#ab9b4ae43e33572d90c4c889452cd91ee" title=" " alt="" coords="5,563,102,589"/>
|
|
||||||
<area shape="poly" id="edge12_Node000001_Node000013" title=" " alt="" coords="207,705,160,655,100,603,82,592,85,588,103,599,163,651,210,701"/>
|
|
||||||
<area shape="rect" id="Node000014" href="$_single_report_tests_8cpp.html#a713376354af2a970230882e2a487050e" title=" " alt="" coords="5,613,102,640"/>
|
|
||||||
<area shape="poly" id="edge13_Node000001_Node000014" title=" " alt="" coords="193,709,100,654,79,643,82,638,103,650,196,704"/>
|
|
||||||
<area shape="rect" id="Node000015" href="$_single_report_tests_8cpp.html#ae4d70e11995e36808b6390b171aba0e8" title=" " alt="" coords="5,664,102,691"/>
|
|
||||||
<area shape="poly" id="edge14_Node000001_Node000015" title=" " alt="" coords="166,712,101,693,103,688,168,707"/>
|
|
||||||
<area shape="rect" id="Node000016" href="$_single_report_tests_8cpp.html#a429f6e7897a9609ddd093d66b6f7b1ff" title=" " alt="" coords="5,715,102,741"/>
|
|
||||||
<area shape="poly" id="edge15_Node000001_Node000016" title=" " alt="" coords="134,731,102,731,102,725,134,725"/>
|
|
||||||
<area shape="rect" id="Node000017" href="$_single_report_tests_8cpp.html#ae436161f7f0085f01ce63d9373944ae8" title=" " alt="" coords="5,765,102,792"/>
|
|
||||||
<area shape="poly" id="edge16_Node000001_Node000017" title=" " alt="" coords="168,749,103,768,101,763,166,744"/>
|
|
||||||
<area shape="rect" id="Node000018" href="$_single_report_tests_8cpp.html#acf249e215fca056266de6e833875925e" title=" " alt="" coords="5,816,102,843"/>
|
|
||||||
<area shape="poly" id="edge17_Node000001_Node000018" title=" " alt="" coords="196,752,103,806,82,818,79,813,100,802,193,747"/>
|
|
||||||
<area shape="rect" id="Node000019" href="$_single_report_tests_8cpp.html#a9f2e049a5b61721869c5f4757e313502" title=" " alt="" coords="5,867,102,893"/>
|
|
||||||
<area shape="poly" id="edge18_Node000001_Node000019" title=" " alt="" coords="210,755,163,805,103,857,85,868,82,864,100,853,160,801,207,751"/>
|
|
||||||
<area shape="rect" id="Node000020" href="$_single_report_tests_8cpp.html#a3cce613b379b768244a176a32b37667c" title=" " alt="" coords="5,917,102,944"/>
|
|
||||||
<area shape="poly" id="edge19_Node000001_Node000020" title=" " alt="" coords="218,756,172,829,140,870,103,907,87,919,84,915,100,903,136,866,168,826,214,753"/>
|
|
||||||
<area shape="rect" id="Node000021" href="$_init_deinit_tests_8cpp.html#a69680e2934e7ec3c6a1771270dc59f05" title=" " alt="" coords="5,968,102,995"/>
|
|
||||||
<area shape="poly" id="edge20_Node000001_Node000021" title=" " alt="" coords="223,757,205,799,179,852,145,908,104,958,88,970,85,965,100,954,141,905,175,850,200,797,218,755"/>
|
|
||||||
<area shape="rect" id="Node000022" href="$_multi_report_tests_8cpp.html#ad96cfd7c30e8693897688ce24bb53996" title=" " alt="" coords="5,1019,102,1045"/>
|
|
||||||
<area shape="poly" id="edge21_Node000001_Node000022" title=" " alt="" coords="226,757,211,809,186,875,151,945,129,978,104,1009,89,1020,85,1016,100,1005,124,975,146,942,181,873,206,807,221,756"/>
|
|
||||||
<area shape="rect" id="Node000023" href="$_init_deinit_tests_8cpp.html#ac4fb371054271d54830b58cc164dc0f6" title=" " alt="" coords="5,1069,102,1096"/>
|
|
||||||
<area shape="poly" id="edge22_Node000001_Node000023" title=" " alt="" coords="228,757,216,818,192,897,156,982,132,1022,104,1059,89,1071,86,1067,100,1055,127,1019,151,979,187,895,211,816,223,756"/>
|
|
||||||
<area shape="rect" id="Node000024" href="$_init_deinit_tests_8cpp.html#a6ed5310154fb7e7f290e619e6fbed708" title=" " alt="" coords="5,1120,102,1147"/>
|
|
||||||
<area shape="poly" id="edge23_Node000001_Node000024" title=" " alt="" coords="230,757,220,826,198,918,182,969,161,1018,135,1066,104,1110,90,1122,86,1118,100,1106,131,1063,156,1016,177,967,193,917,215,825,225,756"/>
|
|
||||||
<area shape="rect" id="Node000025" href="$_init_deinit_tests_8cpp.html#a96d79e5c8f3096a207d806be926af15b" title=" " alt="" coords="5,1171,102,1197"/>
|
|
||||||
<area shape="poly" id="edge24_Node000001_Node000025" title=" " alt="" coords="231,757,224,834,204,939,188,997,166,1055,138,1110,104,1160,90,1172,87,1168,100,1157,134,1107,161,1053,183,995,199,938,219,833,226,756"/>
|
|
||||||
<area shape="rect" id="Node000026" href="$_init_deinit_tests_8cpp.html#ab8015ecd4179bc39223921d6eef1165a" title=" " alt="" coords="5,1221,102,1248"/>
|
|
||||||
<area shape="poly" id="edge25_Node000001_Node000026" title=" " alt="" coords="233,757,227,842,210,961,193,1026,171,1091,141,1154,104,1211,90,1223,87,1219,100,1208,137,1151,166,1089,188,1025,204,960,222,842,227,757"/>
|
|
||||||
<area shape="rect" id="Node000027" href="$_init_deinit_tests_8cpp.html#ad71fea7e4a2e587d48d2bf7fadd711cc" title=" " alt="" coords="5,1272,102,1299"/>
|
|
||||||
<area shape="poly" id="edge26_Node000001_Node000027" title=" " alt="" coords="233,757,231,850,225,912,215,982,199,1054,176,1127,145,1198,104,1262,91,1274,87,1270,100,1258,140,1195,171,1126,194,1053,210,981,220,912,226,849,228,757"/>
|
|
||||||
<area shape="rect" id="Node000028" href="$_init_deinit_tests_8cpp.html#a9f7d58c894a252a5d5f4926f43c1da05" title=" " alt="" coords="5,1323,102,1349"/>
|
|
||||||
<area shape="poly" id="edge27_Node000001_Node000028" title=" " alt="" coords="229,757,214,875,188,1040,171,1124,151,1202,128,1266,104,1312,91,1324,87,1320,100,1309,124,1264,146,1200,165,1123,183,1039,209,875,224,757"/>
|
|
||||||
<area shape="rect" id="Node000029" href="$_multi_report_tests_8cpp.html#a1438f6b8587b635b6096dda2927fa9a1" title=" " alt="" coords="5,1373,102,1400"/>
|
|
||||||
<area shape="poly" id="edge28_Node000001_Node000029" title=" " alt="" coords="230,757,216,884,191,1064,173,1156,153,1241,130,1313,104,1363,91,1375,88,1371,100,1360,125,1310,148,1240,168,1155,185,1063,211,884,225,757"/>
|
|
||||||
<area shape="rect" id="Node000030" href="$_multi_report_tests_8cpp.html#a915d6c272bf95057a8bb22abfb307882" title=" " alt="" coords="5,1424,102,1451"/>
|
|
||||||
<area shape="poly" id="edge29_Node000001_Node000030" title=" " alt="" coords="231,757,218,893,193,1088,176,1189,156,1281,132,1359,104,1414,91,1425,88,1421,100,1410,127,1357,151,1280,171,1187,188,1087,213,893,225,757"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
63c0e8b27ef5c63411df199109689b0c
|
|
||||||
|
Before Width: | Height: | Size: 104 KiB |
|
|
@ -1,101 +0,0 @@
|
||||||
<map id="TEST_CASE" name="TEST_CASE">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="5,263,102,289"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$class_b_n_o08x_test_helper.html#a6bd040c7d670a9713f2ab8a8a3913518" title="Calls BNO08x constructor and creates new test IMU on heap." alt="" coords="150,93,326,136"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="66,261,148,182,194,144,198,148,151,186,70,264"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="159,196,317,239"/>
|
|
||||||
<area shape="poly" id="edge3_Node000001_Node000004" title=" " alt="" coords="97,260,154,241,155,246,99,265"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$class_b_n_o08x.html#aea8e2c6dd7a2c9899479a7f39fe94798" title="Initializes BNO08x sensor." alt="" coords="175,263,301,289"/>
|
|
||||||
<area shape="poly" id="edge4_Node000001_Node000005" title=" " alt="" coords="102,273,160,273,160,279,102,279"/>
|
|
||||||
<area shape="rect" id="Node000055" href="$class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="155,313,321,356"/>
|
|
||||||
<area shape="poly" id="edge48_Node000001_Node000055" title=" " alt="" coords="99,287,155,306,154,311,97,292"/>
|
|
||||||
<area shape="rect" id="Node000056" href="$_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="156,380,320,407"/>
|
|
||||||
<area shape="poly" id="edge49_Node000001_Node000056" title=" " alt="" coords="67,288,102,326,125,348,151,366,162,371,159,376,148,370,122,352,98,330,63,291"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="374,56,557,99"/>
|
|
||||||
<area shape="poly" id="edge2_Node000002_Node000003" title=" " alt="" coords="326,98,358,92,359,98,327,103"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$class_b_n_o08x.html#a96d47dd0f9aedfbe3f731f8ae76b2e85" title="Requests product ID, prints the returned info over serial, and returns the reason for the most resent..." alt="" coords="377,123,555,149"/>
|
|
||||||
<area shape="poly" id="edge5_Node000005_Node000006" title=" " alt="" coords="300,262,324,249,341,229,348,208,355,186,372,165,388,154,391,158,376,169,360,189,353,210,345,231,328,253,302,267"/>
|
|
||||||
<area shape="rect" id="Node000011" href="$class_b_n_o08x.html#a28cd1c0b3477571d87133234e6358503" title="Hard resets BNO08x sensor." alt="" coords="396,179,535,205"/>
|
|
||||||
<area shape="poly" id="edge10_Node000005_Node000011" title=" " alt="" coords="293,260,325,248,349,235,373,222,405,209,407,213,375,226,351,240,327,253,295,265"/>
|
|
||||||
<area shape="rect" id="Node000013" href="$class_b_n_o08x.html#a589eb9780f5bf613bbd447ef5b9ade3d" title="Initializes required esp-idf SPI data structures with values from user passed bno08x_config_t struct." alt="" coords="382,236,550,263"/>
|
|
||||||
<area shape="poly" id="edge12_Node000005_Node000013" title=" " alt="" coords="300,266,365,258,366,264,301,271"/>
|
|
||||||
<area shape="rect" id="Node000015" href="$class_b_n_o08x.html#ae0dab25557befcf62bf384fdc241ef10" title="Initializes required gpio." alt="" coords="403,288,529,315"/>
|
|
||||||
<area shape="poly" id="edge14_Node000005_Node000015" title=" " alt="" coords="301,280,387,290,387,295,300,286"/>
|
|
||||||
<area shape="rect" id="Node000018" href="$class_b_n_o08x.html#aa27026da2c52b4aca49b78863f10ec61" title="Initializes host interrupt ISR." alt="" coords="394,339,538,365"/>
|
|
||||||
<area shape="poly" id="edge17_Node000005_Node000018" title=" " alt="" coords="294,287,327,299,375,324,394,331,392,336,373,329,325,304,292,292"/>
|
|
||||||
<area shape="rect" id="Node000020" href="$class_b_n_o08x.html#a58f43c8bb1e7fe8560ce442d46240e81" title="Initializes SPI." alt="" coords="406,389,525,416"/>
|
|
||||||
<area shape="poly" id="edge19_Node000005_Node000020" title=" " alt="" coords="302,286,328,299,345,319,352,338,360,357,376,375,393,385,390,390,372,379,355,360,347,340,340,321,324,303,300,290"/>
|
|
||||||
<area shape="rect" id="Node000021" href="$class_b_n_o08x.html#a06f99a6b2182b49a0e61e2107f2be6be" title="Launches spi_task and data_proc_task on constructor call." alt="" coords="388,451,543,477"/>
|
|
||||||
<area shape="poly" id="edge20_Node000005_Node000021" title=" " alt="" coords="302,284,328,299,341,315,349,332,353,364,357,395,364,411,376,426,397,441,393,446,372,430,359,413,352,397,348,364,344,333,337,318,324,303,299,288"/>
|
|
||||||
<area shape="rect" id="Node000007" href="$class_b_n_o08x.html#ab5f200069a2f8cb74cb79c6f162da5a1" title="Queues a packet containing the request product ID command." alt="" coords="621,5,784,48"/>
|
|
||||||
<area shape="poly" id="edge6_Node000006_Node000007" title=" " alt="" coords="532,120,556,108,570,97,579,84,589,71,604,58,612,53,614,58,607,62,593,75,584,87,574,100,559,113,534,124"/>
|
|
||||||
<area shape="rect" id="Node000009" href="$class_b_n_o08x.html#a4f12de628073f44b2a3fab2688cf1caf" title="Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse." alt="" coords="625,72,780,99"/>
|
|
||||||
<area shape="poly" id="edge8_Node000006_Node000009" title=" " alt="" coords="531,119,621,100,622,105,532,125"/>
|
|
||||||
<area shape="rect" id="Node000010" href="$class_b_n_o08x.html#a7cdeb849e728487de961cdfd4030c773" title="Waits for a queued packet to be sent or host_int_timeout_ms to elapse." alt="" coords="615,123,790,149"/>
|
|
||||||
<area shape="poly" id="edge9_Node000006_Node000010" title=" " alt="" coords="555,133,599,133,599,139,555,139"/>
|
|
||||||
<area shape="rect" id="Node000008" href="$class_b_n_o08x.html#a62c570ba96512f4d0d10b2594048de1f" title="Queues an SHTP packet to be sent via SPI." alt="" coords="852,13,1011,40"/>
|
|
||||||
<area shape="poly" id="edge7_Node000007_Node000008" title=" " alt="" coords="784,24,836,24,836,29,784,29"/>
|
|
||||||
<area shape="rect" id="Node000012" href="$class_b_n_o08x.html#a2897a178bf2c53cd99df0d4570edf72e" title="Waits for data to be received over SPI, or host_int_timeout_ms to elapse." alt="" coords="615,173,790,200"/>
|
|
||||||
<area shape="poly" id="edge11_Node000011_Node000012" title=" " alt="" coords="536,188,600,186,600,192,536,193"/>
|
|
||||||
<area shape="rect" id="Node000014" href="$class_b_n_o08x.html#a453ec8a70646651d4e5b10bf0b2e4d61" title="Resets all data returned by public getter APIs to initial values of 0 and low accuracy." alt="" coords="623,224,782,267"/>
|
|
||||||
<area shape="poly" id="edge13_Node000013_Node000014" title=" " alt="" coords="550,245,608,244,608,250,550,251"/>
|
|
||||||
<area shape="rect" id="Node000016" href="$class_b_n_o08x.html#a8f34d5475474f00ae6a92f73c1fe14e4" title="Initializes required gpio inputs." alt="" coords="618,291,787,317"/>
|
|
||||||
<area shape="poly" id="edge15_Node000015_Node000016" title=" " alt="" coords="529,299,603,300,603,306,529,305"/>
|
|
||||||
<area shape="rect" id="Node000017" href="$class_b_n_o08x.html#ad0b9e8f8d051798bb1da9b19598dbd64" title="Initializes required gpio outputs." alt="" coords="614,341,791,368"/>
|
|
||||||
<area shape="poly" id="edge16_Node000015_Node000017" title=" " alt="" coords="529,313,626,335,625,340,527,318"/>
|
|
||||||
<area shape="rect" id="Node000019" href="$class_b_n_o08x.html#a804b95c58c30d36933fd251626b85bf7" title="HINT interrupt service routine, handles falling edge of BNO08x HINT pin." alt="" coords="628,392,777,419"/>
|
|
||||||
<area shape="poly" id="edge18_Node000018_Node000019" title=" " alt="" coords="529,363,626,385,625,391,527,368"/>
|
|
||||||
<area shape="rect" id="Node000022" href="$class_b_n_o08x.html#a0ae135d7bf7a5f047a1d1aa5cc07e520" title="Static function used to launch data processing task." alt="" coords="619,443,786,485"/>
|
|
||||||
<area shape="poly" id="edge21_Node000021_Node000022" title=" " alt="" coords="544,461,603,461,603,467,544,467"/>
|
|
||||||
<area shape="rect" id="Node000049" href="$class_b_n_o08x.html#a0ce6d9db873555f1ebe7e095251eab74" title="Static function used to launch spi task." alt="" coords="605,532,800,559"/>
|
|
||||||
<area shape="poly" id="edge42_Node000021_Node000049" title=" " alt="" coords="508,475,648,524,646,529,506,481"/>
|
|
||||||
<area shape="rect" id="Node000023" href="$class_b_n_o08x.html#ab4373e9b87837ea9fcbc0b536338c7b8" title="Task responsible parsing packets. Executed when SPI task sends a packet to be parsed,..." alt="" coords="848,440,1015,467"/>
|
|
||||||
<area shape="poly" id="edge22_Node000022_Node000023" title=" " alt="" coords="787,457,832,455,832,461,787,463"/>
|
|
||||||
<area shape="rect" id="Node000024" href="$class_b_n_o08x.html#a1c47d27917ae3b2876efa121b803f924" title="Parses a packet received from bno08x, updating any data according to received reports." alt="" coords="1067,377,1223,404"/>
|
|
||||||
<area shape="poly" id="edge23_Node000023_Node000024" title=" " alt="" coords="979,437,1081,406,1083,412,980,442"/>
|
|
||||||
<area shape="rect" id="Node000048" href="$class_b_n_o08x.html#a05e4cd5861b55fc0182d7dd13bb85e49" title="Prints the passed SHTP packet to serial console with ESP_LOG statement." alt="" coords="1071,440,1220,467"/>
|
|
||||||
<area shape="poly" id="edge41_Node000023_Node000048" title=" " alt="" coords="1016,451,1055,451,1055,456,1016,456"/>
|
|
||||||
<area shape="rect" id="Node000025" href="$class_b_n_o08x.html#a4f66045a0528a0c17c52421ea51612e7" title="Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)" alt="" coords="1288,161,1462,204"/>
|
|
||||||
<area shape="poly" id="edge24_Node000024_Node000025" title=" " alt="" coords="1150,376,1168,343,1195,300,1230,254,1274,214,1280,209,1283,214,1277,218,1234,257,1199,303,1172,346,1155,378"/>
|
|
||||||
<area shape="rect" id="Node000026" href="$class_b_n_o08x.html#a206c0e3ddc3b745b56914976d6e69981" title="Parses get feature request report received from BNO08x." alt="" coords="1297,228,1453,271"/>
|
|
||||||
<area shape="poly" id="edge25_Node000024_Node000026" title=" " alt="" coords="1158,375,1206,329,1239,303,1274,280,1284,275,1287,280,1277,285,1242,308,1210,333,1161,379"/>
|
|
||||||
<area shape="rect" id="Node000027" href="$class_b_n_o08x.html#a51b360d795563b55559f11efb40be36a" title="Sends packet to be parsed to meta data function call (FRS_read_data()) through queue." alt="" coords="1293,295,1457,337"/>
|
|
||||||
<area shape="poly" id="edge26_Node000024_Node000027" title=" " alt="" coords="1188,374,1292,340,1294,345,1190,379"/>
|
|
||||||
<area shape="rect" id="Node000028" href="$class_b_n_o08x.html#a7be6047fef851a064c7cbc9eba092f6d" title="Parses received gyro integrated rotation vector report sent by BNO08x." alt="" coords="1304,361,1446,420"/>
|
|
||||||
<area shape="poly" id="edge27_Node000024_Node000028" title=" " alt="" coords="1223,388,1288,388,1288,393,1223,393"/>
|
|
||||||
<area shape="rect" id="Node000030" href="$class_b_n_o08x.html#a8d9db3e1b6208c2661e1c543deefa53d" title="Parses received input report sent by BNO08x." alt="" coords="1302,444,1448,487"/>
|
|
||||||
<area shape="poly" id="edge29_Node000024_Node000030" title=" " alt="" coords="1190,402,1294,436,1292,441,1188,407"/>
|
|
||||||
<area shape="rect" id="Node000047" href="$class_b_n_o08x.html#a29cfd7fc2816483ebebe9d55b677a036" title="Parses product id report and prints device info." alt="" coords="1295,511,1455,553"/>
|
|
||||||
<area shape="poly" id="edge40_Node000024_Node000047" title=" " alt="" coords="1189,402,1229,426,1245,445,1253,463,1261,480,1277,497,1283,501,1280,505,1274,501,1257,483,1248,465,1241,448,1226,430,1186,407"/>
|
|
||||||
<area shape="rect" id="Node000029" href="$class_b_n_o08x.html#ab02386f13caa446bab5921c1a71f92ab" title="Updates integrated gyro rotation vector data from SHTP channel 5 (CHANNEL_GYRO) special report data." alt="" coords="1551,151,1733,193"/>
|
|
||||||
<area shape="poly" id="edge28_Node000028_Node000029" title=" " alt="" coords="1445,368,1473,347,1486,330,1492,312,1495,276,1498,240,1506,221,1521,203,1535,192,1539,196,1525,207,1511,224,1504,241,1500,276,1497,313,1490,332,1477,351,1448,372"/>
|
|
||||||
<area shape="rect" id="Node000031" href="$class_b_n_o08x.html#a002aa97c9af8f6df2d0c83034e4f7b55" title="Parses data from received input report." alt="" coords="1569,217,1715,260"/>
|
|
||||||
<area shape="poly" id="edge30_Node000030_Node000031" title=" " alt="" coords="1447,448,1473,430,1487,411,1494,391,1495,351,1497,311,1505,290,1521,270,1536,258,1554,249,1556,254,1539,263,1525,274,1510,293,1503,312,1501,352,1499,392,1492,413,1477,434,1450,452"/>
|
|
||||||
<area shape="rect" id="Node000032" href="$class_b_n_o08x.html#afe588fbd0055193d3bc08984d7732354" title="Updates accelerometer data from parsed input report." alt="" coords="1523,284,1761,311"/>
|
|
||||||
<area shape="poly" id="edge31_Node000030_Node000032" title=" " alt="" coords="1447,447,1473,430,1484,417,1490,404,1495,376,1501,348,1508,334,1521,321,1526,317,1530,321,1524,325,1513,337,1506,350,1501,377,1495,405,1489,420,1476,434,1449,451"/>
|
|
||||||
<area shape="rect" id="Node000033" href="$class_b_n_o08x.html#a962b695ef4733d558c6f9684da0931ab" title="Updates linear gyro data from parsed input report." alt="" coords="1552,335,1732,377"/>
|
|
||||||
<area shape="poly" id="edge32_Node000030_Node000033" title=" " alt="" coords="1447,442,1473,430,1487,419,1497,409,1506,398,1521,387,1536,380,1538,385,1524,392,1510,402,1501,412,1491,423,1476,434,1449,447"/>
|
|
||||||
<area shape="rect" id="Node000034" href="$class_b_n_o08x.html#af971d82426740e62c1f05adcd2c9ce7c" title="Updates command data from parsed input report." alt="" coords="1535,401,1749,428"/>
|
|
||||||
<area shape="poly" id="edge33_Node000030_Node000034" title=" " alt="" coords="1448,449,1552,429,1553,434,1449,454"/>
|
|
||||||
<area shape="rect" id="Node000035" href="$class_b_n_o08x.html#ad7de3999d4df19038e27c01f9b02010e" title="Updates gravity data from parsed input report." alt="" coords="1545,452,1739,479"/>
|
|
||||||
<area shape="poly" id="edge34_Node000030_Node000035" title=" " alt="" coords="1448,463,1530,463,1530,468,1448,468"/>
|
|
||||||
<area shape="rect" id="Node000036" href="$class_b_n_o08x.html#a7416d844f6188c8d16f181d6d4431708" title="Updates linear accelerometer data from parsed input report." alt="" coords="1571,503,1713,545"/>
|
|
||||||
<area shape="poly" id="edge35_Node000030_Node000036" title=" " alt="" coords="1449,479,1556,502,1555,508,1448,484"/>
|
|
||||||
<area shape="rect" id="Node000037" href="$class_b_n_o08x.html#a3abf4a199bc7a03ac7447c2781673d88" title="Updates magnetic field data from parsed input report." alt="" coords="1550,569,1734,596"/>
|
|
||||||
<area shape="poly" id="edge36_Node000030_Node000037" title=" " alt="" coords="1449,482,1476,497,1492,512,1501,527,1509,542,1524,555,1536,562,1534,566,1521,560,1505,545,1496,530,1488,515,1473,501,1447,487"/>
|
|
||||||
<area shape="rect" id="Node000038" href="$class_b_n_o08x.html#a04489cf9a125495c7cf07c6ba5e9f6c0" title="Updates activity classifier data from parsed input report." alt="" coords="1555,620,1729,663"/>
|
|
||||||
<area shape="poly" id="edge37_Node000030_Node000038" title=" " alt="" coords="1449,479,1476,497,1489,511,1496,525,1501,553,1506,580,1513,593,1524,606,1542,618,1539,623,1521,610,1509,596,1501,582,1496,554,1491,527,1484,514,1473,501,1447,484"/>
|
|
||||||
<area shape="rect" id="Node000039" href="$class_b_n_o08x.html#a83fed63c67957ec4338afd43087d6e22" title="Updates raw accelerometer data from parsed input report." alt="" coords="1570,687,1714,729"/>
|
|
||||||
<area shape="poly" id="edge38_Node000030_Node000039" title=" " alt="" coords="1449,478,1477,497,1493,520,1500,543,1501,587,1502,631,1509,652,1525,673,1539,684,1556,693,1554,698,1536,689,1521,677,1504,654,1496,632,1495,587,1495,543,1488,522,1473,501,1446,482"/>
|
|
||||||
<area shape="rect" id="Node000040" href="$class_b_n_o08x.html#ad0f0fec4e53029b4ba907414a36ac5ea" title="Updates raw gyro data from parsed input report." alt="" coords="1570,753,1714,796"/>
|
|
||||||
<area shape="poly" id="edge39_Node000030_Node000040" title=" " alt="" coords="1450,477,1477,497,1497,528,1505,560,1505,591,1501,621,1496,651,1497,681,1505,710,1525,740,1539,752,1556,760,1554,765,1536,756,1521,743,1500,712,1491,681,1491,651,1495,620,1499,590,1500,560,1492,531,1473,501,1446,482"/>
|
|
||||||
<area shape="rect" id="Node000050" href="$class_b_n_o08x.html#a2ecd4ed60f82730ae230c61687ec92bf" title="Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x." alt="" coords="868,577,995,604"/>
|
|
||||||
<area shape="poly" id="edge43_Node000049_Node000050" title=" " alt="" coords="774,557,853,572,852,578,773,562"/>
|
|
||||||
<area shape="rect" id="Node000051" href="$class_b_n_o08x.html#a8d9f28d8857279a3c4b1f62f6dabb638" title="Receives a SHTP packet via SPI and sends it to data_proc_task()" alt="" coords="1063,577,1227,604"/>
|
|
||||||
<area shape="poly" id="edge44_Node000050_Node000051" title=" " alt="" coords="995,588,1047,588,1047,593,995,593"/>
|
|
||||||
<area shape="rect" id="Node000054" href="$class_b_n_o08x.html#a2c359a44a2c8e83ecb258a340e2d0e1a" title="Sends a queued SHTP packet via SPI." alt="" coords="1069,628,1221,655"/>
|
|
||||||
<area shape="poly" id="edge47_Node000050_Node000054" title=" " alt="" coords="992,602,1072,621,1071,626,990,607"/>
|
|
||||||
<area shape="rect" id="Node000052" href="$class_b_n_o08x.html#a9ee7e73f695af8965a9ede50136d5a8c" title="Receives a SHTP packet body via SPI." alt="" coords="1275,577,1475,604"/>
|
|
||||||
<area shape="poly" id="edge45_Node000051_Node000052" title=" " alt="" coords="1228,588,1260,588,1260,593,1228,593"/>
|
|
||||||
<area shape="rect" id="Node000053" href="$class_b_n_o08x.html#acb246769719351e02bf2aff06d039475" title="Receives a SHTP packet header via SPI." alt="" coords="1293,628,1457,671"/>
|
|
||||||
<area shape="poly" id="edge46_Node000051_Node000053" title=" " alt="" coords="1201,602,1278,622,1277,627,1200,607"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
b3c196a6ebab141b340f0e0a7846097c
|
|
||||||
|
Before Width: | Height: | Size: 94 KiB |
|
|
@ -1,652 +0,0 @@
|
||||||
<!DOCTYPE html PUBLIC "-//W3C//DTD XHTML 1.0 Transitional//EN" "https://www.w3.org/TR/xhtml1/DTD/xhtml1-transitional.dtd">
|
|
||||||
<html xmlns="http://www.w3.org/1999/xhtml" lang="en-US">
|
|
||||||
<head>
|
|
||||||
<meta http-equiv="Content-Type" content="text/xhtml;charset=UTF-8"/>
|
|
||||||
<meta http-equiv="X-UA-Compatible" content="IE=11"/>
|
|
||||||
<meta name="generator" content="Doxygen 1.10.0"/>
|
|
||||||
<meta name="viewport" content="width=device-width, initial-scale=1"/>
|
|
||||||
<title>esp32_BNO08x: InitDeinitTests.cpp File Reference</title>
|
|
||||||
<link href="tabs.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="jquery.js"></script>
|
|
||||||
<script type="text/javascript" src="dynsections.js"></script>
|
|
||||||
<script type="text/javascript" src="clipboard.js"></script>
|
|
||||||
<link href="navtree.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="resize.js"></script>
|
|
||||||
<script type="text/javascript" src="navtreedata.js"></script>
|
|
||||||
<script type="text/javascript" src="navtree.js"></script>
|
|
||||||
<script type="text/javascript" src="cookie.js"></script>
|
|
||||||
<link href="search/search.css" rel="stylesheet" type="text/css"/>
|
|
||||||
<script type="text/javascript" src="search/searchdata.js"></script>
|
|
||||||
<script type="text/javascript" src="search/search.js"></script>
|
|
||||||
<link href="doxygen.css" rel="stylesheet" type="text/css" />
|
|
||||||
</head>
|
|
||||||
<body>
|
|
||||||
<div id="top"><!-- do not remove this div, it is closed by doxygen! -->
|
|
||||||
<div id="titlearea">
|
|
||||||
<table cellspacing="0" cellpadding="0">
|
|
||||||
<tbody>
|
|
||||||
<tr id="projectrow">
|
|
||||||
<td id="projectalign">
|
|
||||||
<div id="projectname">esp32_BNO08x<span id="projectnumber"> 1.2</span>
|
|
||||||
</div>
|
|
||||||
<div id="projectbrief">C++ BNO08x IMU driver component for esp-idf.</div>
|
|
||||||
</td>
|
|
||||||
</tr>
|
|
||||||
</tbody>
|
|
||||||
</table>
|
|
||||||
</div>
|
|
||||||
<!-- end header part -->
|
|
||||||
<!-- Generated by Doxygen 1.10.0 -->
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
var searchBox = new SearchBox("searchBox", "search/",'.html');
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<script type="text/javascript" src="menudata.js"></script>
|
|
||||||
<script type="text/javascript" src="menu.js"></script>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function() {
|
|
||||||
initMenu('',true,false,'search.php','Search');
|
|
||||||
$(function() { init_search(); });
|
|
||||||
});
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="main-nav"></div>
|
|
||||||
</div><!-- top -->
|
|
||||||
<div id="side-nav" class="ui-resizable side-nav-resizable">
|
|
||||||
<div id="nav-tree">
|
|
||||||
<div id="nav-tree-contents">
|
|
||||||
<div id="nav-sync" class="sync"></div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<div id="splitbar" style="-moz-user-select:none;"
|
|
||||||
class="ui-resizable-handle">
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<script type="text/javascript">
|
|
||||||
/* @license magnet:?xt=urn:btih:d3d9a9a6595521f9666a5e94cc830dab83b65699&dn=expat.txt MIT */
|
|
||||||
$(function(){initNavTree('_init_deinit_tests_8cpp.html',''); initResizable(); });
|
|
||||||
/* @license-end */
|
|
||||||
</script>
|
|
||||||
<div id="doc-content">
|
|
||||||
<!-- window showing the filter options -->
|
|
||||||
<div id="MSearchSelectWindow"
|
|
||||||
onmouseover="return searchBox.OnSearchSelectShow()"
|
|
||||||
onmouseout="return searchBox.OnSearchSelectHide()"
|
|
||||||
onkeydown="return searchBox.OnSearchSelectKey(event)">
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<!-- iframe showing the search results (closed by default) -->
|
|
||||||
<div id="MSearchResultsWindow">
|
|
||||||
<div id="MSearchResults">
|
|
||||||
<div class="SRPage">
|
|
||||||
<div id="SRIndex">
|
|
||||||
<div id="SRResults"></div>
|
|
||||||
<div class="SRStatus" id="Loading">Loading...</div>
|
|
||||||
<div class="SRStatus" id="Searching">Searching...</div>
|
|
||||||
<div class="SRStatus" id="NoMatches">No Matches</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
<div class="header">
|
|
||||||
<div class="summary">
|
|
||||||
<a href="#func-members">Functions</a> </div>
|
|
||||||
<div class="headertitle"><div class="title">InitDeinitTests.cpp File Reference</div></div>
|
|
||||||
</div><!--header-->
|
|
||||||
<div class="contents">
|
|
||||||
<div class="textblock"><code>#include "unity.h"</code><br />
|
|
||||||
<code>#include "<a class="el" href="_b_n_o08x_test_helper_8hpp_source.html">../include/BNO08xTestHelper.hpp</a>"</code><br />
|
|
||||||
</div><div class="textblock"><div class="dynheader">
|
|
||||||
Include dependency graph for InitDeinitTests.cpp:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_init_deinit_tests_8cpp__incl.png" border="0" usemap="#a_init_deinit_tests_8cpp" alt=""/></div>
|
|
||||||
<map name="a_init_deinit_tests_8cpp" id="a_init_deinit_tests_8cpp">
|
|
||||||
<area shape="rect" title=" " alt="" coords="367,5,496,32"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="321,80,382,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="419,35,378,72,375,68,416,31"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_test_helper_8hpp.html" title=" " alt="" coords="406,80,620,107"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="447,31,489,68,486,72,444,35"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,229,66,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="473,110,81,230,79,225,471,105"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x_8hpp.html" title=" " alt="" coords="652,155,747,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="546,105,654,146,652,151,544,110"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,174,410,189,249,207,81,232,80,227,248,201,410,184,651,168"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="90,229,168,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="651,176,451,195,320,211,184,231,183,226,319,206,451,189,651,170"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="192,229,253,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,176,486,196,379,211,268,232,267,226,378,206,485,190,651,171"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="277,229,338,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,178,521,199,354,231,352,226,520,193,651,173"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="361,229,438,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="652,183,454,231,452,226,651,178"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="461,229,517,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="664,184,532,229,530,224,662,179"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="541,229,618,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="680,184,615,223,612,219,677,180"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="643,229,756,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="702,182,702,214,697,214,697,182"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="780,229,870,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="723,180,791,219,789,224,720,184"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="893,229,1034,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="746,179,904,222,902,227,745,184"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1058,229,1162,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,175,1043,226,1042,231,747,180"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1186,229,1341,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,173,1171,226,1170,232,747,178"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1365,229,1479,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,170,1001,189,1172,206,1350,226,1349,232,1172,211,1000,195,747,175"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1504,229,1626,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,169,1055,187,1268,204,1488,226,1488,232,1267,209,1055,192,747,174"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1650,229,1754,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,168,1112,182,1369,200,1635,226,1634,232,1368,205,1112,188,747,173"/>
|
|
||||||
<area shape="rect" href="_b_n_o08x__global__types_8hpp.html" title=" " alt="" coords="1779,229,1954,256"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,168,1161,186,1456,203,1763,226,1763,232,1456,209,1160,192,747,174"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1681,304,1771,331"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1843,259,1766,299,1763,294,1841,254"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1796,304,1936,331"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1869,257,1869,288,1864,288,1864,257"/>
|
|
||||||
<area shape="rect" title=" " alt="" coords="1961,304,2091,331"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1895,254,1986,295,1983,300,1893,259"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
</div><table class="memberdecls">
|
|
||||||
<tr class="heading"><td colspan="2"><h2 class="groupheader"><a id="func-members" name="func-members"></a>
|
|
||||||
Functions</h2></td></tr>
|
|
||||||
<tr class="memitem:a6ed5310154fb7e7f290e619e6fbed708" id="r_a6ed5310154fb7e7f290e619e6fbed708"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a6ed5310154fb7e7f290e619e6fbed708">TEST_CASE</a> ("Init Config Args", "[InitComprehensive]")</td></tr>
|
|
||||||
<tr class="separator:a6ed5310154fb7e7f290e619e6fbed708"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a96d79e5c8f3096a207d806be926af15b" id="r_a96d79e5c8f3096a207d806be926af15b"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a96d79e5c8f3096a207d806be926af15b">TEST_CASE</a> ("Init GPIO", "[InitComprehensive]")</td></tr>
|
|
||||||
<tr class="separator:a96d79e5c8f3096a207d806be926af15b"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:ab8015ecd4179bc39223921d6eef1165a" id="r_ab8015ecd4179bc39223921d6eef1165a"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="#ab8015ecd4179bc39223921d6eef1165a">TEST_CASE</a> ("Init HINT ISR", "[InitComprehensive]")</td></tr>
|
|
||||||
<tr class="separator:ab8015ecd4179bc39223921d6eef1165a"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:ad71fea7e4a2e587d48d2bf7fadd711cc" id="r_ad71fea7e4a2e587d48d2bf7fadd711cc"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="#ad71fea7e4a2e587d48d2bf7fadd711cc">TEST_CASE</a> ("Init SPI", "[InitComprehensive]")</td></tr>
|
|
||||||
<tr class="separator:ad71fea7e4a2e587d48d2bf7fadd711cc"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a9f7d58c894a252a5d5f4926f43c1da05" id="r_a9f7d58c894a252a5d5f4926f43c1da05"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a9f7d58c894a252a5d5f4926f43c1da05">TEST_CASE</a> ("InitComprehensive Tasks", "[InitComprehensive]")</td></tr>
|
|
||||||
<tr class="separator:a9f7d58c894a252a5d5f4926f43c1da05"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:a69680e2934e7ec3c6a1771270dc59f05" id="r_a69680e2934e7ec3c6a1771270dc59f05"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="#a69680e2934e7ec3c6a1771270dc59f05">TEST_CASE</a> ("Finish Init", "[InitComprehensive]")</td></tr>
|
|
||||||
<tr class="separator:a69680e2934e7ec3c6a1771270dc59f05"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
<tr class="memitem:ac4fb371054271d54830b58cc164dc0f6" id="r_ac4fb371054271d54830b58cc164dc0f6"><td class="memItemLeft" align="right" valign="top"> </td><td class="memItemRight" valign="bottom"><a class="el" href="#ac4fb371054271d54830b58cc164dc0f6">TEST_CASE</a> ("Init & Deinit", "[InitDenit]")</td></tr>
|
|
||||||
<tr class="separator:ac4fb371054271d54830b58cc164dc0f6"><td class="memSeparator" colspan="2"> </td></tr>
|
|
||||||
</table>
|
|
||||||
<h2 class="groupheader">Function Documentation</h2>
|
|
||||||
<a id="a69680e2934e7ec3c6a1771270dc59f05" name="a69680e2934e7ec3c6a1771270dc59f05"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a69680e2934e7ec3c6a1771270dc59f05">◆ </a></span>TEST_CASE() <span class="overload">[1/7]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">TEST_CASE </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">"Finish Init"</td> <td class="paramname"><span class="paramname">, </span></td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
|
||||||
<td class="paramkey"></td>
|
|
||||||
<td></td>
|
|
||||||
<td class="paramtype">""</td> <td class="paramname"><span class="paramname">[InitComprehensive]</span> )</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph.png" border="0" usemap="#a_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph" alt=""/></div>
|
|
||||||
<map name="a_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph" id="a_init_deinit_tests_8cpp_a69680e2934e7ec3c6a1771270dc59f05_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,219,102,245"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="150,5,333,48"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="56,217,67,185,86,143,113,98,148,58,152,55,155,59,152,62,117,101,91,145,72,187,61,219"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a96d47dd0f9aedfbe3f731f8ae76b2e85" title="Requests product ID, prints the returned info over serial, and returns the reason for the most resent..." alt="" coords="152,72,331,99"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="60,217,93,164,118,134,148,108,157,103,160,108,151,113,122,138,97,167,64,219"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="162,123,321,165"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="75,216,148,175,161,169,163,174,151,180,78,220"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a28cd1c0b3477571d87133234e6358503" title="Hard resets BNO08x sensor." alt="" coords="172,189,311,216"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="102,222,156,213,157,219,102,227"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919" title="Prints end begin banner." alt="" coords="159,240,324,283"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="102,237,144,243,143,249,102,242"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="159,307,324,349"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="74,244,109,268,151,292,162,298,160,303,148,297,106,272,71,248"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885" title="Prints test begin banner." alt="" coords="159,373,324,416"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="64,244,97,300,122,332,151,359,157,363,154,367,148,363,118,335,92,303,59,247"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="160,440,323,467"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="60,245,69,282,86,331,113,382,131,406,151,426,157,430,153,434,148,430,127,409,109,385,82,333,64,283,55,246"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ab5f200069a2f8cb74cb79c6f162da5a1" title="Queues a packet containing the request product ID command." alt="" coords="387,5,550,48"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="295,69,371,49,372,54,297,74"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4f12de628073f44b2a3fab2688cf1caf" title="Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse." alt="" coords="392,72,546,99"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="331,83,376,83,376,88,331,88"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a7cdeb849e728487de961cdfd4030c773" title="Waits for a queued packet to be sent or host_int_timeout_ms to elapse." alt="" coords="381,123,556,149"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="305,97,391,116,390,121,304,102"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a62c570ba96512f4d0d10b2594048de1f" title="Queues an SHTP packet to be sent via SPI." alt="" coords="604,13,764,40"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="550,24,589,24,589,29,550,29"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a2897a178bf2c53cd99df0d4570edf72e" title="Waits for data to be received over SPI, or host_int_timeout_ms to elapse." alt="" coords="381,189,556,216"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="311,200,365,200,365,205,311,205"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="ac4fb371054271d54830b58cc164dc0f6" name="ac4fb371054271d54830b58cc164dc0f6"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#ac4fb371054271d54830b58cc164dc0f6">◆ </a></span>TEST_CASE() <span class="overload">[2/7]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">TEST_CASE </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">"Init & Deinit"</td> <td class="paramname"><span class="paramname">, </span></td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
|
||||||
<td class="paramkey"></td>
|
|
||||||
<td></td>
|
|
||||||
<td class="paramtype">""</td> <td class="paramname"><span class="paramname">[InitDenit]</span> )</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph.png" border="0" usemap="#a_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph" alt=""/></div>
|
|
||||||
<map name="a_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph" id="a_init_deinit_tests_8cpp_ac4fb371054271d54830b58cc164dc0f6_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,269,102,296"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a6bd040c7d670a9713f2ab8a8a3913518" title="Calls BNO08x constructor and creates new test IMU on heap." alt="" coords="150,56,326,99"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="57,268,88,197,114,154,148,115,161,105,165,109,151,119,119,157,93,199,62,270"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="374,56,557,99"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="59,268,92,215,118,185,148,159,226,136,361,100,363,106,227,141,151,164,122,188,97,218,64,270"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="159,173,317,216"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="75,267,148,226,161,220,163,225,151,230,78,271"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#aea8e2c6dd7a2c9899479a7f39fe94798" title="Initializes BNO08x sensor." alt="" coords="175,240,301,267"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="102,272,160,263,160,268,103,278"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919" title="Prints end begin banner." alt="" coords="155,291,321,333"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="103,288,140,294,139,299,102,293"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="155,357,321,400"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="75,294,109,318,151,343,162,348,160,353,148,348,107,323,72,299"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885" title="Prints test begin banner." alt="" coords="155,424,321,467"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="64,295,97,350,122,382,151,410,157,414,154,418,148,414,118,386,92,353,59,298"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="156,491,320,517"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="60,296,69,332,87,381,114,433,131,456,151,477,157,481,153,485,148,481,127,460,109,435,82,383,64,334,55,297"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="326,75,358,75,358,80,326,80"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a96d47dd0f9aedfbe3f731f8ae76b2e85" title="Requests product ID, prints the returned info over serial, and returns the reason for the most resent..." alt="" coords="377,123,555,149"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="300,238,324,226,339,212,348,198,357,182,372,167,397,153,400,158,376,171,361,186,353,200,344,215,328,230,302,243"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a28cd1c0b3477571d87133234e6358503" title="Hard resets BNO08x sensor." alt="" coords="396,181,535,208"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="292,237,396,210,397,215,293,242"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a589eb9780f5bf613bbd447ef5b9ade3d" title="Initializes required esp-idf SPI data structures with values from user passed bno08x_config_t struct." alt="" coords="382,236,550,263"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="301,250,366,248,366,254,301,255"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ae0dab25557befcf62bf384fdc241ef10" title="Initializes required gpio." alt="" coords="403,287,529,313"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="301,263,388,281,387,287,300,269"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#aa27026da2c52b4aca49b78863f10ec61" title="Initializes host interrupt ISR." alt="" coords="394,337,538,364"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="302,265,327,276,343,288,352,300,361,312,375,323,387,329,384,334,373,328,357,316,348,304,339,292,325,281,300,270"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a58f43c8bb1e7fe8560ce442d46240e81" title="Initializes SPI." alt="" coords="406,388,525,415"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="302,262,328,277,339,289,346,302,353,327,359,351,365,363,376,374,393,385,390,389,372,378,361,366,354,353,347,328,341,304,335,292,324,281,299,267"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a06f99a6b2182b49a0e61e2107f2be6be" title="Launches spi_task and data_proc_task on constructor call." alt="" coords="388,451,543,477"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="303,261,328,277,343,295,350,314,354,351,356,388,363,406,376,425,398,442,395,446,372,429,358,409,351,389,348,352,345,316,338,298,324,281,300,266"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ab5f200069a2f8cb74cb79c6f162da5a1" title="Queues a packet containing the request product ID command." alt="" coords="621,5,784,48"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="532,120,556,108,570,97,579,84,589,71,604,58,612,53,614,58,607,62,593,75,584,87,574,100,559,113,534,124"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4f12de628073f44b2a3fab2688cf1caf" title="Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse." alt="" coords="625,72,780,99"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="531,119,621,100,622,105,532,125"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a7cdeb849e728487de961cdfd4030c773" title="Waits for a queued packet to be sent or host_int_timeout_ms to elapse." alt="" coords="615,123,790,149"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="555,133,599,133,599,139,555,139"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a62c570ba96512f4d0d10b2594048de1f" title="Queues an SHTP packet to be sent via SPI." alt="" coords="852,13,1011,40"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="784,24,836,24,836,29,784,29"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a2897a178bf2c53cd99df0d4570edf72e" title="Waits for data to be received over SPI, or host_int_timeout_ms to elapse." alt="" coords="615,173,790,200"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="536,190,600,187,600,193,536,195"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a453ec8a70646651d4e5b10bf0b2e4d61" title="Resets all data returned by public getter APIs to initial values of 0 and low accuracy." alt="" coords="623,224,782,267"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="550,245,608,244,608,250,550,251"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8f34d5475474f00ae6a92f73c1fe14e4" title="Initializes required gpio inputs." alt="" coords="618,291,787,317"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="529,298,603,300,603,305,529,304"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ad0b9e8f8d051798bb1da9b19598dbd64" title="Initializes required gpio outputs." alt="" coords="614,341,791,368"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="527,311,627,335,626,340,526,317"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a804b95c58c30d36933fd251626b85bf7" title="HINT interrupt service routine, handles falling edge of BNO08x HINT pin." alt="" coords="628,392,777,419"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="527,362,627,385,626,391,526,367"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a0ae135d7bf7a5f047a1d1aa5cc07e520" title="Static function used to launch data processing task." alt="" coords="619,443,786,485"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="544,461,603,461,603,467,544,467"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a0ce6d9db873555f1ebe7e095251eab74" title="Static function used to launch spi task." alt="" coords="605,532,800,559"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="508,475,648,524,646,529,506,481"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ab4373e9b87837ea9fcbc0b536338c7b8" title="Task responsible parsing packets. Executed when SPI task sends a packet to be parsed,..." alt="" coords="848,440,1015,467"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="787,457,832,455,832,461,787,463"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a1c47d27917ae3b2876efa121b803f924" title="Parses a packet received from bno08x, updating any data according to received reports." alt="" coords="1067,377,1223,404"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="979,437,1081,406,1083,412,980,442"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a05e4cd5861b55fc0182d7dd13bb85e49" title="Prints the passed SHTP packet to serial console with ESP_LOG statement." alt="" coords="1071,440,1220,467"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1016,451,1055,451,1055,456,1016,456"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4f66045a0528a0c17c52421ea51612e7" title="Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)" alt="" coords="1288,161,1462,204"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1150,376,1168,343,1195,300,1230,254,1274,214,1280,209,1283,214,1277,218,1234,257,1199,303,1172,346,1155,378"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a206c0e3ddc3b745b56914976d6e69981" title="Parses get feature request report received from BNO08x." alt="" coords="1297,228,1453,271"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1158,375,1206,329,1239,303,1274,280,1284,275,1287,280,1277,285,1242,308,1210,333,1161,379"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a51b360d795563b55559f11efb40be36a" title="Sends packet to be parsed to meta data function call (FRS_read_data()) through queue." alt="" coords="1293,295,1457,337"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1188,374,1292,340,1294,345,1190,379"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a7be6047fef851a064c7cbc9eba092f6d" title="Parses received gyro integrated rotation vector report sent by BNO08x." alt="" coords="1304,361,1446,420"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1223,388,1288,388,1288,393,1223,393"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8d9db3e1b6208c2661e1c543deefa53d" title="Parses received input report sent by BNO08x." alt="" coords="1302,444,1448,487"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1190,402,1294,436,1292,441,1188,407"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a29cfd7fc2816483ebebe9d55b677a036" title="Parses product id report and prints device info." alt="" coords="1295,511,1455,553"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1189,402,1229,426,1245,445,1253,463,1261,480,1277,497,1283,501,1280,505,1274,501,1257,483,1248,465,1241,448,1226,430,1186,407"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ab02386f13caa446bab5921c1a71f92ab" title="Updates integrated gyro rotation vector data from SHTP channel 5 (CHANNEL_GYRO) special report data." alt="" coords="1551,201,1733,244"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1445,366,1473,347,1489,324,1495,301,1502,277,1521,254,1536,244,1539,248,1524,258,1507,280,1501,303,1494,327,1477,351,1448,371"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a002aa97c9af8f6df2d0c83034e4f7b55" title="Parses data from received input report." alt="" coords="1569,268,1715,311"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1447,447,1473,430,1484,417,1491,404,1496,376,1501,349,1509,334,1521,321,1553,302,1556,306,1524,325,1513,337,1506,350,1501,377,1496,406,1489,420,1476,434,1449,451"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#afe588fbd0055193d3bc08984d7732354" title="Updates accelerometer data from parsed input report." alt="" coords="1523,335,1761,361"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1447,444,1473,430,1488,416,1496,401,1505,386,1521,371,1532,365,1534,370,1524,376,1509,389,1501,403,1492,419,1476,434,1449,449"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a962b695ef4733d558c6f9684da0931ab" title="Updates linear gyro data from parsed input report." alt="" coords="1552,385,1732,428"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1448,447,1536,427,1537,432,1449,452"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#af971d82426740e62c1f05adcd2c9ce7c" title="Updates command data from parsed input report." alt="" coords="1535,452,1749,479"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1448,463,1520,463,1520,468,1448,468"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ad7de3999d4df19038e27c01f9b02010e" title="Updates gravity data from parsed input report." alt="" coords="1545,503,1739,529"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1449,476,1553,497,1552,502,1448,482"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a7416d844f6188c8d16f181d6d4431708" title="Updates linear accelerometer data from parsed input report." alt="" coords="1571,553,1713,596"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1449,484,1476,496,1491,508,1501,518,1510,529,1524,539,1557,553,1555,558,1521,544,1506,533,1497,522,1487,511,1473,501,1447,488"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a3abf4a199bc7a03ac7447c2781673d88" title="Updates magnetic field data from parsed input report." alt="" coords="1550,620,1734,647"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1449,479,1476,497,1489,511,1495,525,1501,554,1506,581,1513,594,1524,606,1537,615,1534,619,1521,610,1508,597,1501,583,1495,555,1490,527,1484,514,1473,501,1447,484"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a04489cf9a125495c7cf07c6ba5e9f6c0" title="Updates activity classifier data from parsed input report." alt="" coords="1555,671,1729,713"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1450,478,1477,497,1492,517,1499,538,1501,579,1503,619,1510,638,1525,657,1543,670,1540,675,1521,661,1505,640,1497,620,1495,579,1494,539,1487,520,1473,501,1447,483"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a2ecd4ed60f82730ae230c61687ec92bf" title="Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x." alt="" coords="868,577,995,604"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="774,557,853,572,852,578,773,562"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8d9f28d8857279a3c4b1f62f6dabb638" title="Receives a SHTP packet via SPI and sends it to data_proc_task()" alt="" coords="1063,577,1227,604"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="995,588,1047,588,1047,593,995,593"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a2c359a44a2c8e83ecb258a340e2d0e1a" title="Sends a queued SHTP packet via SPI." alt="" coords="1069,628,1221,655"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="992,602,1072,621,1071,626,990,607"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a9ee7e73f695af8965a9ede50136d5a8c" title="Receives a SHTP packet body via SPI." alt="" coords="1275,577,1475,604"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1228,588,1260,588,1260,593,1228,593"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#acb246769719351e02bf2aff06d039475" title="Receives a SHTP packet header via SPI." alt="" coords="1293,628,1457,671"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1201,602,1278,622,1277,627,1200,607"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a6ed5310154fb7e7f290e619e6fbed708" name="a6ed5310154fb7e7f290e619e6fbed708"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a6ed5310154fb7e7f290e619e6fbed708">◆ </a></span>TEST_CASE() <span class="overload">[3/7]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">TEST_CASE </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">"Init Config Args"</td> <td class="paramname"><span class="paramname">, </span></td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
|
||||||
<td class="paramkey"></td>
|
|
||||||
<td></td>
|
|
||||||
<td class="paramtype">""</td> <td class="paramname"><span class="paramname">[InitComprehensive]</span> )</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph.png" border="0" usemap="#a_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph" alt=""/></div>
|
|
||||||
<map name="a_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph" id="a_init_deinit_tests_8cpp_a6ed5310154fb7e7f290e619e6fbed708_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,213,102,240"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a71d9fd7d459a98a7e9089a8587a21f8d" title="Used to call private BNO08x::init_config_args() member for tests." alt="" coords="158,5,318,48"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="57,212,68,181,87,140,113,96,148,58,152,55,155,59,152,62,118,99,92,142,73,183,62,214"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a6bd040c7d670a9713f2ab8a8a3913518" title="Calls BNO08x constructor and creates new test IMU on heap." alt="" coords="150,72,326,115"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="63,211,97,169,121,145,148,124,156,120,158,124,151,129,125,149,101,173,67,215"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="159,139,317,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="92,210,162,185,163,190,94,215"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919" title="Prints end begin banner." alt="" coords="155,205,321,248"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="102,224,139,224,139,229,102,229"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="155,272,321,315"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="94,238,163,264,162,269,92,243"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885" title="Prints test begin banner." alt="" coords="155,339,321,381"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="67,239,101,281,125,304,151,324,158,329,156,333,148,329,121,308,97,284,63,242"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="156,405,320,432"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="61,239,72,271,90,312,117,355,151,391,157,396,154,400,148,395,112,358,86,314,67,273,56,241"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a589eb9780f5bf613bbd447ef5b9ade3d" title="Initializes required esp-idf SPI data structures with values from user passed bno08x_config_t struct." alt="" coords="382,13,550,40"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="319,24,366,24,366,29,319,29"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a453ec8a70646651d4e5b10bf0b2e4d61" title="Resets all data returned by public getter APIs to initial values of 0 and low accuracy." alt="" coords="605,5,765,48"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="550,24,590,24,590,29,550,29"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="374,72,557,115"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="326,91,358,91,358,96,326,96"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a96d79e5c8f3096a207d806be926af15b" name="a96d79e5c8f3096a207d806be926af15b"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a96d79e5c8f3096a207d806be926af15b">◆ </a></span>TEST_CASE() <span class="overload">[4/7]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">TEST_CASE </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">"Init GPIO"</td> <td class="paramname"><span class="paramname">, </span></td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
|
||||||
<td class="paramkey"></td>
|
|
||||||
<td></td>
|
|
||||||
<td class="paramtype">""</td> <td class="paramname"><span class="paramname">[InitComprehensive]</span> )</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph.png" border="0" usemap="#a_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph" alt=""/></div>
|
|
||||||
<map name="a_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph" id="a_init_deinit_tests_8cpp_a96d79e5c8f3096a207d806be926af15b_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,164,102,191"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a504749533ccd91890d73440809d38161" title="Used to call private BNO08x::init_gpio() member for tests." alt="" coords="152,23,313,65"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="63,162,98,120,122,96,148,75,155,71,158,75,151,80,125,100,102,124,67,165"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="153,89,312,132"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="91,161,158,135,160,140,93,166"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919" title="Prints end begin banner." alt="" coords="150,156,315,199"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="102,175,134,175,134,180,102,180"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885" title="Prints test begin banner." alt="" coords="150,223,315,265"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="93,189,160,214,158,219,91,194"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="151,289,314,316"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="66,189,101,232,124,255,151,275,161,280,158,285,148,280,121,259,97,235,62,193"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ae0dab25557befcf62bf384fdc241ef10" title="Initializes required gpio." alt="" coords="363,31,489,57"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="313,41,348,41,348,47,313,47"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8f34d5475474f00ae6a92f73c1fe14e4" title="Initializes required gpio inputs." alt="" coords="541,5,710,32"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="489,33,525,29,526,34,490,39"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ad0b9e8f8d051798bb1da9b19598dbd64" title="Initializes required gpio outputs." alt="" coords="537,56,714,83"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="490,49,522,54,522,59,489,55"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="ab8015ecd4179bc39223921d6eef1165a" name="ab8015ecd4179bc39223921d6eef1165a"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#ab8015ecd4179bc39223921d6eef1165a">◆ </a></span>TEST_CASE() <span class="overload">[5/7]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">TEST_CASE </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">"Init HINT ISR"</td> <td class="paramname"><span class="paramname">, </span></td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
|
||||||
<td class="paramkey"></td>
|
|
||||||
<td></td>
|
|
||||||
<td class="paramtype">""</td> <td class="paramname"><span class="paramname">[InitComprehensive]</span> )</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph.png" border="0" usemap="#a_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph" alt=""/></div>
|
|
||||||
<map name="a_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph" id="a_init_deinit_tests_8cpp_ab8015ecd4179bc39223921d6eef1165a_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,147,102,173"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a836c928981ac85d34668c9b97af17a15" title="Used to call private BNO08x::init_hint_isr() member for tests." alt="" coords="152,5,313,48"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="63,145,98,103,122,79,148,58,155,54,158,58,151,62,125,83,102,106,67,148"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="153,72,312,115"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="91,144,158,118,160,123,93,149"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919" title="Prints end begin banner." alt="" coords="150,139,315,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="102,157,134,157,134,163,102,163"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885" title="Prints test begin banner." alt="" coords="150,205,315,248"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="93,171,160,197,158,202,91,176"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="151,272,314,299"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="66,172,101,214,124,238,151,258,161,263,158,268,148,262,121,242,97,218,62,175"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#aa27026da2c52b4aca49b78863f10ec61" title="Initializes host interrupt ISR." alt="" coords="363,13,507,40"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="313,24,347,24,347,29,313,29"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a804b95c58c30d36933fd251626b85bf7" title="HINT interrupt service routine, handles falling edge of BNO08x HINT pin." alt="" coords="555,13,704,40"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="508,24,540,24,540,29,508,29"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="ad71fea7e4a2e587d48d2bf7fadd711cc" name="ad71fea7e4a2e587d48d2bf7fadd711cc"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#ad71fea7e4a2e587d48d2bf7fadd711cc">◆ </a></span>TEST_CASE() <span class="overload">[6/7]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">TEST_CASE </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">"Init SPI"</td> <td class="paramname"><span class="paramname">, </span></td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
|
||||||
<td class="paramkey"></td>
|
|
||||||
<td></td>
|
|
||||||
<td class="paramtype">""</td> <td class="paramname"><span class="paramname">[InitComprehensive]</span> )</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph.png" border="0" usemap="#a_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph" alt=""/></div>
|
|
||||||
<map name="a_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph" id="a_init_deinit_tests_8cpp_ad71fea7e4a2e587d48d2bf7fadd711cc_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,147,102,173"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a7d2d784da1e850dab41154b35d7cdab5" title="Used to call private BNO08x::init_spi() member for tests." alt="" coords="152,5,313,48"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="63,145,98,103,122,79,148,58,155,54,158,58,151,62,125,83,102,106,67,148"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="153,72,312,115"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="91,144,158,118,160,123,93,149"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919" title="Prints end begin banner." alt="" coords="150,139,315,181"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="102,157,134,157,134,163,102,163"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885" title="Prints test begin banner." alt="" coords="150,205,315,248"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="93,171,160,197,158,202,91,176"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="151,272,314,299"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="66,172,101,214,124,238,151,258,161,263,158,268,148,262,121,242,97,218,62,175"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a58f43c8bb1e7fe8560ce442d46240e81" title="Initializes SPI." alt="" coords="363,13,482,40"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="313,24,347,24,347,29,313,29"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
<a id="a9f7d58c894a252a5d5f4926f43c1da05" name="a9f7d58c894a252a5d5f4926f43c1da05"></a>
|
|
||||||
<h2 class="memtitle"><span class="permalink"><a href="#a9f7d58c894a252a5d5f4926f43c1da05">◆ </a></span>TEST_CASE() <span class="overload">[7/7]</span></h2>
|
|
||||||
|
|
||||||
<div class="memitem">
|
|
||||||
<div class="memproto">
|
|
||||||
<table class="memname">
|
|
||||||
<tr>
|
|
||||||
<td class="memname">TEST_CASE </td>
|
|
||||||
<td>(</td>
|
|
||||||
<td class="paramtype">"InitComprehensive Tasks"</td> <td class="paramname"><span class="paramname">, </span></td>
|
|
||||||
</tr>
|
|
||||||
<tr>
|
|
||||||
<td class="paramkey"></td>
|
|
||||||
<td></td>
|
|
||||||
<td class="paramtype">""</td> <td class="paramname"><span class="paramname">[InitComprehensive]</span> )</td>
|
|
||||||
</tr>
|
|
||||||
</table>
|
|
||||||
</div><div class="memdoc">
|
|
||||||
<div class="dynheader">
|
|
||||||
Here is the call graph for this function:</div>
|
|
||||||
<div class="dyncontent">
|
|
||||||
<div class="center"><img src="_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph.png" border="0" usemap="#a_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph" alt=""/></div>
|
|
||||||
<map name="a_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph" id="a_init_deinit_tests_8cpp_a9f7d58c894a252a5d5f4926f43c1da05_cgraph">
|
|
||||||
<area shape="rect" title=" " alt="" coords="5,667,102,693"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#adf2488d1f7e3dec21a0d0c99417c181a" title="Used to call private BNO08x::launch_tasks() member for tests." alt="" coords="152,525,313,568"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="63,665,98,623,122,599,148,578,155,574,158,578,151,582,125,603,102,626,67,668"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="153,592,312,635"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="91,664,158,638,160,643,93,669"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919" title="Prints end begin banner." alt="" coords="150,659,315,701"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="102,677,134,677,134,683,102,683"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885" title="Prints test begin banner." alt="" coords="150,725,315,768"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="93,691,160,717,158,722,91,696"/>
|
|
||||||
<area shape="rect" href="_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="151,792,314,819"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="66,692,101,734,124,758,151,778,161,783,158,788,148,782,121,762,97,738,62,695"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a06f99a6b2182b49a0e61e2107f2be6be" title="Launches spi_task and data_proc_task on constructor call." alt="" coords="363,533,518,560"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="313,544,347,544,347,549,313,549"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a0ae135d7bf7a5f047a1d1aa5cc07e520" title="Static function used to launch data processing task." alt="" coords="580,473,747,516"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="500,530,564,515,565,520,502,535"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a0ce6d9db873555f1ebe7e095251eab74" title="Static function used to launch spi task." alt="" coords="566,563,761,589"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="519,554,551,559,550,564,518,559"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ab4373e9b87837ea9fcbc0b536338c7b8" title="Task responsible parsing packets. Executed when SPI task sends a packet to be parsed,..." alt="" coords="809,471,976,497"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="748,488,793,486,793,491,748,493"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a1c47d27917ae3b2876efa121b803f924" title="Parses a packet received from bno08x, updating any data according to received reports." alt="" coords="1028,408,1184,435"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="940,468,1042,437,1044,442,941,473"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a05e4cd5861b55fc0182d7dd13bb85e49" title="Prints the passed SHTP packet to serial console with ESP_LOG statement." alt="" coords="1032,471,1181,497"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="977,481,1016,481,1016,487,977,487"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a4f66045a0528a0c17c52421ea51612e7" title="Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)" alt="" coords="1249,192,1423,235"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1111,407,1129,374,1156,330,1191,284,1235,245,1241,240,1244,245,1238,249,1195,288,1160,333,1133,377,1116,409"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a206c0e3ddc3b745b56914976d6e69981" title="Parses get feature request report received from BNO08x." alt="" coords="1258,259,1414,301"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1119,406,1167,360,1200,334,1235,311,1245,306,1248,310,1238,316,1203,338,1171,364,1122,409"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a51b360d795563b55559f11efb40be36a" title="Sends packet to be parsed to meta data function call (FRS_read_data()) through queue." alt="" coords="1254,325,1418,368"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1149,405,1253,371,1255,376,1151,410"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a7be6047fef851a064c7cbc9eba092f6d" title="Parses received gyro integrated rotation vector report sent by BNO08x." alt="" coords="1265,392,1407,451"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1184,419,1249,419,1249,424,1184,424"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8d9db3e1b6208c2661e1c543deefa53d" title="Parses received input report sent by BNO08x." alt="" coords="1263,475,1409,517"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1151,433,1255,467,1253,472,1149,438"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a29cfd7fc2816483ebebe9d55b677a036" title="Parses product id report and prints device info." alt="" coords="1256,541,1416,584"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1150,433,1190,457,1206,475,1214,493,1222,511,1238,527,1244,532,1241,536,1235,531,1218,514,1209,496,1202,478,1187,461,1147,438"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ab02386f13caa446bab5921c1a71f92ab" title="Updates integrated gyro rotation vector data from SHTP channel 5 (CHANNEL_GYRO) special report data." alt="" coords="1512,5,1694,48"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1406,400,1421,391,1434,378,1447,358,1457,337,1464,297,1462,258,1455,218,1447,179,1446,139,1455,99,1466,79,1482,58,1497,45,1500,49,1486,62,1471,82,1460,101,1451,140,1453,178,1460,217,1467,257,1470,297,1462,339,1452,360,1438,382,1425,395,1409,405"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a002aa97c9af8f6df2d0c83034e4f7b55" title="Parses data from received input report." alt="" coords="1530,72,1676,115"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1408,480,1422,472,1434,461,1449,440,1459,419,1467,377,1464,336,1456,294,1448,253,1445,211,1455,168,1466,146,1482,125,1497,112,1514,103,1517,107,1500,116,1486,128,1470,149,1460,170,1450,211,1453,252,1461,293,1470,335,1473,377,1464,420,1453,442,1438,464,1425,476,1410,485"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#afe588fbd0055193d3bc08984d7732354" title="Updates accelerometer data from parsed input report." alt="" coords="1484,139,1722,165"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1408,480,1434,461,1456,425,1463,390,1461,354,1455,319,1449,283,1448,247,1457,211,1482,176,1484,173,1488,177,1486,179,1462,213,1453,248,1454,282,1460,318,1467,354,1468,390,1460,427,1438,464,1411,484"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a962b695ef4733d558c6f9684da0931ab" title="Updates linear gyro data from parsed input report." alt="" coords="1513,189,1693,232"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1408,479,1434,461,1452,434,1459,407,1459,380,1456,353,1453,326,1454,298,1462,270,1482,242,1498,229,1501,233,1486,246,1467,272,1459,299,1459,325,1462,352,1465,380,1464,408,1456,436,1438,465,1411,484"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#af971d82426740e62c1f05adcd2c9ce7c" title="Updates command data from parsed input report." alt="" coords="1496,256,1710,283"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1407,479,1434,461,1448,440,1455,420,1456,377,1457,335,1465,313,1482,293,1486,289,1489,293,1486,297,1470,316,1462,336,1461,378,1460,421,1453,443,1438,465,1410,483"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ad7de3999d4df19038e27c01f9b02010e" title="Updates gravity data from parsed input report." alt="" coords="1506,307,1700,333"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1408,478,1434,461,1445,447,1452,432,1456,403,1461,373,1469,358,1482,343,1491,337,1494,341,1485,347,1473,361,1466,374,1461,404,1457,434,1450,449,1437,465,1411,482"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a7416d844f6188c8d16f181d6d4431708" title="Updates linear accelerometer data from parsed input report." alt="" coords="1532,357,1674,400"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1408,474,1434,460,1448,448,1457,436,1467,423,1482,410,1515,394,1518,399,1485,414,1471,426,1462,439,1452,452,1437,465,1410,479"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a3abf4a199bc7a03ac7447c2781673d88" title="Updates magnetic field data from parsed input report." alt="" coords="1511,424,1695,451"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1409,477,1483,460,1521,452,1522,457,1484,465,1410,482"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a04489cf9a125495c7cf07c6ba5e9f6c0" title="Updates activity classifier data from parsed input report." alt="" coords="1516,475,1690,517"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1409,493,1500,493,1500,499,1409,499"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a83fed63c67957ec4338afd43087d6e22" title="Updates raw accelerometer data from parsed input report." alt="" coords="1531,541,1675,584"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1410,512,1516,538,1515,544,1409,517"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ad0f0fec4e53029b4ba907414a36ac5ea" title="Updates raw gyro data from parsed input report." alt="" coords="1531,608,1675,651"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1411,512,1437,527,1454,544,1462,562,1470,578,1485,594,1517,610,1514,615,1482,598,1466,581,1457,564,1449,547,1434,531,1408,517"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a6ddc9600c53a4248d1affcab36f6f245" title="Updates raw magnetic field data from parsed input report." alt="" coords="1531,675,1675,717"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1410,509,1437,527,1451,545,1458,562,1462,596,1466,629,1472,645,1485,661,1518,680,1515,685,1482,665,1468,648,1460,631,1457,597,1453,563,1446,547,1434,531,1407,514"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#aa309152750686fbf8ebf7d6de1f1254b" title="Updates roation vector data from parsed input report." alt="" coords="1519,741,1687,784"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1411,508,1438,527,1455,553,1463,579,1464,605,1462,630,1460,655,1461,679,1468,703,1486,727,1506,743,1503,747,1482,731,1464,706,1455,680,1454,655,1456,630,1459,605,1458,580,1450,556,1434,531,1408,513"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a358316b883928c50dd381f024e6b0645" title="Updates stability classifier data from parsed input report." alt="" coords="1518,808,1688,851"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1411,508,1438,528,1459,562,1468,597,1467,631,1461,664,1456,697,1456,729,1464,762,1486,794,1506,810,1503,814,1482,798,1459,764,1450,730,1451,696,1456,663,1461,630,1462,597,1455,564,1434,531,1408,512"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#aa390bf840246e3233e07f6a424efcb6f" title="Updates step counter data from parsed input report." alt="" coords="1528,875,1678,917"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1410,507,1425,516,1438,528,1453,549,1464,571,1472,614,1470,656,1461,697,1453,738,1451,779,1460,820,1470,840,1486,861,1499,873,1515,881,1513,886,1496,877,1482,864,1466,843,1455,822,1445,779,1448,738,1456,696,1464,655,1467,614,1459,573,1449,552,1434,531,1422,520,1408,512"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#ac75b7fb1a1b407d0888ea07d708831b1" title="Updates tap detector data from parsed input report." alt="" coords="1532,941,1674,984"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1410,507,1425,516,1438,528,1456,554,1468,580,1475,606,1477,631,1472,682,1461,731,1450,780,1446,829,1448,853,1455,878,1467,903,1486,928,1501,941,1519,950,1516,955,1498,945,1482,931,1463,905,1450,880,1443,854,1440,829,1444,779,1456,730,1467,681,1472,631,1469,607,1463,582,1451,557,1434,531,1422,520,1408,512"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8de12c9c47549502147bd85dbb7e364e" title="Updates uncalibrated gyro data from parsed input report." alt="" coords="1506,1008,1700,1051"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1411,507,1425,516,1438,528,1458,558,1472,589,1480,619,1482,649,1475,707,1461,765,1446,822,1441,879,1443,907,1451,936,1465,965,1486,994,1495,1003,1491,1007,1482,998,1460,968,1446,938,1438,908,1435,879,1441,821,1456,763,1470,706,1476,649,1474,620,1467,591,1454,561,1434,531,1422,520,1408,512"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a2ecd4ed60f82730ae230c61687ec92bf" title="Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x." alt="" coords="829,608,956,635"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="735,587,814,603,813,608,734,593"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a8d9f28d8857279a3c4b1f62f6dabb638" title="Receives a SHTP packet via SPI and sends it to data_proc_task()" alt="" coords="1024,608,1188,635"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="956,619,1008,619,1008,624,956,624"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a2c359a44a2c8e83ecb258a340e2d0e1a" title="Sends a queued SHTP packet via SPI." alt="" coords="1030,659,1182,685"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="953,633,1033,652,1032,657,951,638"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#a9ee7e73f695af8965a9ede50136d5a8c" title="Receives a SHTP packet body via SPI." alt="" coords="1236,608,1436,635"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1189,619,1221,619,1221,624,1189,624"/>
|
|
||||||
<area shape="rect" href="class_b_n_o08x.html#acb246769719351e02bf2aff06d039475" title="Receives a SHTP packet header via SPI." alt="" coords="1254,659,1418,701"/>
|
|
||||||
<area shape="poly" title=" " alt="" coords="1162,633,1239,653,1238,658,1161,638"/>
|
|
||||||
</map>
|
|
||||||
</div>
|
|
||||||
|
|
||||||
</div>
|
|
||||||
</div>
|
|
||||||
</div><!-- contents -->
|
|
||||||
</div><!-- doc-content -->
|
|
||||||
<!-- start footer part -->
|
|
||||||
<div id="nav-path" class="navpath"><!-- id is needed for treeview function! -->
|
|
||||||
<ul>
|
|
||||||
<li class="navelem"><a class="el" href="dir_85e9385bd83516731053aadc7da3c8af.html">imu_update</a></li><li class="navelem"><a class="el" href="dir_c60d9bf80716f90f729fd65c40ec81f7.html">bno08x_update</a></li><li class="navelem"><a class="el" href="dir_fd670e5d11b8bb731501003ff6578ae1.html">components</a></li><li class="navelem"><a class="el" href="dir_a6718ce9703adf4789a693642ffedf7f.html">esp32_BNO08x</a></li><li class="navelem"><a class="el" href="dir_14dea6b744ab39100edf1f9916c217e0.html">test</a></li><li class="navelem"><a class="el" href="_init_deinit_tests_8cpp.html">InitDeinitTests.cpp</a></li>
|
|
||||||
<li class="footer">Generated by <a href="https://www.doxygen.org/index.html"><img class="footer" src="doxygen.svg" width="104" height="31" alt="doxygen"/></a> 1.10.0 </li>
|
|
||||||
</ul>
|
|
||||||
</div>
|
|
||||||
</body>
|
|
||||||
</html>
|
|
||||||
|
|
@ -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 ]
|
|
||||||
];
|
|
||||||
|
|
@ -1,48 +0,0 @@
|
||||||
<map id="InitDeinitTests.cpp" name="InitDeinitTests.cpp">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="367,5,496,32"/>
|
|
||||||
<area shape="rect" id="Node000002" title=" " alt="" coords="321,80,382,107"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="419,35,378,72,375,68,416,31"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$_b_n_o08x_test_helper_8hpp.html" title=" " alt="" coords="406,80,620,107"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="447,31,489,68,486,72,444,35"/>
|
|
||||||
<area shape="rect" id="Node000004" title=" " alt="" coords="5,229,66,256"/>
|
|
||||||
<area shape="poly" id="edge3_Node000003_Node000004" title=" " alt="" coords="473,110,81,230,79,225,471,105"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$_b_n_o08x_8hpp.html" title=" " alt="" coords="652,155,747,181"/>
|
|
||||||
<area shape="poly" id="edge4_Node000003_Node000005" title=" " alt="" coords="546,105,654,146,652,151,544,110"/>
|
|
||||||
<area shape="poly" id="edge7_Node000005_Node000004" title=" " alt="" coords="652,174,410,189,249,207,81,232,80,227,248,201,410,184,651,168"/>
|
|
||||||
<area shape="rect" id="Node000006" title=" " alt="" coords="90,229,168,256"/>
|
|
||||||
<area shape="poly" id="edge5_Node000005_Node000006" title=" " alt="" coords="651,176,451,195,320,211,184,231,183,226,319,206,451,189,651,170"/>
|
|
||||||
<area shape="rect" id="Node000007" title=" " alt="" coords="192,229,253,256"/>
|
|
||||||
<area shape="poly" id="edge6_Node000005_Node000007" title=" " alt="" coords="652,176,486,196,379,211,268,232,267,226,378,206,485,190,651,171"/>
|
|
||||||
<area shape="rect" id="Node000008" title=" " alt="" coords="277,229,338,256"/>
|
|
||||||
<area shape="poly" id="edge8_Node000005_Node000008" title=" " alt="" coords="652,178,521,199,354,231,352,226,520,193,651,173"/>
|
|
||||||
<area shape="rect" id="Node000009" title=" " alt="" coords="361,229,438,256"/>
|
|
||||||
<area shape="poly" id="edge9_Node000005_Node000009" title=" " alt="" coords="652,183,454,231,452,226,651,178"/>
|
|
||||||
<area shape="rect" id="Node000010" title=" " alt="" coords="461,229,517,256"/>
|
|
||||||
<area shape="poly" id="edge10_Node000005_Node000010" title=" " alt="" coords="664,184,532,229,530,224,662,179"/>
|
|
||||||
<area shape="rect" id="Node000011" title=" " alt="" coords="541,229,618,256"/>
|
|
||||||
<area shape="poly" id="edge11_Node000005_Node000011" title=" " alt="" coords="680,184,615,223,612,219,677,180"/>
|
|
||||||
<area shape="rect" id="Node000012" title=" " alt="" coords="643,229,756,256"/>
|
|
||||||
<area shape="poly" id="edge12_Node000005_Node000012" title=" " alt="" coords="702,182,702,214,697,214,697,182"/>
|
|
||||||
<area shape="rect" id="Node000013" title=" " alt="" coords="780,229,870,256"/>
|
|
||||||
<area shape="poly" id="edge13_Node000005_Node000013" title=" " alt="" coords="723,180,791,219,789,224,720,184"/>
|
|
||||||
<area shape="rect" id="Node000014" title=" " alt="" coords="893,229,1034,256"/>
|
|
||||||
<area shape="poly" id="edge14_Node000005_Node000014" title=" " alt="" coords="746,179,904,222,902,227,745,184"/>
|
|
||||||
<area shape="rect" id="Node000015" title=" " alt="" coords="1058,229,1162,256"/>
|
|
||||||
<area shape="poly" id="edge15_Node000005_Node000015" title=" " alt="" coords="748,175,1043,226,1042,231,747,180"/>
|
|
||||||
<area shape="rect" id="Node000016" title=" " alt="" coords="1186,229,1341,256"/>
|
|
||||||
<area shape="poly" id="edge16_Node000005_Node000016" title=" " alt="" coords="748,173,1171,226,1170,232,747,178"/>
|
|
||||||
<area shape="rect" id="Node000017" title=" " alt="" coords="1365,229,1479,256"/>
|
|
||||||
<area shape="poly" id="edge17_Node000005_Node000017" title=" " alt="" coords="748,170,1001,189,1172,206,1350,226,1349,232,1172,211,1000,195,747,175"/>
|
|
||||||
<area shape="rect" id="Node000018" title=" " alt="" coords="1504,229,1626,256"/>
|
|
||||||
<area shape="poly" id="edge18_Node000005_Node000018" title=" " alt="" coords="748,169,1055,187,1268,204,1488,226,1488,232,1267,209,1055,192,747,174"/>
|
|
||||||
<area shape="rect" id="Node000019" title=" " alt="" coords="1650,229,1754,256"/>
|
|
||||||
<area shape="poly" id="edge19_Node000005_Node000019" title=" " alt="" coords="748,168,1112,182,1369,200,1635,226,1634,232,1368,205,1112,188,747,173"/>
|
|
||||||
<area shape="rect" id="Node000020" href="$_b_n_o08x__global__types_8hpp.html" title=" " alt="" coords="1779,229,1954,256"/>
|
|
||||||
<area shape="poly" id="edge20_Node000005_Node000020" title=" " alt="" coords="748,168,1161,186,1456,203,1763,226,1763,232,1456,209,1160,192,747,174"/>
|
|
||||||
<area shape="rect" id="Node000021" title=" " alt="" coords="1681,304,1771,331"/>
|
|
||||||
<area shape="poly" id="edge21_Node000020_Node000021" title=" " alt="" coords="1843,259,1766,299,1763,294,1841,254"/>
|
|
||||||
<area shape="rect" id="Node000022" title=" " alt="" coords="1796,304,1936,331"/>
|
|
||||||
<area shape="poly" id="edge22_Node000020_Node000022" title=" " alt="" coords="1869,257,1869,288,1864,288,1864,257"/>
|
|
||||||
<area shape="rect" id="Node000023" title=" " alt="" coords="1961,304,2091,331"/>
|
|
||||||
<area shape="poly" id="edge23_Node000020_Node000023" title=" " alt="" coords="1895,254,1986,295,1983,300,1893,259"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
16d2f71c23d2ba4bf9ce8a27e1d3f2a0
|
|
||||||
|
Before Width: | Height: | Size: 50 KiB |
|
|
@ -1,29 +0,0 @@
|
||||||
<map id="TEST_CASE" name="TEST_CASE">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="5,219,102,245"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="150,5,333,48"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="56,217,67,185,86,143,113,98,148,58,152,55,155,59,152,62,117,101,91,145,72,187,61,219"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$class_b_n_o08x.html#a96d47dd0f9aedfbe3f731f8ae76b2e85" title="Requests product ID, prints the returned info over serial, and returns the reason for the most resent..." alt="" coords="152,72,331,99"/>
|
|
||||||
<area shape="poly" id="edge2_Node000001_Node000003" title=" " alt="" coords="60,217,93,164,118,134,148,108,157,103,160,108,151,113,122,138,97,167,64,219"/>
|
|
||||||
<area shape="rect" id="Node000008" href="$class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="162,123,321,165"/>
|
|
||||||
<area shape="poly" id="edge7_Node000001_Node000008" title=" " alt="" coords="75,216,148,175,161,169,163,174,151,180,78,220"/>
|
|
||||||
<area shape="rect" id="Node000009" href="$class_b_n_o08x.html#a28cd1c0b3477571d87133234e6358503" title="Hard resets BNO08x sensor." alt="" coords="172,189,311,216"/>
|
|
||||||
<area shape="poly" id="edge8_Node000001_Node000009" title=" " alt="" coords="102,222,156,213,157,219,102,227"/>
|
|
||||||
<area shape="rect" id="Node000011" href="$class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919" title="Prints end begin banner." alt="" coords="159,240,324,283"/>
|
|
||||||
<area shape="poly" id="edge10_Node000001_Node000011" title=" " alt="" coords="102,237,144,243,143,249,102,242"/>
|
|
||||||
<area shape="rect" id="Node000012" href="$class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="159,307,324,349"/>
|
|
||||||
<area shape="poly" id="edge11_Node000001_Node000012" title=" " alt="" coords="74,244,109,268,151,292,162,298,160,303,148,297,106,272,71,248"/>
|
|
||||||
<area shape="rect" id="Node000013" href="$class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885" title="Prints test begin banner." alt="" coords="159,373,324,416"/>
|
|
||||||
<area shape="poly" id="edge12_Node000001_Node000013" title=" " alt="" coords="64,244,97,300,122,332,151,359,157,363,154,367,148,363,118,335,92,303,59,247"/>
|
|
||||||
<area shape="rect" id="Node000014" href="$_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="160,440,323,467"/>
|
|
||||||
<area shape="poly" id="edge13_Node000001_Node000014" title=" " alt="" coords="60,245,69,282,86,331,113,382,131,406,151,426,157,430,153,434,148,430,127,409,109,385,82,333,64,283,55,246"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$class_b_n_o08x.html#ab5f200069a2f8cb74cb79c6f162da5a1" title="Queues a packet containing the request product ID command." alt="" coords="387,5,550,48"/>
|
|
||||||
<area shape="poly" id="edge3_Node000003_Node000004" title=" " alt="" coords="295,69,371,49,372,54,297,74"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$class_b_n_o08x.html#a4f12de628073f44b2a3fab2688cf1caf" title="Waits for a valid or invalid packet to be received or host_int_timeout_ms to elapse." alt="" coords="392,72,546,99"/>
|
|
||||||
<area shape="poly" id="edge5_Node000003_Node000006" title=" " alt="" coords="331,83,376,83,376,88,331,88"/>
|
|
||||||
<area shape="rect" id="Node000007" href="$class_b_n_o08x.html#a7cdeb849e728487de961cdfd4030c773" title="Waits for a queued packet to be sent or host_int_timeout_ms to elapse." alt="" coords="381,123,556,149"/>
|
|
||||||
<area shape="poly" id="edge6_Node000003_Node000007" title=" " alt="" coords="305,97,391,116,390,121,304,102"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$class_b_n_o08x.html#a62c570ba96512f4d0d10b2594048de1f" title="Queues an SHTP packet to be sent via SPI." alt="" coords="604,13,764,40"/>
|
|
||||||
<area shape="poly" id="edge4_Node000004_Node000005" title=" " alt="" coords="550,24,589,24,589,29,550,29"/>
|
|
||||||
<area shape="rect" id="Node000010" href="$class_b_n_o08x.html#a2897a178bf2c53cd99df0d4570edf72e" title="Waits for data to be received over SPI, or host_int_timeout_ms to elapse." alt="" coords="381,189,556,216"/>
|
|
||||||
<area shape="poly" id="edge9_Node000009_Node000010" title=" " alt="" coords="311,200,365,200,365,205,311,205"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
64d3863693f55fb40e5c863d899c319c
|
|
||||||
|
Before Width: | Height: | Size: 26 KiB |
|
|
@ -1,23 +0,0 @@
|
||||||
<map id="TEST_CASE" name="TEST_CASE">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="5,213,102,240"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$class_b_n_o08x_test_helper.html#a71d9fd7d459a98a7e9089a8587a21f8d" title="Used to call private BNO08x::init_config_args() member for tests." alt="" coords="158,5,318,48"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="57,212,68,181,87,140,113,96,148,58,152,55,155,59,152,62,118,99,92,142,73,183,62,214"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$class_b_n_o08x_test_helper.html#a6bd040c7d670a9713f2ab8a8a3913518" title="Calls BNO08x constructor and creates new test IMU on heap." alt="" coords="150,72,326,115"/>
|
|
||||||
<area shape="poly" id="edge4_Node000001_Node000005" title=" " alt="" coords="63,211,97,169,121,145,148,124,156,120,158,124,151,129,125,149,101,173,67,215"/>
|
|
||||||
<area shape="rect" id="Node000007" href="$class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="159,139,317,181"/>
|
|
||||||
<area shape="poly" id="edge6_Node000001_Node000007" title=" " alt="" coords="92,210,162,185,163,190,94,215"/>
|
|
||||||
<area shape="rect" id="Node000008" href="$class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919" title="Prints end begin banner." alt="" coords="155,205,321,248"/>
|
|
||||||
<area shape="poly" id="edge7_Node000001_Node000008" title=" " alt="" coords="102,224,139,224,139,229,102,229"/>
|
|
||||||
<area shape="rect" id="Node000009" href="$class_b_n_o08x_test_helper.html#a7fbfc48c0fff306ab81e2320bc171002" title="Prints a message during a test." alt="" coords="155,272,321,315"/>
|
|
||||||
<area shape="poly" id="edge8_Node000001_Node000009" title=" " alt="" coords="94,238,163,264,162,269,92,243"/>
|
|
||||||
<area shape="rect" id="Node000010" href="$class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885" title="Prints test begin banner." alt="" coords="155,339,321,381"/>
|
|
||||||
<area shape="poly" id="edge9_Node000001_Node000010" title=" " alt="" coords="67,239,101,281,125,304,151,324,158,329,156,333,148,329,121,308,97,284,63,242"/>
|
|
||||||
<area shape="rect" id="Node000011" href="$_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="156,405,320,432"/>
|
|
||||||
<area shape="poly" id="edge10_Node000001_Node000011" title=" " alt="" coords="61,239,72,271,90,312,117,355,151,391,157,396,154,400,148,395,112,358,86,314,67,273,56,241"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$class_b_n_o08x.html#a589eb9780f5bf613bbd447ef5b9ade3d" title="Initializes required esp-idf SPI data structures with values from user passed bno08x_config_t struct." alt="" coords="382,13,550,40"/>
|
|
||||||
<area shape="poly" id="edge2_Node000002_Node000003" title=" " alt="" coords="319,24,366,24,366,29,319,29"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$class_b_n_o08x.html#a453ec8a70646651d4e5b10bf0b2e4d61" title="Resets all data returned by public getter APIs to initial values of 0 and low accuracy." alt="" coords="605,5,765,48"/>
|
|
||||||
<area shape="poly" id="edge3_Node000003_Node000004" title=" " alt="" coords="550,24,590,24,590,29,550,29"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$class_b_n_o08x_test_helper.html#ae2d6df7dcfdbd106c2247803461bbc40" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="374,72,557,115"/>
|
|
||||||
<area shape="poly" id="edge5_Node000005_Node000006" title=" " alt="" coords="326,91,358,91,358,96,326,96"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
39b96ab0a1e474640b1b44c7d7f7b204
|
|
||||||
|
Before Width: | Height: | Size: 21 KiB |
|
|
@ -1,19 +0,0 @@
|
||||||
<map id="TEST_CASE" name="TEST_CASE">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="5,164,102,191"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$class_b_n_o08x_test_helper.html#a504749533ccd91890d73440809d38161" title="Used to call private BNO08x::init_gpio() member for tests." alt="" coords="152,23,313,65"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="63,162,98,120,122,96,148,75,155,71,158,75,151,80,125,100,102,124,67,165"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="153,89,312,132"/>
|
|
||||||
<area shape="poly" id="edge5_Node000001_Node000006" title=" " alt="" coords="91,161,158,135,160,140,93,166"/>
|
|
||||||
<area shape="rect" id="Node000007" href="$class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919" title="Prints end begin banner." alt="" coords="150,156,315,199"/>
|
|
||||||
<area shape="poly" id="edge6_Node000001_Node000007" title=" " alt="" coords="102,175,134,175,134,180,102,180"/>
|
|
||||||
<area shape="rect" id="Node000008" href="$class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885" title="Prints test begin banner." alt="" coords="150,223,315,265"/>
|
|
||||||
<area shape="poly" id="edge7_Node000001_Node000008" title=" " alt="" coords="93,189,160,214,158,219,91,194"/>
|
|
||||||
<area shape="rect" id="Node000009" href="$_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="151,289,314,316"/>
|
|
||||||
<area shape="poly" id="edge8_Node000001_Node000009" title=" " alt="" coords="66,189,101,232,124,255,151,275,161,280,158,285,148,280,121,259,97,235,62,193"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$class_b_n_o08x.html#ae0dab25557befcf62bf384fdc241ef10" title="Initializes required gpio." alt="" coords="363,31,489,57"/>
|
|
||||||
<area shape="poly" id="edge2_Node000002_Node000003" title=" " alt="" coords="313,41,348,41,348,47,313,47"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$class_b_n_o08x.html#a8f34d5475474f00ae6a92f73c1fe14e4" title="Initializes required gpio inputs." alt="" coords="541,5,710,32"/>
|
|
||||||
<area shape="poly" id="edge3_Node000003_Node000004" title=" " alt="" coords="489,33,525,29,526,34,490,39"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$class_b_n_o08x.html#ad0b9e8f8d051798bb1da9b19598dbd64" title="Initializes required gpio outputs." alt="" coords="537,56,714,83"/>
|
|
||||||
<area shape="poly" id="edge4_Node000003_Node000005" title=" " alt="" coords="490,49,522,54,522,59,489,55"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
0c439ca96468053d82fd88a4544d028a
|
|
||||||
|
Before Width: | Height: | Size: 14 KiB |
|
|
@ -1,81 +0,0 @@
|
||||||
<map id="TEST_CASE" name="TEST_CASE">
|
|
||||||
<area shape="rect" id="Node000001" title=" " alt="" coords="5,667,102,693"/>
|
|
||||||
<area shape="rect" id="Node000002" href="$class_b_n_o08x_test_helper.html#adf2488d1f7e3dec21a0d0c99417c181a" title="Used to call private BNO08x::launch_tasks() member for tests." alt="" coords="152,525,313,568"/>
|
|
||||||
<area shape="poly" id="edge1_Node000001_Node000002" title=" " alt="" coords="63,665,98,623,122,599,148,578,155,574,158,578,151,582,125,603,102,626,67,668"/>
|
|
||||||
<area shape="rect" id="Node000037" href="$class_b_n_o08x_test_helper.html#a41a432a3fe288e45b6ab139a00bd7d6b" title="Deletes test IMU calling deconstructor and releases heap allocated memory." alt="" coords="153,592,312,635"/>
|
|
||||||
<area shape="poly" id="edge36_Node000001_Node000037" title=" " alt="" coords="91,664,158,638,160,643,93,669"/>
|
|
||||||
<area shape="rect" id="Node000038" href="$class_b_n_o08x_test_helper.html#a16423fc3250e88eb5392800022f82919" title="Prints end begin banner." alt="" coords="150,659,315,701"/>
|
|
||||||
<area shape="poly" id="edge37_Node000001_Node000038" title=" " alt="" coords="102,677,134,677,134,683,102,683"/>
|
|
||||||
<area shape="rect" id="Node000039" href="$class_b_n_o08x_test_helper.html#a066f8389fd1c682ec9565ebc3060d885" title="Prints test begin banner." alt="" coords="150,725,315,768"/>
|
|
||||||
<area shape="poly" id="edge38_Node000001_Node000039" title=" " alt="" coords="93,691,160,717,158,722,91,696"/>
|
|
||||||
<area shape="rect" id="Node000040" href="$_callback_tests_8cpp.html#a9091949d4ea860523915687536d5c4d3" title=" " alt="" coords="151,792,314,819"/>
|
|
||||||
<area shape="poly" id="edge39_Node000001_Node000040" title=" " alt="" coords="66,692,101,734,124,758,151,778,161,783,158,788,148,782,121,762,97,738,62,695"/>
|
|
||||||
<area shape="rect" id="Node000003" href="$class_b_n_o08x.html#a06f99a6b2182b49a0e61e2107f2be6be" title="Launches spi_task and data_proc_task on constructor call." alt="" coords="363,533,518,560"/>
|
|
||||||
<area shape="poly" id="edge2_Node000002_Node000003" title=" " alt="" coords="313,544,347,544,347,549,313,549"/>
|
|
||||||
<area shape="rect" id="Node000004" href="$class_b_n_o08x.html#a0ae135d7bf7a5f047a1d1aa5cc07e520" title="Static function used to launch data processing task." alt="" coords="580,473,747,516"/>
|
|
||||||
<area shape="poly" id="edge3_Node000003_Node000004" title=" " alt="" coords="500,530,564,515,565,520,502,535"/>
|
|
||||||
<area shape="rect" id="Node000031" href="$class_b_n_o08x.html#a0ce6d9db873555f1ebe7e095251eab74" title="Static function used to launch spi task." alt="" coords="566,563,761,589"/>
|
|
||||||
<area shape="poly" id="edge30_Node000003_Node000031" title=" " alt="" coords="519,554,551,559,550,564,518,559"/>
|
|
||||||
<area shape="rect" id="Node000005" href="$class_b_n_o08x.html#ab4373e9b87837ea9fcbc0b536338c7b8" title="Task responsible parsing packets. Executed when SPI task sends a packet to be parsed,..." alt="" coords="809,471,976,497"/>
|
|
||||||
<area shape="poly" id="edge4_Node000004_Node000005" title=" " alt="" coords="748,488,793,486,793,491,748,493"/>
|
|
||||||
<area shape="rect" id="Node000006" href="$class_b_n_o08x.html#a1c47d27917ae3b2876efa121b803f924" title="Parses a packet received from bno08x, updating any data according to received reports." alt="" coords="1028,408,1184,435"/>
|
|
||||||
<area shape="poly" id="edge5_Node000005_Node000006" title=" " alt="" coords="940,468,1042,437,1044,442,941,473"/>
|
|
||||||
<area shape="rect" id="Node000030" href="$class_b_n_o08x.html#a05e4cd5861b55fc0182d7dd13bb85e49" title="Prints the passed SHTP packet to serial console with ESP_LOG statement." alt="" coords="1032,471,1181,497"/>
|
|
||||||
<area shape="poly" id="edge29_Node000005_Node000030" title=" " alt="" coords="977,481,1016,481,1016,487,977,487"/>
|
|
||||||
<area shape="rect" id="Node000007" href="$class_b_n_o08x.html#a4f66045a0528a0c17c52421ea51612e7" title="Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)" alt="" coords="1249,192,1423,235"/>
|
|
||||||
<area shape="poly" id="edge6_Node000006_Node000007" title=" " alt="" coords="1111,407,1129,374,1156,330,1191,284,1235,245,1241,240,1244,245,1238,249,1195,288,1160,333,1133,377,1116,409"/>
|
|
||||||
<area shape="rect" id="Node000008" href="$class_b_n_o08x.html#a206c0e3ddc3b745b56914976d6e69981" title="Parses get feature request report received from BNO08x." alt="" coords="1258,259,1414,301"/>
|
|
||||||
<area shape="poly" id="edge7_Node000006_Node000008" title=" " alt="" coords="1119,406,1167,360,1200,334,1235,311,1245,306,1248,310,1238,316,1203,338,1171,364,1122,409"/>
|
|
||||||
<area shape="rect" id="Node000009" href="$class_b_n_o08x.html#a51b360d795563b55559f11efb40be36a" title="Sends packet to be parsed to meta data function call (FRS_read_data()) through queue." alt="" coords="1254,325,1418,368"/>
|
|
||||||
<area shape="poly" id="edge8_Node000006_Node000009" title=" " alt="" coords="1149,405,1253,371,1255,376,1151,410"/>
|
|
||||||
<area shape="rect" id="Node000010" href="$class_b_n_o08x.html#a7be6047fef851a064c7cbc9eba092f6d" title="Parses received gyro integrated rotation vector report sent by BNO08x." alt="" coords="1265,392,1407,451"/>
|
|
||||||
<area shape="poly" id="edge9_Node000006_Node000010" title=" " alt="" coords="1184,419,1249,419,1249,424,1184,424"/>
|
|
||||||
<area shape="rect" id="Node000012" href="$class_b_n_o08x.html#a8d9db3e1b6208c2661e1c543deefa53d" title="Parses received input report sent by BNO08x." alt="" coords="1263,475,1409,517"/>
|
|
||||||
<area shape="poly" id="edge11_Node000006_Node000012" title=" " alt="" coords="1151,433,1255,467,1253,472,1149,438"/>
|
|
||||||
<area shape="rect" id="Node000029" href="$class_b_n_o08x.html#a29cfd7fc2816483ebebe9d55b677a036" title="Parses product id report and prints device info." alt="" coords="1256,541,1416,584"/>
|
|
||||||
<area shape="poly" id="edge28_Node000006_Node000029" title=" " alt="" coords="1150,433,1190,457,1206,475,1214,493,1222,511,1238,527,1244,532,1241,536,1235,531,1218,514,1209,496,1202,478,1187,461,1147,438"/>
|
|
||||||
<area shape="rect" id="Node000011" href="$class_b_n_o08x.html#ab02386f13caa446bab5921c1a71f92ab" title="Updates integrated gyro rotation vector data from SHTP channel 5 (CHANNEL_GYRO) special report data." alt="" coords="1512,5,1694,48"/>
|
|
||||||
<area shape="poly" id="edge10_Node000010_Node000011" title=" " alt="" coords="1406,400,1421,391,1434,378,1447,358,1457,337,1464,297,1462,258,1455,218,1447,179,1446,139,1455,99,1466,79,1482,58,1497,45,1500,49,1486,62,1471,82,1460,101,1451,140,1453,178,1460,217,1467,257,1470,297,1462,339,1452,360,1438,382,1425,395,1409,405"/>
|
|
||||||
<area shape="rect" id="Node000013" href="$class_b_n_o08x.html#a002aa97c9af8f6df2d0c83034e4f7b55" title="Parses data from received input report." alt="" coords="1530,72,1676,115"/>
|
|
||||||
<area shape="poly" id="edge12_Node000012_Node000013" title=" " alt="" coords="1408,480,1422,472,1434,461,1449,440,1459,419,1467,377,1464,336,1456,294,1448,253,1445,211,1455,168,1466,146,1482,125,1497,112,1514,103,1517,107,1500,116,1486,128,1470,149,1460,170,1450,211,1453,252,1461,293,1470,335,1473,377,1464,420,1453,442,1438,464,1425,476,1410,485"/>
|
|
||||||
<area shape="rect" id="Node000014" href="$class_b_n_o08x.html#afe588fbd0055193d3bc08984d7732354" title="Updates accelerometer data from parsed input report." alt="" coords="1484,139,1722,165"/>
|
|
||||||
<area shape="poly" id="edge13_Node000012_Node000014" title=" " alt="" coords="1408,480,1434,461,1456,425,1463,390,1461,354,1455,319,1449,283,1448,247,1457,211,1482,176,1484,173,1488,177,1486,179,1462,213,1453,248,1454,282,1460,318,1467,354,1468,390,1460,427,1438,464,1411,484"/>
|
|
||||||
<area shape="rect" id="Node000015" href="$class_b_n_o08x.html#a962b695ef4733d558c6f9684da0931ab" title="Updates linear gyro data from parsed input report." alt="" coords="1513,189,1693,232"/>
|
|
||||||
<area shape="poly" id="edge14_Node000012_Node000015" title=" " alt="" coords="1408,479,1434,461,1452,434,1459,407,1459,380,1456,353,1453,326,1454,298,1462,270,1482,242,1498,229,1501,233,1486,246,1467,272,1459,299,1459,325,1462,352,1465,380,1464,408,1456,436,1438,465,1411,484"/>
|
|
||||||
<area shape="rect" id="Node000016" href="$class_b_n_o08x.html#af971d82426740e62c1f05adcd2c9ce7c" title="Updates command data from parsed input report." alt="" coords="1496,256,1710,283"/>
|
|
||||||
<area shape="poly" id="edge15_Node000012_Node000016" title=" " alt="" coords="1407,479,1434,461,1448,440,1455,420,1456,377,1457,335,1465,313,1482,293,1486,289,1489,293,1486,297,1470,316,1462,336,1461,378,1460,421,1453,443,1438,465,1410,483"/>
|
|
||||||
<area shape="rect" id="Node000017" href="$class_b_n_o08x.html#ad7de3999d4df19038e27c01f9b02010e" title="Updates gravity data from parsed input report." alt="" coords="1506,307,1700,333"/>
|
|
||||||
<area shape="poly" id="edge16_Node000012_Node000017" title=" " alt="" coords="1408,478,1434,461,1445,447,1452,432,1456,403,1461,373,1469,358,1482,343,1491,337,1494,341,1485,347,1473,361,1466,374,1461,404,1457,434,1450,449,1437,465,1411,482"/>
|
|
||||||
<area shape="rect" id="Node000018" href="$class_b_n_o08x.html#a7416d844f6188c8d16f181d6d4431708" title="Updates linear accelerometer data from parsed input report." alt="" coords="1532,357,1674,400"/>
|
|
||||||
<area shape="poly" id="edge17_Node000012_Node000018" title=" " alt="" coords="1408,474,1434,460,1448,448,1457,436,1467,423,1482,410,1515,394,1518,399,1485,414,1471,426,1462,439,1452,452,1437,465,1410,479"/>
|
|
||||||
<area shape="rect" id="Node000019" href="$class_b_n_o08x.html#a3abf4a199bc7a03ac7447c2781673d88" title="Updates magnetic field data from parsed input report." alt="" coords="1511,424,1695,451"/>
|
|
||||||
<area shape="poly" id="edge18_Node000012_Node000019" title=" " alt="" coords="1409,477,1483,460,1521,452,1522,457,1484,465,1410,482"/>
|
|
||||||
<area shape="rect" id="Node000020" href="$class_b_n_o08x.html#a04489cf9a125495c7cf07c6ba5e9f6c0" title="Updates activity classifier data from parsed input report." alt="" coords="1516,475,1690,517"/>
|
|
||||||
<area shape="poly" id="edge19_Node000012_Node000020" title=" " alt="" coords="1409,493,1500,493,1500,499,1409,499"/>
|
|
||||||
<area shape="rect" id="Node000021" href="$class_b_n_o08x.html#a83fed63c67957ec4338afd43087d6e22" title="Updates raw accelerometer data from parsed input report." alt="" coords="1531,541,1675,584"/>
|
|
||||||
<area shape="poly" id="edge20_Node000012_Node000021" title=" " alt="" coords="1410,512,1516,538,1515,544,1409,517"/>
|
|
||||||
<area shape="rect" id="Node000022" href="$class_b_n_o08x.html#ad0f0fec4e53029b4ba907414a36ac5ea" title="Updates raw gyro data from parsed input report." alt="" coords="1531,608,1675,651"/>
|
|
||||||
<area shape="poly" id="edge21_Node000012_Node000022" title=" " alt="" coords="1411,512,1437,527,1454,544,1462,562,1470,578,1485,594,1517,610,1514,615,1482,598,1466,581,1457,564,1449,547,1434,531,1408,517"/>
|
|
||||||
<area shape="rect" id="Node000023" href="$class_b_n_o08x.html#a6ddc9600c53a4248d1affcab36f6f245" title="Updates raw magnetic field data from parsed input report." alt="" coords="1531,675,1675,717"/>
|
|
||||||
<area shape="poly" id="edge22_Node000012_Node000023" title=" " alt="" coords="1410,509,1437,527,1451,545,1458,562,1462,596,1466,629,1472,645,1485,661,1518,680,1515,685,1482,665,1468,648,1460,631,1457,597,1453,563,1446,547,1434,531,1407,514"/>
|
|
||||||
<area shape="rect" id="Node000024" href="$class_b_n_o08x.html#aa309152750686fbf8ebf7d6de1f1254b" title="Updates roation vector data from parsed input report." alt="" coords="1519,741,1687,784"/>
|
|
||||||
<area shape="poly" id="edge23_Node000012_Node000024" title=" " alt="" coords="1411,508,1438,527,1455,553,1463,579,1464,605,1462,630,1460,655,1461,679,1468,703,1486,727,1506,743,1503,747,1482,731,1464,706,1455,680,1454,655,1456,630,1459,605,1458,580,1450,556,1434,531,1408,513"/>
|
|
||||||
<area shape="rect" id="Node000025" href="$class_b_n_o08x.html#a358316b883928c50dd381f024e6b0645" title="Updates stability classifier data from parsed input report." alt="" coords="1518,808,1688,851"/>
|
|
||||||
<area shape="poly" id="edge24_Node000012_Node000025" title=" " alt="" coords="1411,508,1438,528,1459,562,1468,597,1467,631,1461,664,1456,697,1456,729,1464,762,1486,794,1506,810,1503,814,1482,798,1459,764,1450,730,1451,696,1456,663,1461,630,1462,597,1455,564,1434,531,1408,512"/>
|
|
||||||
<area shape="rect" id="Node000026" href="$class_b_n_o08x.html#aa390bf840246e3233e07f6a424efcb6f" title="Updates step counter data from parsed input report." alt="" coords="1528,875,1678,917"/>
|
|
||||||
<area shape="poly" id="edge25_Node000012_Node000026" title=" " alt="" coords="1410,507,1425,516,1438,528,1453,549,1464,571,1472,614,1470,656,1461,697,1453,738,1451,779,1460,820,1470,840,1486,861,1499,873,1515,881,1513,886,1496,877,1482,864,1466,843,1455,822,1445,779,1448,738,1456,696,1464,655,1467,614,1459,573,1449,552,1434,531,1422,520,1408,512"/>
|
|
||||||
<area shape="rect" id="Node000027" href="$class_b_n_o08x.html#ac75b7fb1a1b407d0888ea07d708831b1" title="Updates tap detector data from parsed input report." alt="" coords="1532,941,1674,984"/>
|
|
||||||
<area shape="poly" id="edge26_Node000012_Node000027" title=" " alt="" coords="1410,507,1425,516,1438,528,1456,554,1468,580,1475,606,1477,631,1472,682,1461,731,1450,780,1446,829,1448,853,1455,878,1467,903,1486,928,1501,941,1519,950,1516,955,1498,945,1482,931,1463,905,1450,880,1443,854,1440,829,1444,779,1456,730,1467,681,1472,631,1469,607,1463,582,1451,557,1434,531,1422,520,1408,512"/>
|
|
||||||
<area shape="rect" id="Node000028" href="$class_b_n_o08x.html#a8de12c9c47549502147bd85dbb7e364e" title="Updates uncalibrated gyro data from parsed input report." alt="" coords="1506,1008,1700,1051"/>
|
|
||||||
<area shape="poly" id="edge27_Node000012_Node000028" title=" " alt="" coords="1411,507,1425,516,1438,528,1458,558,1472,589,1480,619,1482,649,1475,707,1461,765,1446,822,1441,879,1443,907,1451,936,1465,965,1486,994,1495,1003,1491,1007,1482,998,1460,968,1446,938,1438,908,1435,879,1441,821,1456,763,1470,706,1476,649,1474,620,1467,591,1454,561,1434,531,1422,520,1408,512"/>
|
|
||||||
<area shape="rect" id="Node000032" href="$class_b_n_o08x.html#a2ecd4ed60f82730ae230c61687ec92bf" title="Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x." alt="" coords="829,608,956,635"/>
|
|
||||||
<area shape="poly" id="edge31_Node000031_Node000032" title=" " alt="" coords="735,587,814,603,813,608,734,593"/>
|
|
||||||
<area shape="rect" id="Node000033" href="$class_b_n_o08x.html#a8d9f28d8857279a3c4b1f62f6dabb638" title="Receives a SHTP packet via SPI and sends it to data_proc_task()" alt="" coords="1024,608,1188,635"/>
|
|
||||||
<area shape="poly" id="edge32_Node000032_Node000033" title=" " alt="" coords="956,619,1008,619,1008,624,956,624"/>
|
|
||||||
<area shape="rect" id="Node000036" href="$class_b_n_o08x.html#a2c359a44a2c8e83ecb258a340e2d0e1a" title="Sends a queued SHTP packet via SPI." alt="" coords="1030,659,1182,685"/>
|
|
||||||
<area shape="poly" id="edge35_Node000032_Node000036" title=" " alt="" coords="953,633,1033,652,1032,657,951,638"/>
|
|
||||||
<area shape="rect" id="Node000034" href="$class_b_n_o08x.html#a9ee7e73f695af8965a9ede50136d5a8c" title="Receives a SHTP packet body via SPI." alt="" coords="1236,608,1436,635"/>
|
|
||||||
<area shape="poly" id="edge33_Node000033_Node000034" title=" " alt="" coords="1189,619,1221,619,1221,624,1189,624"/>
|
|
||||||
<area shape="rect" id="Node000035" href="$class_b_n_o08x.html#acb246769719351e02bf2aff06d039475" title="Receives a SHTP packet header via SPI." alt="" coords="1254,659,1418,701"/>
|
|
||||||
<area shape="poly" id="edge34_Node000033_Node000035" title=" " alt="" coords="1162,633,1239,653,1238,658,1161,638"/>
|
|
||||||
</map>
|
|
||||||
|
|
@ -1 +0,0 @@
|
||||||
24522c05ba59e36f919ab7878909d19f
|
|
||||||
|
Before Width: | Height: | Size: 97 KiB |