diff --git a/BNO08x.cpp b/BNO08x.cpp new file mode 100644 index 0000000..3f11855 --- /dev/null +++ b/BNO08x.cpp @@ -0,0 +1,2465 @@ +#include "BNO08x.hpp" + + +bool BNO08x::isr_service_installed = {false}; +bno08x_config_t BNO08x::default_imu_config; + +/** + * @brief BNO08x imu constructor. + * + * Construct a BNO08x object for managing a BNO08x sensor. + * Initializes required GPIO pins, interrupts, SPI peripheral, and local task for SPI transactions. + * + * @param imu_config Configuration settings (optional), default settings can be seen in bno08x_config_t + * @return void, nothing to return + */ +BNO08x::BNO08x(bno08x_config_t imu_config): +tx_packet_queued(0U), +imu_config(imu_config), +calibration_status(1), +int_asserted(false) +{ + //clear all buffers + memset(tx_buffer, 0, sizeof(tx_buffer)); + memset(rx_buffer, 0, sizeof(rx_buffer)); + memset(packet_header_rx, 0, sizeof(packet_header_rx)); + memset(commands, 0, sizeof(commands)); + memset(sequence_number, 0, sizeof(sequence_number)); + + //SPI bus config + bus_config.mosi_io_num = imu_config.io_mosi; //assign mosi gpio pin + bus_config.miso_io_num = imu_config.io_miso; //assign miso gpio pin + bus_config.sclk_io_num = imu_config.io_sclk; //assign sclk gpio pin + bus_config.quadhd_io_num = -1; //hold signal gpio (not used) + bus_config.quadwp_io_num = -1; //write protect signal gpio (not used) + + + + //SPI slave device specific config + imu_spi_config.mode = 0x3; //set mode to 3 as per BNO08x datasheet (CPHA second edge, CPOL bus high when idle) + + if(imu_config.sclk_speed > 3000000) //max sclk speed of 3MHz for BNO08x + { + ESP_LOGE(TAG, "Max clock speed exceeded, %lld overwritten with 3000000Hz", imu_config.sclk_speed); + imu_config.sclk_speed = 3000000; + } + + imu_spi_config.clock_source = SPI_CLK_SRC_DEFAULT; + imu_spi_config.clock_speed_hz = imu_config.sclk_speed; //assign SCLK speed + imu_spi_config.address_bits = 0; //0 address bits, not using this system + imu_spi_config.command_bits = 0; //0 command bits, not using this system + imu_spi_config.spics_io_num = -1; //due to esp32 silicon issue, chip select cannot be used with full-duplex mode driver, it must be handled via calls to gpio pins + imu_spi_config.queue_size = 5; //only allow for 5 queued transactions at a time + + + //SPI non-driver-controlled GPIO config + //configure outputs + gpio_config_t outputs_config; + outputs_config.pin_bit_mask = (1ULL << imu_config.io_cs) | (1ULL << imu_config.io_rst) | (1ULL << imu_config.io_wake); //configure CS, RST, and wake gpio pins + outputs_config.mode = GPIO_MODE_OUTPUT; + outputs_config.pull_down_en = GPIO_PULLDOWN_DISABLE; + outputs_config.pull_up_en = GPIO_PULLUP_DISABLE; + outputs_config.intr_type = GPIO_INTR_DISABLE; + gpio_config(&outputs_config); + gpio_set_level(imu_config.io_cs, 1); + gpio_set_level(imu_config.io_wake, 1); + gpio_set_level(imu_config.io_rst, 1); + + //configure input (HINT pin) + gpio_config_t inputs_config; + inputs_config.pin_bit_mask = (1ULL << imu_config.io_int); + inputs_config.mode = GPIO_MODE_INPUT; + inputs_config.pull_up_en = GPIO_PULLUP_ENABLE; + inputs_config.pull_down_en = GPIO_PULLDOWN_DISABLE; + inputs_config.intr_type = GPIO_INTR_NEGEDGE; + gpio_config(&inputs_config); + + //check if GPIO ISR service has been installed (only has to be done once regardless of SPI slaves being used) + if(!isr_service_installed) + { + gpio_install_isr_service(0); //install isr service + isr_service_installed = true; + } + + ESP_ERROR_CHECK(gpio_isr_handler_add(imu_config.io_int, hint_handler, (void *)this)); + gpio_intr_disable(imu_config.io_int); //disable interrupts initially before reset + + //initialize the spi peripheral + spi_bus_initialize(imu_config.spi_peripheral, &bus_config, SPI_DMA_CH_AUTO); + //add the imu device to the bus + spi_bus_add_device(imu_config.spi_peripheral, &imu_spi_config, &spi_hdl); + + //do first SPI operation into nowhere before BNO085 reset to let periphiral stabilize (Anton B.) + memset(tx_buffer, 0, sizeof(tx_buffer)); + spi_transaction.length = 8; + spi_transaction.rxlength = 0; + spi_transaction.tx_buffer = tx_buffer; + spi_transaction.rx_buffer = NULL; + spi_transaction.flags = 0; + spi_device_polling_transmit(spi_hdl, &spi_transaction); //send data packet + + tx_semaphore = xSemaphoreCreateRecursiveMutex(); + spi_task_hdl = NULL; + xTaskCreate(&spi_task_trampoline, "spi_task", 4096, this, 8, &spi_task_hdl); //launch SPI task +} + + +/** + * @brief Initializes BNO08x sensor + * + * Resets sensor and goes through initializing process outlined in BNO08x datasheet. + * + * @return void, nothing to return + */ +bool BNO08x::initialize() +{ + + //Receive advertisement message on boot (see SH2 Ref. Manual 5.2 & 5.3) + if(!hard_reset()) + { + ESP_LOGE(TAG, "Failed to receive advertisement message on boot."); + return false; + } + else + { + ESP_LOGI(TAG, "Received advertisement message."); + } + + //The BNO080 will then transmit an unsolicited Initialize Response (see SH2 Ref. Manual 6.4.5.2) + if(!wait_for_device_int()) + { + ESP_LOGE(TAG, "Failed to receive initialize response on boot."); + return false; + } + else + { + ESP_LOGI(TAG, "Received initialize response."); + } + + + //queue request for product ID command + queue_request_product_id_command(); + //transmit request for product ID + if(!wait_for_device_int()) + { + ESP_LOGE(TAG, "Failed to send product ID report request"); + return false; + } + + //receive product ID report + if(!wait_for_device_int()) + { + ESP_LOGE(TAG, "Failed to receive product ID report."); + return false; + } + + + if(rx_buffer[0] == SHTP_REPORT_PRODUCT_ID_RESPONSE) //check to see that product ID matches what it should + { + uint32_t sw_part_number = ((uint32_t)rx_buffer[7] << 24) | ((uint32_t)rx_buffer[6] << 16) | ((uint32_t)rx_buffer[5] << 8) | ((uint32_t)rx_buffer[4]); + uint32_t sw_build_number = ((uint32_t)rx_buffer[11] << 24) | ((uint32_t)rx_buffer[10] << 16) | ((uint32_t)rx_buffer[9] << 8) | ((uint32_t)rx_buffer[8]); + uint16_t sw_version_patch = ((uint16_t)rx_buffer[13] << 8) | ((uint16_t)rx_buffer[12]); + + //print product ID info packet + ESP_LOGI(TAG, "Successfully initialized....\n\r" + " ---------------------------\n\r" + " Product ID: 0x%" PRIx32 "\n\r" + " SW Version Major: 0x%" PRIx32 "\n\r" + " SW Version Minor: 0x%" PRIx32 "\n\r" + " SW Part Number: 0x%" PRIx32 "\n\r" + " SW Build Number: 0x%" PRIx32 "\n\r" + " SW Version Patch: 0x%" PRIx32 "\n\r" + " ---------------------------\n\r", + (uint32_t)rx_buffer[0], + (uint32_t)rx_buffer[2], + (uint32_t)rx_buffer[3], + sw_part_number, + sw_build_number, + (uint32_t)sw_version_patch); + } + else + return false; + + return true; +} + +/** + * @brief Re-enables interrupts and waits for BNO08x to assert HINT pin. + * + * @return void, nothing to return + */ +bool BNO08x::wait_for_device_int() +{ + int64_t start_time = esp_timer_get_time(); //get start time to manager timeout period + gpio_intr_enable(imu_config.io_int); //re-enable interrupts + + //wait until an interrupt has been asserted or timeout has occured + while(!int_asserted) + { + vTaskDelay(10/portTICK_PERIOD_MS); + + if((esp_timer_get_time() - start_time) > HOST_INT_TIMEOUT_US) + break; + } + + if(int_asserted) + { + if(imu_config.debug_en) + ESP_LOGI(TAG, "int asserted"); + + int_asserted = false; //reset HINT ISR flag + return true; + } + + if(!int_asserted) + ESP_LOGE(TAG, "Interrupt to host device never asserted."); + + return false; +} + +/** + * @brief Hard resets BNO08x sensor. + * + * @return void, nothing to return + */ +bool BNO08x::hard_reset() +{ + gpio_set_level(imu_config.io_cs, 1); + gpio_set_level(imu_config.io_wake, 1); + gpio_set_level(imu_config.io_rst, 0); //set reset pin low + vTaskDelay(50/portTICK_PERIOD_MS); //10ns min, set to 50ms to let things stabilize(Anton) + gpio_set_level(imu_config.io_rst, 1); //bring out of reset + + if(!wait_for_device_int()) //wait for BNO08x to assert INT pin + { + ESP_LOGE(TAG, "Reset Failed, interrupt to host device never asserted."); + return false; + } + + return true; +} + +/** + * @brief Soft resets BNO08x sensor using executable channel. + * + * @return True if reset was success. + */ +bool BNO08x::soft_reset() +{ + bool success = false; + + memset(commands, 0, sizeof(commands)); + commands[0] = 1; + + queue_packet(CHANNEL_EXECUTABLE, 1); + success = wait_for_device_int(); + vTaskDelay(20/portTICK_PERIOD_MS); + success = wait_for_device_int(); //receive advertisement message; + vTaskDelay(20/portTICK_PERIOD_MS); + success = wait_for_device_int(); //receive initialize message + + return success; +} + +/** + * @brief Get the reason for the most recent reset. + * + * @return The reason for the most recent recent reset ( 1 = POR (power on reset), 2 = internal reset, 3 = watchdog timer, 4 = external reset 5 = other) + */ +uint8_t BNO08x::get_reset_reason() +{ + memset(commands, 0, sizeof(commands)); + commands[0] = SHTP_REPORT_PRODUCT_ID_REQUEST; //Request the product ID and reset info + commands[1] = 0; //Reserved + + //Transmit packet on channel 2, 2 bytes + queue_packet(CHANNEL_CONTROL, 2); + wait_for_device_int(); + + if(wait_for_device_int()) + { + if (commands[0] == SHTP_REPORT_PRODUCT_ID_RESPONSE) + return (commands[1]); + } + + return 0; +} + +/** + * @brief Turns on/ brings BNO08x sensor out of sleep mode using executable channel. + * + * @return True if exiting sleep mode was success. + */ +bool BNO08x::mode_on() +{ + bool success = false; + + memset(commands, 0, sizeof(commands)); + commands[0] = 2; + + queue_packet(CHANNEL_EXECUTABLE, 1); + success = wait_for_device_int(); + vTaskDelay(20/portTICK_PERIOD_MS); + success = wait_for_device_int(); //receive advertisement message; + vTaskDelay(20/portTICK_PERIOD_MS); + success = wait_for_device_int(); //receive initialize message + + return success; +} + +/** + * @brief Puts BNO08x sensor into sleep/low power mode using executable channel. + * + * @return True if entering sleep mode was success. + */ +bool BNO08x::mode_sleep() +{ + bool success = false; + + memset(commands, 0, sizeof(commands)); + commands[0] = 3; + + queue_packet(CHANNEL_EXECUTABLE, 1); + success = wait_for_device_int(); + vTaskDelay(20/portTICK_PERIOD_MS); + success = wait_for_device_int(); //receive advertisement message; + vTaskDelay(20/portTICK_PERIOD_MS); + success = wait_for_device_int(); //receive initialize message + + return success; +} + +/** + * @brief Receives a SHTP packet via SPI. + * + * @return void, nothing to return + */ +bool BNO08x::receive_packet() +{ + uint8_t dummy_header_tx[4]; + + memset(packet_header_rx, 0, sizeof(packet_header_rx)); + memset(dummy_header_tx, 0, sizeof(dummy_header_tx)); + + if(gpio_get_level(imu_config.io_int)) //ensure INT pin is low + return false; + + + //setup transaction to receive first 4 bytes (packet header) + spi_transaction.rx_buffer = packet_header_rx; + spi_transaction.tx_buffer = dummy_header_tx; + spi_transaction.length = 4 * 8; + spi_transaction.rxlength = 4 * 8; + spi_transaction.flags = 0; + + gpio_set_level(imu_config.io_cs, 0); //assert chip select + spi_device_polling_transmit(spi_hdl, &spi_transaction); //receive first 4 bytes (packet header) + + //calculate length of packet from received header + packet_length_rx = (((uint16_t)packet_header_rx[1]) << 8) | ((uint16_t)packet_header_rx[0]); + packet_length_rx &= ~(1 << 15); //Clear the MSbit + + if(imu_config.debug_en) + ESP_LOGW(TAG, "packet rx length: %d", packet_length_rx); + + if(packet_length_rx == 0) + return false; + + packet_length_rx -= 4; //remove 4 header bytes from packet length (we already read those) + + //setup transacton to read the data packet + spi_transaction.rx_buffer = rx_buffer; + spi_transaction.tx_buffer = NULL; + spi_transaction.length = packet_length_rx * 8; + spi_transaction.rxlength = packet_length_rx * 8; + spi_transaction.flags = 0; + + spi_device_polling_transmit(spi_hdl, &spi_transaction); //receive rest of packet + + + gpio_set_level(imu_config.io_cs, 1); //de-assert chip select + + return true; +} + +/** + * @brief Queues an SHTP packet to be sent via SPI. + * + * @return void, nothing to return + */ +void BNO08x::queue_packet(uint8_t channel_number, uint8_t data_length) +{ + + packet_length_tx = data_length + 4; //add 4 bytes for header + uint8_t i = 0; + + xSemaphoreTake(tx_semaphore, portMAX_DELAY); + + memset(tx_buffer, 0, sizeof(tx_buffer)); + + tx_buffer[0] = packet_length_tx & 0xFF; //packet length LSB + tx_buffer[1] = packet_length_tx >> 8; //packet length MSB + tx_buffer[2] = channel_number; //channel number to write to + tx_buffer[3] = sequence_number[channel_number]++; //increment and send sequence number (packet counter) + + //save commands to send to tx_buffer + for(i = 0; i < data_length; i++) + { + tx_buffer[i+4] = commands[i]; + } + + tx_packet_queued = 1; + + xSemaphoreGive(tx_semaphore); +} + +/** + * @brief Sends a queued SHTP packet via SPI. + * + * @return void, nothing to return + */ +void BNO08x::send_packet() +{ + //setup transaction to send packet + spi_transaction.length = packet_length_tx * 8; + spi_transaction.rxlength = 0; + spi_transaction.tx_buffer = tx_buffer; + spi_transaction.rx_buffer = NULL; + spi_transaction.flags = 0; + + gpio_set_level(imu_config.io_cs, 0); //assert chip select + spi_device_polling_transmit(spi_hdl, &spi_transaction); //send data packet + + gpio_set_level(imu_config.io_cs, 1); //de-assert chip select + + tx_packet_queued = 0; +} + +/** + * @brief Queues a packet containing a command. + * + * @param command The command to be sent. + * @return void, nothing to return + */ +void BNO08x::queue_command(uint8_t command) +{ + commands[0] = SHTP_REPORT_COMMAND_REQUEST; //Command Request + commands[1] = command_sequence_number++; //Increments automatically each function call + commands[2] = command; //Command + + queue_packet(CHANNEL_CONTROL, 12); +} + +/** + * @brief Queues a packet containing the request product ID command. + * + * @return void, nothing to return + */ +void BNO08x::queue_request_product_id_command() +{ + commands[0] = SHTP_REPORT_PRODUCT_ID_REQUEST; //request product ID and reset info + commands[1] = 0; //reserved + queue_packet(CHANNEL_CONTROL, 2); +} + +/** + * @brief Sends command to calibrate accelerometer, gyro, and magnetometer. + * + * @return void, nothing to return + */ +void BNO08x::calibrate_all() +{ + queue_calibrate_command(CALIBRATE_ACCEL_GYRO_MAG); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to calibrate accelerometer. + * + * @return void, nothing to return + */ +void BNO08x::calibrate_accelerometer() +{ + queue_calibrate_command(CALIBRATE_ACCEL); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to calibrate gyro. + * + * @return void, nothing to return + */ +void BNO08x::calibrate_gyro() +{ + queue_calibrate_command(CALIBRATE_GYRO); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to calibrate magnetometer. + * + * @return void, nothing to return + */ +void BNO08x::calibrate_magnetometer() +{ + queue_calibrate_command(CALIBRATE_MAG); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to calibrate planar accelerometer + * + * @return void, nothing to return + */ +void BNO08x::calibrate_planar_accelerometer() +{ + queue_calibrate_command(CALIBRATE_PLANAR_ACCEL); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + + +/** + * @brief Queues a packet containing a command to calibrate the specified sensor. + * + * @param sensor_to_calibrate The sensor to calibrate. + * @return void, nothing to return + */ +void BNO08x::queue_calibrate_command(uint8_t sensor_to_calibrate) +{ + memset(commands, 0, sizeof(commands)); + + switch(sensor_to_calibrate) + { + case CALIBRATE_ACCEL: + commands[3] = 1; + break; + + case CALIBRATE_GYRO: + commands[4] = 1; + break; + + case CALIBRATE_MAG: + commands[5] = 1; + break; + + case CALIBRATE_PLANAR_ACCEL: + commands[7]= 1; + break; + + case CALIBRATE_ACCEL_GYRO_MAG: + commands[3] = 1; + commands[4] = 1; + commands[5] = 1; + break; + + case CALIBRATE_STOP: + //do nothing, send packet of all 0s + break; + + default: + + break; + } + + calibration_status = 1; + + queue_command(COMMAND_ME_CALIBRATE); +} + +/** + * @brief Requests ME calibration status from BNO08x (see Ref. Manual 6.4.7.2) + * + * @return void, nothing to return + */ +void BNO08x::request_calibration_status() +{ + memset(commands, 0, sizeof(commands)); + + commands[6] = 0x01; //P3 - 0x01 - Subcommand: Get ME Calibration + + //Using this commands packet, send a command + queue_command(COMMAND_ME_CALIBRATE); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed + +} + +/** + * @brief Returns true if calibration has completed. + * + * @return void, nothing to return + */ +bool BNO08x::calibration_complete() +{ + if (calibration_status == 0) + return true; + + return false; +} + +/** + * @brief Sends command to end calibration procedure. + * + * @return void, nothing to return + */ +void BNO08x::end_calibration() +{ + queue_calibrate_command(CALIBRATE_STOP); //Disables all calibrations + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to save internal calibration data (See Ref. Manual 6.4.7). + * + * @return void, nothing to return + */ +void BNO08x::save_calibration() +{ + memset(commands, 0, sizeof(commands)); + + //Using this shtpData packet, send a command + queue_command(COMMAND_DCD); //Save DCD command + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Runs full calibration routine. + * + * Enables game rotation vector and magnetometer, starts ME calibration process. + * Waits for accuracy of returned quaternions and magnetic field vectors to be high, then saves calibration data and returns. + * + * @return void, nothing to return + */ +bool BNO08x::run_full_calibration_routine() +{ + float magf_x = 0; + float magf_y = 0; + float magf_z = 0; + uint8_t magnetometer_accuracy = LOW_ACCURACY; + + float quat_I = 0; + float quat_J = 0; + float quat_K = 0; + float quat_real = 0; + uint8_t quat_accuracy = LOW_ACCURACY; + + uint16_t high_accuracy = 0; + uint16_t save_calibration_attempt = 0; + + //Enable dynamic calibration for accel, gyro, and mag + calibrate_all(); //Turn on cal for Accel, Gyro, and Mag + + //Enable Game Rotation Vector output + enable_game_rotation_vector(100); //Send data update every 100ms + + //Enable Magnetic Field output + enable_magnetometer(100); //Send data update every 100ms + + while(1) + { + if(data_available()) + { + magf_x = get_magf_X(); + magf_y = get_magf_Y(); + magf_z = get_magf_Z(); + magnetometer_accuracy = get_magf_accuracy(); + + quat_I = get_quat_I(); + quat_J = get_quat_J(); + quat_K = get_quat_K(); + quat_real = get_quat_real(); + quat_accuracy = get_quat_accuracy(); + + ESP_LOGI(TAG, "Magnetometer: x: %.3f y: %.3f z: %.3f, accuracy: %d", magf_x, magf_y, magf_z, magnetometer_accuracy); + ESP_LOGI(TAG, "Quaternion Rotation Vector: i: %.3f j: %.3f k: %.3f, real: %.3f, accuracy: %d", quat_I, quat_J, quat_K, quat_real, quat_accuracy); + + if((magnetometer_accuracy >= MED_ACCURACY) && (quat_accuracy == HIGH_ACCURACY)) + high_accuracy++; + else + high_accuracy = 0; + + if(high_accuracy > 10) + { + save_calibration(); + request_calibration_status(); + + save_calibration_attempt = 0; + + while(save_calibration_attempt < 100) + { + if(data_available()) + { + if(calibration_complete()) + { + ESP_LOGW(TAG, "Calibration data successfully stored."); + return true; + } + } + + vTaskDelay(1/portTICK_PERIOD_MS); + } + + if(save_calibration_attempt >= 100) + ESP_LOGE(TAG, "Calibration data failed to store."); + + return false; + } + } + + vTaskDelay(40/portTICK_PERIOD_MS); + } +} + + /** + * @brief Checks if BNO08x has asserted interrupt and sent data. + * + * @return true if new data has been parsed and saved + */ +bool BNO08x::data_available() +{ + return (get_readings() != 0); +} + +/** + * @brief Waits for BNO08x HINT pin to assert, and parses the received data. + * + * @return void, nothing to return + */ +uint16_t BNO08x::get_readings() +{ + if (wait_for_device_int()) + { + if(imu_config.debug_en) + ESP_LOGE(TAG, "SHTP Header RX'd: 0x%X 0x%X 0x%X 0x%X", packet_header_rx[0], packet_header_rx[1], packet_header_rx[2], packet_header_rx[3]); + + //Check to see if this packet is a sensor reporting its data to us + if (packet_header_rx[2] == CHANNEL_REPORTS && rx_buffer[0] == SHTP_REPORT_BASE_TIMESTAMP) + { + if(imu_config.debug_en) + ESP_LOGI(TAG, "RX'd packet, channel report"); + + return parse_input_report(); //This will update the rawAccelX, etc variables depending on which feature report is found + } + else if (packet_header_rx[2] == CHANNEL_CONTROL) + { + if(imu_config.debug_en) + ESP_LOGI(TAG, "RX'd packet, channel control"); + + return parse_command_report(); //This will update responses to commands, calibrationStatus, etc. + } + else if(packet_header_rx[2] == CHANNEL_GYRO) + { + if(imu_config.debug_en) + ESP_LOGI(TAG, "Rx packet, channel gyro"); + + return parse_input_report(); //This will update the rawAccelX, etc variables depending on which feature report is found + } + } + + return 0; +} + + /** + * @brief Parses received input report sent by BNO08x. + * + * Unit responds with packet that contains the following: + * + * packet_header_rx[0:3]: First, a 4 byte header + * rx_buffer[0:4]: Then a 5 byte timestamp of microsecond ticks since reading was taken + * rx_buffer[5 + 0]: Then a feature report ID (0x01 for Accel, 0x05 for Rotation Vector, etc...) + * rx_buffer[5 + 1]: Sequence number (See Ref.Manual 6.5.8.2) + * rx_buffer[5 + 2]: Status + * rx_buffer[3]: Delay + * rx_buffer[4:5]: i/accel x/gyro x/etc + * rx_buffer[6:7]: j/accel y/gyro y/etc + * rx_buffer[8:9]: k/accel z/gyro z/etc + * rx_buffer[10:11]: real/gyro temp/etc + * rx_buffer[12:13]: Accuracy estimate + * + * @return void, nothing to return + */ +uint16_t BNO08x::parse_input_report() +{ + uint16_t i = 0; + uint8_t status = 0; + uint8_t command = 0; + + //Calculate the number of data bytes in this packet + uint16_t data_length = ((uint16_t)packet_header_rx[1] << 8 | packet_header_rx[0]); + data_length &= ~(1 << 15); //Clear the MSbit. This bit indicates if this package is a continuation of the last. + //Ignore it for now. TODO catch this as an error and exit + + data_length -= 4; //Remove the header bytes from the data count + time_stamp = ((uint32_t)rx_buffer[4] << (8 * 3)) | ((uint32_t)rx_buffer[3] << (8 * 2)) | ((uint32_t)rx_buffer[2] << (8 * 1)) | ((uint32_t)rx_buffer[1] << (8 * 0)); + + // The gyro-integrated input reports are sent via the special gyro channel and do no include the usual ID, sequence, and status fields + if(packet_header_rx[2] == CHANNEL_GYRO) { + raw_quat_I = (uint16_t)rx_buffer[1] << 8 | rx_buffer[0]; + raw_quat_J = (uint16_t)rx_buffer[3] << 8 | rx_buffer[2]; + raw_quat_K = (uint16_t)rx_buffer[5] << 8 | rx_buffer[4]; + raw_quat_real = (uint16_t)rx_buffer[7] << 8 | rx_buffer[6]; + raw_velocity_gyro_X = (uint16_t)rx_buffer[9] << 8 | rx_buffer[8]; + raw_velocity_gyro_Y = (uint16_t)rx_buffer[11] << 8 | rx_buffer[10]; + raw_velocity_gyro_Z = (uint16_t)rx_buffer[13] << 8 | rx_buffer[12]; + + return SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR; + } + + status = rx_buffer[5 + 2] & 0x03; //Get status bits + uint16_t data1 = (uint16_t)rx_buffer[5 + 5] << 8 | rx_buffer[5 + 4]; + uint16_t data2 = (uint16_t)rx_buffer[5 + 7] << 8 | rx_buffer[5 + 6]; + uint16_t data3 = (uint16_t)rx_buffer[5 + 9] << 8 | rx_buffer[5 + 8]; + uint16_t data4 = 0; + uint16_t data5 = 0; + uint16_t data6 = 0; + + if (data_length - 5 > 9) + { + data4 = (uint16_t)rx_buffer[5 + 11] << 8 | rx_buffer[5 + 10]; + } + if (data_length - 5 > 11) + { + data5 = (uint16_t)rx_buffer[5 + 13] << 8 | rx_buffer[5 + 12]; + } + if (data_length - 5 > 13) + { + data6 = (uint16_t)rx_buffer[5 + 15] << 8 | rx_buffer[5 + 14]; + } + + //Store these generic values to their proper global variable + switch(rx_buffer[5]) + { + case SENSOR_REPORTID_ACCELEROMETER: + accel_accuracy = status; + raw_accel_X = data1; + raw_accel_Y = data2; + raw_accel_Z = data3; + break; + + case SENSOR_REPORTID_LINEAR_ACCELERATION: + accel_lin_accuracy = status; + raw_lin_accel_X = data1; + raw_lin_accel_Y = data2; + raw_lin_accel_Z = data3; + break; + + case SENSOR_REPORTID_GYROSCOPE: + gyro_accuracy = status; + raw_gyro_X = data1; + raw_gyro_Y = data2; + raw_gyro_Z = data3; + break; + + case SENSOR_REPORTID_UNCALIBRATED_GYRO: + uncalib_gyro_accuracy = status; + raw_uncalib_gyro_X = data1; + raw_uncalib_gyro_Y = data2; + raw_uncalib_gyro_Z = data3; + raw_bias_X = data4; + raw_bias_Y = data5; + raw_bias_Z = data6; + break; + + case SENSOR_REPORTID_MAGNETIC_FIELD: + magf_accuracy = status; + raw_magf_X = data1; + raw_magf_Y = data2; + raw_magf_Z = data3; + break; + + case SENSOR_REPORTID_TAP_DETECTOR: + tap_detector = rx_buffer[5 + 4]; //Byte 4 only + break; + + case SENSOR_REPORTID_STEP_COUNTER: + step_count = data3; //Bytes 8/9 + break; + + case SENSOR_REPORTID_STABILITY_CLASSIFIER: + stability_classifier = rx_buffer[5 + 4]; //Byte 4 only + break; + + case SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER: + activity_classifier = rx_buffer[5 + 5]; //Most likely state + + //Load activity classification confidences into the array + for (i = 0; i < 9; i++) //Hardcoded to max of 9. TODO - bring in array size + activity_confidences[i] = rx_buffer[5 + 6 + i]; //5 bytes of timestamp, byte 6 is first confidence byte + break; + + case SENSOR_REPORTID_RAW_ACCELEROMETER: + mems_raw_accel_X = data1; + mems_raw_accel_Y = data2; + mems_raw_accel_Z = data3; + break; + + case SENSOR_REPORTID_RAW_GYROSCOPE: + mems_raw_gyro_X = data1; + mems_raw_gyro_Y = data2; + mems_raw_gyro_Z = data3; + break; + + case SENSOR_REPORTID_RAW_MAGNETOMETER: + mems_raw_magf_X = data1; + mems_raw_magf_Y = data2; + mems_raw_magf_Z = data3; + break; + + case SHTP_REPORT_COMMAND_RESPONSE: + //The BNO080 responds with this report to command requests. It's up to use to remember which command we issued. + command = rx_buffer[5 + 2]; //This is the Command byte of the response + + if (command == COMMAND_ME_CALIBRATE) + calibration_status = rx_buffer[5 + 5]; //R0 - Status (0 = success, non-zero = fail) + break; + + case SENSOR_REPORTID_GRAVITY: + gravity_accuracy = status; + gravity_X = data1; + gravity_Y = data2; + gravity_Z = data3; + break; + + default: + if(rx_buffer[5] == SENSOR_REPORTID_ROTATION_VECTOR || + rx_buffer[5] == SENSOR_REPORTID_GAME_ROTATION_VECTOR || + rx_buffer[5] == SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR || + rx_buffer[5] == SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR) + { + quat_accuracy = status; + raw_quat_I = data1; + raw_quat_J = data2; + raw_quat_K = data3; + raw_quat_real = data4; + + //Only available on rotation vector and ar/vr stabilized rotation vector, + // not game rot vector and not ar/vr stabilized rotation vector + raw_quat_radian_accuracy = data5; + } + else + { + //This sensor report ID is unhandled. + //See reference manual to add additional feature reports as needed + return 0; + } + + break; + } + + //TODO additional feature reports may be strung together. Parse them all. + return rx_buffer[5]; +} + + +/** + * @brief Parses received command report sent by BNO08x (See Ref. Manual 6.3.9) + * + * @return The command report ID, 0 if invalid. + */ +uint16_t BNO08x::parse_command_report() +{ + uint8_t command = 0; + + if (rx_buffer[0] == SHTP_REPORT_COMMAND_RESPONSE) + { + //The BNO080 responds with this report to command requests. It's up to use to remember which command we issued. + command = rx_buffer[2]; //This is the Command byte of the response + + if (command == COMMAND_ME_CALIBRATE) + { + calibration_status = rx_buffer[5 + 0]; //R0 - Status (0 = success, non-zero = fail) + } + return rx_buffer[0]; + } + else + { + //This sensor report ID is unhandled. + //See SH2 Ref. Manual to add additional feature reports as needed + } + + return 0; +} + + /** + * @brief Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_game_rotation_vector(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_GAME_ROTATION_VECTOR, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + + /** + * @brief Sends command to enable rotation vector reports (See Ref. Manual 6.5.18) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_rotation_vector(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_ROTATION_VECTOR, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + + /** + * @brief Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6.5.42) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_ARVR_stabilized_rotation_vector(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + + /** + * @brief Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6.5.43) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_ARVR_stabilized_game_rotation_vector(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6.5.44) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_gyro_integrated_rotation_vector(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + + /** + * @brief Sends command to enable accelerometer reports (See Ref. Manual 6.5.9) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_accelerometer(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_ACCELEROMETER, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable linear accelerometer reports (See Ref. Manual 6.5.10) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_linear_accelerometer(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_LINEAR_ACCELERATION, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable gravity reading reports (See Ref. Manual 6.5.11) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_gravity(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_GRAVITY, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable gyro reports (See Ref. Manual 6.5.13) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_gyro(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_GYROSCOPE, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.5.14) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_uncalibrated_gyro(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_UNCALIBRATED_GYRO, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable magnetometer reports (See Ref. Manual 6.5.16) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_magnetometer(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_MAGNETIC_FIELD, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable tap detector reports (See Ref. Manual 6.5.27) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_tap_detector(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_TAP_DETECTOR, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable step counter reports (See Ref. Manual 6.5.29) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_step_counter(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_STEP_COUNTER, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable activity stability classifier reports (See Ref. Manual 6.5.31) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_stability_classifier(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_STABILITY_CLASSIFIER, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable activity classifier reports (See Ref. Manual 6.5.36) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @param activities_to_enable Desired activities to enable (0x1F enables all). + * @param activity_confidence_vals Returned activity level confidences. + * @return void, nothing to return + */ +void BNO08x::enable_activity_classifier(uint16_t time_between_reports, uint32_t activities_to_enable, uint8_t (&activity_confidence_vals)[9]) +{ + activity_confidences = activity_confidence_vals; //Store pointer to array + queue_feature_command(SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER, time_between_reports, activities_to_enable); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable raw accelerometer reports (See Ref. Manual 6.5.8) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_raw_accelerometer(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_RAW_ACCELEROMETER, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable raw gyro reports (See Ref. Manual 6.5.12) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_raw_gyro(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_RAW_GYROSCOPE, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to enable raw magnetometer reports (See Ref. Manual 6.5.15) + * + * @param time_between_reports Desired time between reports in miliseconds. + * @return void, nothing to return + */ +void BNO08x::enable_raw_magnetometer(uint16_t time_between_reports) +{ + queue_feature_command(SENSOR_REPORTID_RAW_MAGNETOMETER, time_between_reports); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(50/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to tare an axis (See Ref. Manual 6.4.4.1) + * + * @param axis_sel Which axes to zero, can be TARE_AXIS_ALL (all axes) or TARE_AXIS_Z (only yaw) + * @param rotation_vector_basis Which rotation vector type to zero axes can be TARE_ROTATION_VECTOR, TARE_GAME_ROTATION_VECTOR, TARE_GEOMAGNETIC_ROTATION_VECTOR, etc.. + * @return void, nothing to return + */ +void BNO08x::tare_now(uint8_t axis_sel, uint8_t rotation_vector_basis) +{ + queue_tare_command(TARE_NOW, axis_sel, rotation_vector_basis); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(12/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to save tare into non-volatile memory of BNO08x (See Ref. Manual 6.4.4.2) + * + * @return void, nothing to return + */ +void BNO08x::save_tare() +{ + queue_tare_command(TARE_PERSIST); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(12/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Sends command to clear persistent tare settings in non-volatile memory of BNO08x (See Ref. Manual 6.4.4.3) + * + * @return void, nothing to return + */ +void BNO08x::clear_tare() +{ + queue_tare_command(TARE_SET_REORIENTATION); + wait_for_device_int(); //wait for next interrupt such that command is sent + vTaskDelay(12/portTICK_PERIOD_MS); //allow some time for command to be executed +} + +/** + * @brief Converts a register value to a float using its associated Q point. (See https://en.wikipedia.org/wiki/Q_(number_format)) + * + * @param q_point Q point value associated with register. + * @param fixed_point_value The fixed point value to convert. + * + * @return void, nothing to return + */ +float BNO08x::q_to_float(int16_t fixed_point_value, uint8_t q_point) +{ + + float q_float = fixed_point_value; + q_float *= pow(2, q_point * -1); + return (q_float); +} + +/** + * @brief Return timestamp of most recent report. + * + * @return void, nothing to return + */ +uint32_t BNO08x::get_time_stamp() +{ + return time_stamp; +} + +/** + * @brief Get the full magnetic field vector. + * + * @param x Reference variable to save reported x magnitude. + * @param y Reference variable to save reported y magnitude. + * @param x Reference variable to save reported z magnitude. + * @param accuracy Reference variable save reported accuracy. + * + * @return void, nothing to return + */ +void BNO08x::get_magf(float &x, float &y, float &z, uint8_t &accuracy) +{ + x = q_to_float(raw_magf_X, MAGNETOMETER_Q1); + y = q_to_float(raw_magf_Y, MAGNETOMETER_Q1); + z = q_to_float(raw_magf_Z, MAGNETOMETER_Q1); + accuracy = magf_accuracy; +} + +/** + * @brief Get X component of magnetic field vector. + * + * @return The reported X component of magnetic field vector. + */ +float BNO08x::get_magf_X() +{ + float mag = q_to_float(raw_magf_X, MAGNETOMETER_Q1); + return mag; +} + +/** + * @brief Get Y component of magnetic field vector. + * + * @return The reported Y component of magnetic field vector. + */ +float BNO08x::get_magf_Y() +{ + float mag = q_to_float(raw_magf_Y, MAGNETOMETER_Q1); + return mag; +} + +/** + * @brief Get Z component of magnetic field vector. + * + * @return The reported Z component of magnetic field vector. + */ +float BNO08x::get_magf_Z() +{ + float mag = q_to_float(raw_magf_Z, MAGNETOMETER_Q1); + return mag; +} + +/** + * @brief Get accuracy of reported magnetic field vector. + * + * @return The accuracy of reported magnetic field vector. + */ +uint8_t BNO08x::get_magf_accuracy() +{ + return magf_accuracy; +} + +/** + * @brief Get full reported gravity vector, units in m/s^2 + * + * @param x Reference variable to save X axis gravity. + * @param y Reference variable to save Y axis axis gravity. + * @param z Reference variable to save Z axis axis gravity. + * @param accuracy Reference variable to save reported gravity accuracy. + * + * @return void, nothing to return + */ +void BNO08x::get_gravity(float &x, float &y, float &z, uint8_t &accuracy) +{ + x = q_to_float(gravity_X, GRAVITY_Q1); + y = q_to_float(gravity_Y, GRAVITY_Q1); + z = q_to_float(gravity_Z, GRAVITY_Q1); + accuracy = gravity_accuracy; +} + +/** + * @brief Get the reported x axis gravity. + * + * @return x axis gravity in m/s^2 + */ +float BNO08x::get_gravity_X() +{ + return q_to_float(gravity_X, GRAVITY_Q1); +} + +/** + * @brief Get the reported y axis gravity. + * + * @return y axis gravity in m/s^2 + */ +float BNO08x::get_gravity_Y() +{ + return q_to_float(gravity_Y, GRAVITY_Q1); +} + +/** + * @brief Get the reported z axis gravity. + * + * @return z axis gravity in m/s^2 + */ +float BNO08x::get_gravity_Z() +{ + return q_to_float(gravity_Z, GRAVITY_Q1); +} + +/** + * @brief Get the reported gravity accuracy. + * + * @return Accuracy of reported gravity. + */ +uint8_t BNO08x::get_gravity_accuracy() +{ + return gravity_accuracy; +} + +/** + * @brief Get the reported rotation about x axis. + * + * @return Rotation about the x axis in radians. + */ +float BNO08x::get_roll() +{ + float t_0 = 0.0; + float t_1 = 0.0; + float dq_w = get_quat_real(); + float dq_x = get_quat_I(); + float dq_y = get_quat_J(); + float dq_z = get_quat_K(); + + float norm = sqrt(dq_w*dq_w + dq_x*dq_x + dq_y*dq_y + dq_z*dq_z); + dq_w = dq_w/norm; + dq_x = dq_x/norm; + dq_y = dq_y/norm; + dq_z = dq_z/norm; + + // roll (x-axis rotation) + t_0 = 2.0 * (dq_w * dq_x + dq_y * dq_z); + t_1 = 1.0 - (2.0 * ((dq_x * dq_x) + (dq_y * dq_y))); + + + return atan2(t_0, t_1); +} + +/** + * @brief Get the reported rotation about y axis. + * + * @return Rotation about the y axis in radians. + */ +float BNO08x::get_pitch() +{ + float t_2 = 0.0; + float dq_w = get_quat_real(); + float dq_x = get_quat_I(); + float dq_y = get_quat_J(); + float dq_z = get_quat_K(); + float norm = sqrt(dq_w*dq_w + dq_x*dq_x + dq_y*dq_y + dq_z*dq_z); + + dq_w = dq_w/norm; + dq_x = dq_x/norm; + dq_y = dq_y/norm; + dq_z = dq_z/norm; + + //float ysqr = dqy * dqy; + + // pitch (y-axis rotation) + t_2 = 2.0 * ((dq_w * dq_y) - (dq_z * dq_x)); + t_2 = t_2 > 1.0 ? 1.0 : t_2; + t_2 = t_2 < -1.0 ? -1.0 : t_2; + + + return asin(t_2); +} + +/** + * @brief Get the reported rotation about z axis. + * + * @return Rotation about the z axis in radians. + */ +float BNO08x::get_yaw() +{ + float t_3 = 0.0; + float t_4 = 0.0; + float dq_w = get_quat_real(); + float dq_x = get_quat_I(); + float dq_y = get_quat_J(); + float dq_z = get_quat_K(); + float norm = sqrt(dq_w*dq_w + dq_x*dq_x + dq_y*dq_y + dq_z*dq_z); + + dq_w = dq_w/norm; + dq_x = dq_x/norm; + dq_y = dq_y/norm; + dq_z = dq_z/norm; + + // yaw (z-axis rotation) + t_3 = 2.0 * ((dq_w * dq_z) + (dq_x * dq_y)); + t_4 = 1.0 - (2.0 * ((dq_y * dq_y) + (dq_z * dq_z))); + + return atan2(t_3, t_4); +} + +/** + * @brief Get the reported rotation about x axis. + * + * @return Rotation about the x axis in degrees. + */ +float BNO08x::get_roll_deg() +{ + return get_roll()*(180.0 / M_PI); +} + +/** + * @brief Get the reported rotation about y axis. + * + * @return Rotation about the y axis in degrees. + */ +float BNO08x::get_pitch_deg() +{ + return get_pitch()*(180.0 / M_PI); +} + +/** + * @brief Get the reported rotation about z axis. + * + * @return Rotation about the z axis in degrees. + */ +float BNO08x::get_yaw_deg() +{ + return get_yaw()*(180.0 / M_PI); +} + + +/** + * @brief Get the full quaternion reading. + * + * @param i Reference variable to save reported i component of quaternion. + * @param j Reference variable to save reported j component of quaternion. + * @param k Reference variable to save reported k component of quaternion. + * @param real Reference variable to save reported real component of quaternion. + * @param rad_accuracy Reference variable to save reported raw quaternion radian accuracy. + * @param accuracy Reference variable to save reported quaternion accuracy. + * + * @return void, nothing to return + */ +void BNO08x::get_quat(float &i, float &j, float &k, float &real, float &rad_accuracy, uint8_t &accuracy) +{ + i = q_to_float(raw_quat_I, ROTATION_VECTOR_Q1); + j = q_to_float(raw_quat_J, ROTATION_VECTOR_Q1); + k = q_to_float(raw_quat_K, ROTATION_VECTOR_Q1); + real = q_to_float(raw_quat_real, ROTATION_VECTOR_Q1); + rad_accuracy = q_to_float(raw_quat_radian_accuracy, ROTATION_VECTOR_Q1); + accuracy = quat_accuracy; +} + +/** + * @brief Get I component of reported quaternion. + * + * @return The I component of reported quaternion. + */ +float BNO08x::get_quat_I() +{ + float quat = q_to_float(raw_quat_I, ROTATION_VECTOR_Q1); + return quat; +} + +/** + * @brief Get J component of reported quaternion. + * + * @return The J component of reported quaternion. + */ +float BNO08x::get_quat_J() +{ + float quat = q_to_float(raw_quat_J, ROTATION_VECTOR_Q1); + return quat; +} + +/** + * @brief Get K component of reported quaternion. + * + * @return The K component of reported quaternion. + */ +float BNO08x::get_quat_K() +{ + float quat = q_to_float(raw_quat_K, ROTATION_VECTOR_Q1); + return quat; +} + +/** + * @brief Get real component of reported quaternion. + * + * @return The real component of reported quaternion. + */ +float BNO08x::get_quat_real() +{ + float quat = q_to_float(raw_quat_real, ROTATION_VECTOR_Q1); + return quat; +} + +/** + * @brief Get radian accuracy of reported quaternion. + * + * @return The radian accuracy of reported quaternion. + */ +float BNO08x::get_quat_radian_accuracy() +{ + float quat = q_to_float(raw_quat_radian_accuracy, ROTATION_VECTOR_Q1); + return quat; +} + +/** + * @brief Get accuracy of reported quaternion. + * + * @return The accuracy of reported quaternion. + */ +uint8_t BNO08x::get_quat_accuracy() +{ + return quat_accuracy; +} + +/** + * @brief Get full acceleration (total acceleration of device, units in m/s^2). + * + * @param x Reference variable to save X axis acceleration. + * @param y Reference variable to save Y axis acceleration. + * @param z Reference variable to save Z axis acceleration. + * @param accuracy Reference variable to save reported acceleration accuracy. + * + * @return void, nothing to return + */ +void BNO08x::get_accel(float &x, float &y, float &z, uint8_t &accuracy) +{ + x = q_to_float(raw_accel_X, ACCELEROMETER_Q1); + y = q_to_float(raw_accel_Y, ACCELEROMETER_Q1); + z = q_to_float(raw_accel_Z, ACCELEROMETER_Q1); + accuracy = accel_accuracy; +} + +/** + * @brief Get x axis acceleration (total acceleration of device, units in m/s^2). + * + * @return The angular reported x axis acceleration. + */ +float BNO08x::get_accel_X() +{ + return q_to_float(raw_accel_X, ACCELEROMETER_Q1); +} + +/** + * @brief Get y axis acceleration (total acceleration of device, units in m/s^2). + * + * @return The angular reported y axis acceleration. + */ +float BNO08x::get_accel_Y() +{ + return q_to_float(raw_accel_Y, ACCELEROMETER_Q1); +} + +/** + * @brief Get z axis acceleration (total acceleration of device, units in m/s^2). + * + * @return The angular reported z axis acceleration. + */ +float BNO08x::get_accel_Z() +{ + return q_to_float(raw_accel_Z, ACCELEROMETER_Q1); +} + +/** + * @brief Get accuracy of linear acceleration. + * + * @return Accuracy of linear acceleration. + */ +uint8_t BNO08x::get_accel_accuracy() +{ + return accel_accuracy; +} + +/** + * @brief Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2). + * + * @param x Reference variable to save X axis acceleration. + * @param y Reference variable to save Y axis acceleration. + * @param z Reference variable to save Z axis acceleration. + * @param accuracy Reference variable to save reported linear acceleration accuracy. + * + * @return void, nothing to return + */ +void BNO08x::get_linear_accel(float &x, float &y, float &z, uint8_t &accuracy) +{ + x = q_to_float(raw_lin_accel_X, LINEAR_ACCELEROMETER_Q1); + y = q_to_float(raw_lin_accel_Y, LINEAR_ACCELEROMETER_Q1); + z = q_to_float(raw_lin_accel_Z, LINEAR_ACCELEROMETER_Q1); + accuracy = accel_lin_accuracy; +} + +/** + * @brief Get x axis linear acceleration (acceleration of device minus gravity, units in m/s^2) + * + * @return The angular reported x axis linear acceleration. + */ +float BNO08x::get_linear_accel_X() +{ + return q_to_float(raw_lin_accel_X, LINEAR_ACCELEROMETER_Q1); +} + +/** + * @brief Get y axis linear acceleration (acceleration of device minus gravity, units in m/s^2) + * + * @return The angular reported y axis linear acceleration. + */ +float BNO08x::get_linear_accel_Y() +{ + return q_to_float(raw_lin_accel_Y, LINEAR_ACCELEROMETER_Q1); +} + +/** + * @brief Get z axis linear acceleration (acceleration of device minus gravity, units in m/s^2) + * + * @return The angular reported z axis linear acceleration. + */ +float BNO08x::get_linear_accel_Z() +{ + return q_to_float(raw_lin_accel_Z, LINEAR_ACCELEROMETER_Q1); +} + +/** + * @brief Get accuracy of linear acceleration. + * + * @return Accuracy of linear acceleration. + */ +uint8_t BNO08x::get_linear_accel_accuracy() +{ + return accel_lin_accuracy; +} + +/** + * @brief Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8) + * + * @return Reported raw accelerometer x axis reading from physical MEMs sensor. + */ +int16_t BNO08x::get_raw_accel_X() +{ + return mems_raw_accel_X; +} + +/** + * @brief Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8) + * + * @return Reported raw accelerometer y axis reading from physical MEMs sensor. + */ +int16_t BNO08x::get_raw_accel_Y() +{ + return mems_raw_accel_Y; +} + +/** + * @brief Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8) + * + * @return Reported raw accelerometer z axis reading from physical MEMs sensor. + */ +int16_t BNO08x::get_raw_accel_Z() +{ + return mems_raw_accel_Z; +} + +/** + * @brief Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12) + * + * @return Reported raw gyroscope x axis reading from physical MEMs sensor. + */ +int16_t BNO08x::get_raw_gyro_X() +{ + return mems_raw_gyro_X; +} + +/** + * @brief Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12) + * + * @return Reported raw gyroscope y axis reading from physical MEMs sensor. + */ +int16_t BNO08x::get_raw_gyro_Y() +{ + return mems_raw_gyro_Y; +} + +/** + * @brief Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12) + * + * @return Reported raw gyroscope z axis reading from physical MEMs sensor. + */ +int16_t BNO08x::get_raw_gyro_Z() +{ + return mems_raw_gyro_Z; +} + +/** + * @brief Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15) + * + * @return Reported raw magnetometer x axis reading from physical magnetometer sensor. + */ +int16_t BNO08x::get_raw_magf_X() +{ + return mems_raw_magf_X; +} + +/** + * @brief Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15) + * + * @return Reported raw magnetometer y axis reading from physical magnetometer sensor. + */ +int16_t BNO08x::get_raw_magf_Y() +{ + return mems_raw_magf_Y; +} + +/** + * @brief Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15) + * + * @return Reported raw magnetometer z axis reading from physical magnetometer sensor. + */ +int16_t BNO08x::get_raw_magf_Z() +{ + return mems_raw_magf_Z; +} + +/** + * @brief Get full rotational velocity with drift compensation (units in Rad/s). + * + * @param x Reference variable to save X axis angular velocity + * @param y Reference variable to save Y axis angular velocity + * @param z Reference variable to save Z axis angular velocity + * @param accuracy Reference variable to save reported gyro accuracy. + * + * @return void, nothing to return + */ +void BNO08x::get_gyro_calibrated_velocity(float &x, float &y, float &z, uint8_t &accuracy) +{ + x = q_to_float(raw_gyro_X, GYRO_Q1); + y = q_to_float(raw_gyro_Y, GYRO_Q1); + z = q_to_float(raw_gyro_Z, GYRO_Q1); + accuracy = gyro_accuracy; +} + +/** + * @brief Get calibrated gyro x axis angular velocity measurement. + * + * @return The angular reported x axis angular velocity from calibrated gyro (drift compensation applied). + */ +float BNO08x::get_gyro_calibrated_velocity_X() +{ + return q_to_float(raw_gyro_X, GYRO_Q1); +} + +/** + * @brief Get calibrated gyro y axis angular velocity measurement. + * + * @return The angular reported y axis angular velocity from calibrated gyro (drift compensation applied). + */ +float BNO08x::get_gyro_calibrated_velocity_Y() +{ + return q_to_float(raw_gyro_Y, GYRO_Q1); +} + +/** + * @brief Get calibrated gyro z axis angular velocity measurement. + * + * @return The angular reported z axis angular velocity from calibrated gyro (drift compensation applied). + */ +float BNO08x::get_gyro_calibrated_velocity_Z() +{ + return q_to_float(raw_gyro_Z, GYRO_Q1); +} + +/** + * @brief Get calibrated gyro accuracy. + * + * @return Accuracy of calibrated gyro. + */ +uint8_t BNO08x::get_gyro_accuracy() +{ + return gyro_accuracy; +} + +/** + * @brief Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is given but not applied. + * + * @param x Reference variable to save X axis angular velocity + * @param y Reference variable to save Y axis angular velocity + * @param z Reference variable to save Z axis angular velocity + * @param b_x Reference variable to save X axis drift estimate + * @param b_y Reference variable to save Y axis drift estimate + * @param b_z Reference variable to save Z axis drift estimate + * @param accuracy Reference variable to save reported gyro accuracy. + * + * @return void, nothing to return + */ +void BNO08x::get_uncalibrated_gyro(float &x, float &y, float &z, float &b_x, float &b_y, float &b_z, uint8_t &accuracy) +{ + x = q_to_float(raw_uncalib_gyro_X, GYRO_Q1); + y = q_to_float(raw_uncalib_gyro_Y, GYRO_Q1); + z = q_to_float(raw_uncalib_gyro_Z, GYRO_Q1); + b_x = q_to_float(raw_bias_X, GYRO_Q1); + b_y = q_to_float(raw_bias_Y, GYRO_Q1); + b_z = q_to_float(raw_bias_Z, GYRO_Q1); + accuracy = uncalib_gyro_accuracy; +} + +/** + * @brief Get uncalibrated gyro x axis angular velocity measurement. + * + * @return The angular reported x axis angular velocity from uncalibrated gyro. + */ +float BNO08x::get_uncalibrated_gyro_X() +{ + return q_to_float(raw_uncalib_gyro_X, GYRO_Q1); +} + +/** + * @brief Get uncalibrated gyro Y axis angular velocity measurement. + * + * @return The angular reported Y axis angular velocity from uncalibrated gyro. + */ +float BNO08x::get_uncalibrated_gyro_Y() +{ + return q_to_float(raw_uncalib_gyro_Y, GYRO_Q1); +} + +/** + * @brief Get uncalibrated gyro Z axis angular velocity measurement. + * + * @return The angular reported Z axis angular velocity from uncalibrated gyro. + */ +float BNO08x::get_uncalibrated_gyro_Z() +{ + return q_to_float(raw_uncalib_gyro_Z, GYRO_Q1); +} + +/** + * @brief Get uncalibrated gyro x axis drift estimate. + * + * @return The angular reported x axis drift estimate. + */ +float BNO08x::get_uncalibrated_gyro_bias_X() +{ + return q_to_float(raw_bias_X, GYRO_Q1); +} + +/** + * @brief Get uncalibrated gyro Y axis drift estimate. + * + * @return The angular reported Y axis drift estimate. + */ +float BNO08x::get_uncalibrated_gyro_bias_Y() +{ + return q_to_float(raw_bias_Y, GYRO_Q1); +} + +/** + * @brief Get uncalibrated gyro Z axis drift estimate. + * + * @return The angular reported Z axis drift estimate. + */ +float BNO08x::get_uncalibrated_gyro_bias_Z() +{ + return q_to_float(raw_bias_Z, GYRO_Q1); +} + +/** + * @brief Get uncalibrated gyro accuracy. + * + * @return Accuracy of uncalibrated gyro. + */ +uint8_t BNO08x::get_uncalibrated_gyro_accuracy() +{ + return uncalib_gyro_accuracy; +} + + +/** + * @brief Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5.44) + * + * @param x Reference variable to save X axis angular velocity + * @param y Reference variable to save Y axis angular velocity + * @param z Reference variable to save Z axis angular velocity + * + * @return void, nothing to return + */ +void BNO08x::get_gyro_velocity(float &x, float &y, float &z) +{ + x = q_to_float(raw_velocity_gyro_X, ANGULAR_VELOCITY_Q1); + y = q_to_float(raw_velocity_gyro_Y, ANGULAR_VELOCITY_Q1); + z = q_to_float(raw_velocity_gyro_Z, ANGULAR_VELOCITY_Q1); +} + +/** + * @brief Get x axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44) + * + * @return The reported x axis angular velocity. + */ +float BNO08x::get_gyro_velocity_X() +{ + return q_to_float(raw_velocity_gyro_X, ANGULAR_VELOCITY_Q1); +} + +/** + * @brief Get y axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44) + * + * @return The reported y axis angular velocity. + */ +float BNO08x::get_gyro_velocity_Y() +{ + return q_to_float(raw_velocity_gyro_Y, ANGULAR_VELOCITY_Q1); +} + +/** + * @brief Get z axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44) + * + * @return The reported Z axis angular velocity. + */ +float BNO08x::get_gyro_velocity_Z() +{ + return q_to_float(raw_velocity_gyro_Z, ANGULAR_VELOCITY_Q1); +} + +/** + * @brief Get if tap has occured. + * + * @return 7 bit tap code indicated which axis taps have occurred. (See Ref. Manual 6.5.27) + */ +uint8_t BNO08x::get_tap_detector() +{ + uint8_t previous_tap_detector = tap_detector; + tap_detector = 0; //Reset so user code sees exactly one tap + return (previous_tap_detector); +} + +/** + * @brief Get the counted amount of steps. + * + * @return The current amount of counted steps. + */ +uint16_t BNO08x::get_step_count() +{ + return step_count; +} + +/** + * @brief Get the current stability classifier (Seee Ref. Manual 6.5.31) + * + * @return The current stability (0 = unknown, 1 = on table, 2 = stationary) + */ +int8_t BNO08x::get_stability_classifier() +{ + return stability_classifier; +} + +/** + * @brief Get the current activity classifier (Seee Ref. Manual 6.5.36) + * + * @return The current activity: + * 0 = unknown + * 1 = in vehicle + * 2 = on bicycle + * 3 = on foot + * 4 = still + * 5 = tilting + * 6 = walking + * 7 = runnning + * 8 = on stairs + */ +uint8_t BNO08x::get_activity_classifier() +{ + return activity_classifier; +} + +/** + * @brief Prints the most recently received SHTP header to serial console with ESP_LOG statement. + * + * @return void, nothing to return + */ +void BNO08x::print_header() +{ + //print most recent header + ESP_LOGI(TAG, "SHTP Header:\n\r" + " Raw 32 bit word: 0x%02X%02X%02X%02X\n\r" + " Packet Length: %d\n\r" + " Channel Number: %d\n\r" + " Sequence Number: %d\n\r" + " Channel Type: %s\n\r", + (int)packet_header_rx[0], + (int)packet_header_rx[1], + (int)packet_header_rx[2], + (int)packet_header_rx[3], + (int)(packet_length_rx+4), + (int)packet_header_rx[2], + (int)packet_header_rx[3], + (packet_header_rx[2] == 0) ? "Command" : + (packet_header_rx[2] == 1) ? "Executable" : + (packet_header_rx[2] == 2) ? "Control" : + (packet_header_rx[2] == 3) ? "Sensor-report" : + (packet_header_rx[2] == 4) ? "Wake-report" : + (packet_header_rx[2] == 5) ? "Gyro-vector" : "Unknown"); +} + +void BNO08x::print_packet() +{ + uint8_t i = 0; + uint16_t print_length = 0; + char packet_string[600]; + char byte_string[8]; + + if(packet_length_rx > 40) + print_length = 40; + else + print_length = packet_length_rx; + + sprintf(packet_string, " Body: \n\r "); + for(i = 0; i < print_length; i++) + { + sprintf(byte_string, " 0x%02X ", rx_buffer[i]); + strcat(packet_string, byte_string); + + if ((i + 1) % 6 == 0) // add a newline every 6 bytes + strcat(packet_string, "\n\r "); + + } + + + ESP_LOGI(TAG, "SHTP Header:\n\r" + " Raw 32 bit word: 0x%02X%02X%02X%02X\n\r" + " Packet Length: %d\n\r" + " Channel Number: %d\n\r" + " Sequence Number: %d\n\r" + " Channel Type: %s\n\r" + "%s", + (int)packet_header_rx[0], + (int)packet_header_rx[1], + (int)packet_header_rx[2], + (int)packet_header_rx[3], + (int)(packet_length_rx+4), + (int)packet_header_rx[2], + (int)packet_header_rx[3], + (packet_header_rx[2] == 0) ? "Command" : + (packet_header_rx[2] == 1) ? "Executable" : + (packet_header_rx[2] == 2) ? "Control" : + (packet_header_rx[2] == 3) ? "Sensor-report" : + (packet_header_rx[2] == 4) ? "Wake-report" : + (packet_header_rx[2] == 5) ? "Gyro-vector" : "Unknown", + packet_string); + + + +} + + +/** + * @brief Gets Q1 point from BNO08x FRS (flash record system). + * + * Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. + * + * @param record_ID Which record ID/ sensor to get Q1 value for. + * + * @return Q1 value for requested sensor. + */ +int16_t BNO08x::get_Q1(uint16_t record_ID) +{ + //Q1 is lower 16 bits of word 7 + return (uint16_t)(FRS_read_word(record_ID, 7) & 0xFFFF); +} + +/** + * @brief Gets Q2 point from BNO08x FRS (flash record system). + * + * Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. + * + * @param record_ID Which record ID/ sensor to get Q2 value for. + * + * @return Q2 value for requested sensor. + */ +int16_t BNO08x::get_Q2(uint16_t record_ID) +{ + //Q2 is upper 16 bits of word 7 + return (uint16_t)(FRS_read_word(record_ID, 7) >> 16U); +} + +/** + * @brief Gets Q3 point from BNO08x FRS (flash record system). + * + * Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. + * + * @param record_ID Which record ID/ sensor to get Q3 value for. + * + * @return Q3 value for requested sensor. + */ +int16_t BNO08x::get_Q3(uint16_t record_ID) +{ + //Q3 is upper 16 bits of word 8 + return (uint16_t)(FRS_read_word(record_ID, 8) >> 16U); +} + +/** + * @brief Gets resolution from BNO08x FRS (flash record system). + * + * @param record_ID Which record ID/ sensor to get resolution value for. + * + * @return The resolution value for the requested sensor. + */ +float BNO08x::get_resolution(uint16_t record_ID) +{ + int16_t Q = get_Q1(record_ID); //use same q as sensor's input report for range calc + + //resolution is word 2 + uint32_t value = FRS_read_word(record_ID, 2); + + return q_to_float(value, Q); //return resolution +} + +/** + * @brief Gets range from BNO08x FRS (flash record system). + * + * @param record_ID Which record ID/ sensor to get range value for. + * + * @return The range value for the requested sensor. + */ +float BNO08x::get_range(uint16_t record_ID) + { + int16_t Q = get_Q1(record_ID); //use same q as sensor's input report for range calc + + //resolution is word 1 + uint32_t value = FRS_read_word(record_ID, 1); + + return q_to_float(value, Q); //return range +} + +/** + * @brief Reads meta data word from BNO08x FRS (flash record system) given the record ID and word number. (See Ref. Manual 5.1 & 6.3.7) + * + * Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. + * + * @param record_ID Which record ID/ sensor to request meta data from. + * @param word_number Desired word to read. + * + * @return Requested meta data word, 0 if failed. + */ +uint32_t BNO08x::FRS_read_word(uint16_t record_ID, uint8_t word_number) +{ + if (FRS_read_data(record_ID, word_number, 1)) //start at desired word and only read one 1 word + return (meta_data[0]); + else + return 0; //FRS read failed +} + +/** + * @brief Requests meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.1 & 6.3.6) + * + * Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. + * + * @param record_ID Which record ID/ sensor to request meta data from. + * @param start_location Start byte location. + * @param words_to_read Length of words to read. + * + * @return True if read request acknowledged (HINT was asserted) + */ +bool BNO08x::FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size) +{ + memset(commands, 0, sizeof(commands)); + + commands[0] = SHTP_REPORT_FRS_READ_REQUEST; //FRS Read Request + commands[1] = 0; //Reserved + commands[2] = (read_offset >> 0) & 0xFF; //Read Offset LSB + commands[3] = (read_offset >> 8) & 0xFF; //Read Offset MSB + commands[4] = (record_ID >> 0) & 0xFF; //FRS Type LSB + commands[5] = (record_ID >> 8) & 0xFF; //FRS Type MSB + commands[6] = (block_size >> 0) & 0xFF; //Block size LSB + commands[7] = (block_size >> 8) & 0xFF; //Block size MSB + + //Transmit packet on channel 2, 8 bytes + queue_packet(CHANNEL_CONTROL, 8); + return wait_for_device_int(); +} + +/** + * @brief Read meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.1 & 6.3.7) + * + * Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. + * + * @param record_ID Which record ID/ sensor to request meta data from. + * @param start_location Start byte location. + * @param words_to_read Length of words to read. + * + * @return True if meta data read successfully. + */ +bool BNO08x::FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read) +{ + uint32_t data_0 = 0; + uint32_t data_1 = 0; + uint8_t data_length = 0; + uint8_t FRS_status = 0; + uint8_t attempt_count = 0; + uint16_t i = 0; + + if(FRS_read_request(record_ID, start_location, words_to_read)) + { + vTaskDelay(5/portTICK_PERIOD_MS); + for(attempt_count = 0; attempt_count < 10; attempt_count++) + { + if(wait_for_device_int()) + { + if(rx_buffer[0] != SHTP_REPORT_FRS_READ_RESPONSE) + return false; + + if (!(((((uint16_t)rx_buffer[13]) << 8) | rx_buffer[12]) == record_ID)) + return false; + } + + data_length = rx_buffer[1] >> 4; + FRS_status = rx_buffer[1] & 0x0F; + + data_0 = (uint32_t)rx_buffer[7] << 24 | (uint32_t)rx_buffer[6] << 16 | (uint32_t)rx_buffer[5] << 8 | (uint32_t)rx_buffer[4]; + data_1 = (uint32_t)rx_buffer[11] << 24 | (uint32_t)rx_buffer[10] << 16 | (uint32_t)rx_buffer[9] << 8 | (uint32_t)rx_buffer[8]; + + //save meta data words to their respective buffer + if (data_length > 0) + meta_data[i++] = data_0; + + if (data_length > 1) + meta_data[i++] = data_1; + + + if (i >= 9) + { + if (imu_config.debug_en) + ESP_LOGW(TAG, "meta_data array overrun, returning from FRS_read_request()"); + + return true; + } + + if (FRS_status == 3 || FRS_status == 6 || FRS_status == 7) + return true; + } + + } + + return false; +} + +/** + * @brief Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.5.4) + * + * @param report_ID ID of sensor report to be enabled. + * @param time_between_reports Desired time between reports in miliseconds. + * @param specific_config Specific config word (used with personal activity classifier) + * + * @return void, nothing to return + */ +void BNO08x::queue_feature_command(uint8_t report_ID, uint16_t time_between_reports, uint32_t specific_config) +{ + uint32_t us_between_reports = (uint32_t)time_between_reports * 1000UL; + memset(commands, 0, sizeof(commands)); + + commands[0] = SHTP_REPORT_SET_FEATURE_COMMAND; //Set feature command (See Ref. Manual 6.5.4) + commands[1] = report_ID; //Feature Report ID. 0x01 = Accelerometer, 0x05 = Rotation vector + commands[2] = 0; //Feature flags + commands[3] = 0; //Change sensitivity (LSB) + commands[4] = 0; //Change sensitivity (MSB) + commands[5] = (us_between_reports >> 0) & 0xFF; //Report interval (LSB) in microseconds. 0x7A120 = 500ms + commands[6] = (us_between_reports >> 8) & 0xFF; //Report interval + commands[7] = (us_between_reports >> 16) & 0xFF; //Report interval + commands[8] = (us_between_reports >> 24) & 0xFF; //Report interval (MSB) + commands[9] = 0; //Batch Interval (LSB) + commands[10] = 0; //Batch Interval + commands[11] = 0; //Batch Interval + commands[12] = 0; //Batch Interval (MSB) + commands[13] = (specific_config >> 0) & 0xFF; //Sensor-specific config (LSB) + commands[14] = (specific_config >> 8) & 0xFF; //Sensor-specific config + commands[15] = (specific_config >> 16) & 0xFF; //Sensor-specific config + commands[16] = (specific_config >> 24) & 0xFF; //Sensor-specific config (MSB) + + //Transmit packet on channel 2, 17 bytes + queue_packet(CHANNEL_CONTROL, 17); +} + +/** + * @brief Queues a packet containing a command related to zeroing sensor's axes. (See Ref. Manual 6.4.4.1) + * + * @param command Tare command to be sent. + * @param axis Specified axis (can be z or all at once) + * @param rotation_vector_basis Which rotation vector type to zero axes of, BNO08x saves seperate data for Rotation Vector, Gaming Rotation Vector, etc..) + * + * @return void, nothing to return + */ +void BNO08x::queue_tare_command(uint8_t command, uint8_t axis, uint8_t rotation_vector_basis) +{ + memset(commands, 0, sizeof(commands)); + + commands[3] = command; + + if(command == TARE_NOW) + { + commands[4] = axis; + commands[5] = rotation_vector_basis; + } + + + queue_command(COMMAND_TARE); +} + +/** + * @brief Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.5.4) + * + * @param report_ID ID of sensor report being requested. + * @param time_between_reports Desired time between reports. + * + * @return void, nothing to return + */ +void BNO08x::queue_feature_command(uint8_t report_ID, uint16_t time_between_reports) +{ + queue_feature_command(report_ID, time_between_reports, 0); //No specific config +} + +/** + * @brief Static function used to launch spi task. + * + * Used such that spi_task() can be non-static class member. + * + * @return void, nothing to return + */ +void BNO08x::spi_task_trampoline(void *arg) +{ + BNO08x *imu = (BNO08x *)arg; //cast argument received by xTaskCreate ("this" pointer to imu object created by constructor call) + imu->spi_task(); //launch spi task from object +} + +/** + * @brief Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x + * + * @return void, nothing to return + */ +void BNO08x::spi_task() +{ + while(1) + { + ulTaskNotifyTake(pdTRUE, portMAX_DELAY); //block until notified by ISR + xSemaphoreTake(tx_semaphore, portMAX_DELAY); //wait if queue_packet is executing + + if (tx_packet_queued != 0) + send_packet(); //send packet + else + receive_packet(); //receive packet + + int_asserted = true; //SPI completed, set interrupt asserted flag as true + + xSemaphoreGive(tx_semaphore); //give back the semaphore such that queue packet be blocked + } +} + +/** + * @brief HINT interrupt service routine, handles falling edge of BNO08x HINT pin. + * + * ISR that launches SPI task to perform transaction upon assertion of BNO08x interrupt pin. + * + * @return void, nothing to return + */ +void IRAM_ATTR BNO08x::hint_handler(void *arg) +{ + BaseType_t xHighPriorityTaskWoken = pdFALSE; + BNO08x *imu = (BNO08x *)arg; //cast argument received by gpio_isr_handler_add ("this" pointer to imu object created by constructor call) + + gpio_intr_disable(imu->imu_config.io_int); //disable interrupts + vTaskNotifyGiveFromISR(imu->spi_task_hdl, &xHighPriorityTaskWoken); //notify SPI task BNO08x is ready for servicing + portYIELD_FROM_ISR(xHighPriorityTaskWoken); //perform context switch if necessary +} diff --git a/BNO08x.hpp b/BNO08x.hpp new file mode 100644 index 0000000..773d664 --- /dev/null +++ b/BNO08x.hpp @@ -0,0 +1,367 @@ +#pragma once + +//standard library includes +#include +#include +#include +#include + +//esp-idf includes +#include "driver/gpio.h" +#include "esp_rom_gpio.h" +#include "driver/spi_common.h" +#include "driver/spi_master.h" +#include "freertos/FreeRTOS.h" +#include "freertos/task.h" +#include "freertos/semphr.h" +#include "esp_log.h" +#include "esp_timer.h" +#include "rom/ets_sys.h" + +/// @brief SHTP protocol channels +enum channels_t +{ + CHANNEL_COMMAND, + CHANNEL_EXECUTABLE, + CHANNEL_CONTROL, + CHANNEL_REPORTS, + CHANNEL_WAKE_REPORTS, + CHANNEL_GYRO +}; + +/// @brief Sensor accuracy returned during sensor calibration +enum sensor_accuracy_t +{ + LOW_ACCURACY = 1, + MED_ACCURACY, + HIGH_ACCURACY +}; + +/// @brief IMU configuration settings passed into constructor +typedef struct bno08x_config_t +{ + spi_host_device_t spi_peripheral; ///Table of Contents +
    +
  1. + About +
  2. +
  3. + Getting Started + +
  4. +
  5. Example
  6. +
  7. Example
  8. +
  9. Acknowledgements
  10. +
  11. License
  12. +
  13. Contact
  14. +
+ + +## About + +esp32_BNO08x is a C++ esp-idf v5.x component, intended to serve as a driver for both the BNO080 and BNO085 IMUs. +This library is heavy influenced by the SparkFun BNO080 Arduino Library, it is more or less a port. It supports access to all the same data that the BNO08x provides. +Currently, only SPI is supported, there is no plans to support I2C (esp32 has I2C driver silicone bug, leading to unpredictable behavior). +I may implement UART at some point in the future. + +## Getting Started +

(back to top)

+ +### Wiring +The default wiring is depicted below, it can be changed at driver initialization (see example section). +![image](esp32_BNO08x_wiring.png) +

(back to top)

+ +### Adding to Project +1. Create a "components" directory in the root workspace directory of your esp-idf project if it does not exist already. + + In workspace directory: + ```sh + mkdir components + ``` + + +2. Cd into the components directory and clone the esp32_BNO08x repo. + + ```sh + cd components + git clone https://github.com/myles-parfeniuk/esp32_BNO08x.git + ``` +

(back to top)

+ +### Example +```cpp +#include +#include "BNO08x.hpp" + +extern "C" void app_main(void) +{ + BNO08x imu; //create IMU object with default wiring scheme + + /* + //if a custom wiring scheme is desired: + //create config struct + bno08x_config_t imu_config; + imu_config.io_mos = GPIO_NUM_X; + imu_config.io_miso = GPIO_NUM_X; + //etc... + + BNO08x imu(imu_config); + */ + + imu.initialize(); //initialize IMU + + //enable gyro & game rotation vector + imu.enable_game_rotation_vector(100); + imu.enable_gyro(150); + + while(1) + { + //print absolute heading in degrees and angular velocity in Rad/s + if(imu.data_available()) + { + ESP_LOGW("Main", "Velocity: x: %.3f y: %.3f z: %.3f", imu.get_gyro_calibrated_velocity_X(), imu.get_gyro_calibrated_velocity_Y(), imu.get_gyro_calibrated_velocity_Z()); + ESP_LOGI("Main", "Euler Angle: pitch: %.3f roll: %.3f yaw: %.3f", imu.get_pitch_deg(), imu.get_roll_deg(), imu.get_yaw_deg()); + } + } + +} +``` +

(back to top)

+ +## Documentation +API documentation generated with doxygen can be found in the documentation directory of the master branch. +

(back to top)

+ +## Acknowledgements + +Special thanks to the original creators of the sparkfun BNO080 library. Developing this without a reference would have been much more time consuming. +https://github.com/sparkfun/SparkFun_BNO080_Arduino_Library + +Special thanks to Anton Babiy, aka hwBirdy007 for helping with debugging SPI. +https://github.com/hwBirdy007 + +

(back to top)

+ +## License + +Distributed under the MIT License. See `LICENSE.md` for more information. +

(back to top)

+ +## Contact + +Myles Parfeniuk - myles.parfenyuk@gmail.com + +Project Link: [https://github.com/myles-parfeniuk/esp32_BNO08x.git](https://github.com/myles-parfeniuk/esp32_BNO08x.git) +

(back to top)

\ No newline at end of file diff --git a/documentation/html/_b_n_o08x_8hpp_source.html b/documentation/html/_b_n_o08x_8hpp_source.html new file mode 100644 index 0000000..a619000 --- /dev/null +++ b/documentation/html/_b_n_o08x_8hpp_source.html @@ -0,0 +1,687 @@ + + + + + + + +esp32_BNO08x: D:/development/git/esp32_BNO08x/BNO08x.hpp Source File + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
BNO08x.hpp
+
+
+
1#pragma once
+
2
+
3//standard library includes
+
4#include <stdio.h>
+
5#include <cstring>
+
6#include <inttypes.h>
+
7#include <math.h>
+
8
+
9//esp-idf includes
+
10#include "driver/gpio.h"
+
11#include "esp_rom_gpio.h"
+
12#include "driver/spi_common.h"
+
13#include "driver/spi_master.h"
+
14#include "freertos/FreeRTOS.h"
+
15#include "freertos/task.h"
+
16#include "freertos/semphr.h"
+
17#include "esp_log.h"
+
18#include "esp_timer.h"
+
19#include "rom/ets_sys.h"
+
20
+
22enum channels_t
+
23{
+
24 CHANNEL_COMMAND,
+
25 CHANNEL_EXECUTABLE,
+
26 CHANNEL_CONTROL,
+
27 CHANNEL_REPORTS,
+
28 CHANNEL_WAKE_REPORTS,
+
29 CHANNEL_GYRO
+
30};
+
31
+
33enum sensor_accuracy_t
+
34{
+
35 LOW_ACCURACY = 1,
+
36 MED_ACCURACY,
+
37 HIGH_ACCURACY
+
38};
+
39
+
41typedef struct bno08x_config_t
+
42{
+
43 spi_host_device_t spi_peripheral;
+
44 gpio_num_t io_mosi;
+
45 gpio_num_t io_miso;
+
46 gpio_num_t io_sclk;
+
47 gpio_num_t io_cs;
+
48 gpio_num_t io_int;
+
49 gpio_num_t io_rst;
+
50 gpio_num_t io_wake;
+
51 uint64_t sclk_speed;
+
52 bool debug_en;
+
53
+ +
56 spi_peripheral(SPI3_HOST),
+
57 io_mosi(GPIO_NUM_23),
+
58 io_miso(GPIO_NUM_19),
+
59 io_sclk(GPIO_NUM_18),
+
60 io_cs(GPIO_NUM_33),
+
61 io_int(GPIO_NUM_26),
+
62 io_rst(GPIO_NUM_32),
+
63 io_wake(GPIO_NUM_4),
+
64 //sclk_speed(10000U), //clock slowed to see on AD2
+
65 sclk_speed(2000000U), //1MHz SCLK speed
+
66 debug_en(false)
+
67
+
68 {
+
69 }
+
70
+ +
72
+
73class BNO08x
+
74{
+
75 public:
+ +
77 bool initialize();
+
78
+
79 bool hard_reset();
+
80 bool soft_reset();
+
81 uint8_t get_reset_reason();
+
82 bool mode_sleep();
+
83 bool mode_on();
+
84
+
85 float q_to_float(int16_t fixed_point_value, uint8_t q_point);
+
86
+ +
88 void calibrate_all();
+ +
90 void calibrate_gyro();
+ + + + +
95 void end_calibration();
+
96 void save_calibration();
+
97
+
98 void enable_rotation_vector(uint16_t time_between_reports);
+
99 void enable_game_rotation_vector(uint16_t time_between_reports);
+
100 void enable_ARVR_stabilized_rotation_vector(uint16_t time_between_reports);
+
101 void enable_ARVR_stabilized_game_rotation_vector(uint16_t time_between_reports);
+
102 void enable_gyro_integrated_rotation_vector(uint16_t timeBetweenReports);
+
103 void enable_accelerometer(uint16_t time_between_reports);
+
104 void enable_linear_accelerometer(uint16_t time_between_reports);
+
105 void enable_gravity(uint16_t time_between_reports);
+
106 void enable_gyro(uint16_t time_between_reports);
+
107 void enable_uncalibrated_gyro(uint16_t time_between_reports);
+
108 void enable_magnetometer(uint16_t time_between_reports);
+
109 void enable_tap_detector(uint16_t time_between_reports);
+
110 void enable_step_counter(uint16_t time_between_reports);
+
111 void enable_stability_classifier(uint16_t time_between_reports);
+
112 void enable_activity_classifier(uint16_t time_between_reports, uint32_t activities_to_enable, uint8_t (&activity_confidence_vals)[9]);
+
113 void enable_raw_accelerometer(uint16_t time_between_reports);
+
114 void enable_raw_gyro(uint16_t time_between_reports);
+
115 void enable_raw_magnetometer(uint16_t time_between_reports);
+
116
+
117 void tare_now(uint8_t axis_sel = TARE_AXIS_ALL, uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR);
+
118 void save_tare();
+
119 void clear_tare();
+
120
+
121 bool data_available();
+
122 uint16_t parse_input_report();
+
123 uint16_t parse_command_report();
+
124 uint16_t get_readings();
+
125
+
126 uint32_t get_time_stamp();
+
127
+
128 void get_magf(float &x, float &y, float &z, uint8_t &accuracy);
+
129 float get_magf_X();
+
130 float get_magf_Y();
+
131 float get_magf_Z();
+
132 uint8_t get_magf_accuracy();
+
133
+
134 void get_gravity(float &x, float &y, float &z, uint8_t &accuracy);
+
135 float get_gravity_X();
+
136 float get_gravity_Y();
+
137 float get_gravity_Z();
+
138 uint8_t get_gravity_accuracy();
+
139
+
140 float get_roll();
+
141 float get_pitch();
+
142 float get_yaw();
+
143
+
144 float get_roll_deg();
+
145 float get_pitch_deg();
+
146 float get_yaw_deg();
+
147
+
148 void get_quat(float &i, float &j, float &k, float &real, float &rad_accuracy, uint8_t &accuracy);
+
149 float get_quat_I();
+
150 float get_quat_J();
+
151 float get_quat_K();
+
152 float get_quat_real();
+ +
154 uint8_t get_quat_accuracy();
+
155
+
156 void get_accel(float &x, float &y, float &z, uint8_t &accuracy);
+
157 float get_accel_X();
+
158 float get_accel_Y();
+
159 float get_accel_Z();
+
160 uint8_t get_accel_accuracy();
+
161
+
162 void get_linear_accel(float &x, float &y, float &z, uint8_t &accuracy);
+
163 float get_linear_accel_X();
+
164 float get_linear_accel_Y();
+
165 float get_linear_accel_Z();
+ +
167
+
168 int16_t get_raw_accel_X();
+
169 int16_t get_raw_accel_Y();
+
170 int16_t get_raw_accel_Z();
+
171
+
172 int16_t get_raw_gyro_X();
+
173 int16_t get_raw_gyro_Y();
+
174 int16_t get_raw_gyro_Z();
+
175
+
176 int16_t get_raw_magf_X();
+
177 int16_t get_raw_magf_Y();
+
178 int16_t get_raw_magf_Z();
+
179
+
180 void get_gyro_calibrated_velocity(float &x, float &y, float &z, uint8_t &accuracy);
+ + + +
184 uint8_t get_gyro_accuracy();
+
185
+
186 void get_uncalibrated_gyro(float &x, float &y, float &z, float &bx, float &by, float &bz, uint8_t &accuracy);
+ + + + + + + +
194
+
195 void get_gyro_velocity(float &x, float &y, float &z);
+
196 float get_gyro_velocity_X();
+
197 float get_gyro_velocity_Y();
+
198 float get_gyro_velocity_Z();
+
199
+
200 uint8_t get_tap_detector();
+
201 uint16_t get_step_count();
+ +
203 uint8_t get_activity_classifier();
+
204
+
205 void print_header();
+
206 void print_packet();
+
207
+
208 //Metadata functions
+
209 int16_t get_Q1(uint16_t record_ID);
+
210 int16_t get_Q2(uint16_t record_ID);
+
211 int16_t get_Q3(uint16_t record_ID);
+
212 float get_resolution(uint16_t record_ID);
+
213 float get_range(uint16_t record_ID);
+
214 uint32_t FRS_read_word(uint16_t record_ID, uint8_t word_number);
+
215 bool FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size);
+
216 bool FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read);
+
217
+
218 //Record IDs from figure 29, page 29 reference manual
+
219 //These are used to read the metadata for each sensor type
+
220 static const constexpr uint16_t FRS_RECORDID_ACCELEROMETER = 0xE302;
+
221 static const constexpr uint16_t FRS_RECORDID_GYROSCOPE_CALIBRATED = 0xE306;
+
222 static const constexpr uint16_t FRS_RECORDID_MAGNETIC_FIELD_CALIBRATED = 0xE309;
+
223 static const constexpr uint16_t FRS_RECORDID_ROTATION_VECTOR = 0xE30B;
+
224
+
225
+
226 private:
+
227 bool wait_for_device_int();
+
228 bool receive_packet();
+
229 void send_packet();
+
230 void queue_packet(uint8_t channel_number, uint8_t data_length);
+
231 void queue_command(uint8_t command);
+
232 void queue_feature_command(uint8_t report_ID, uint16_t time_between_reports);
+
233 void queue_feature_command(uint8_t report_ID, uint16_t time_between_reports, uint32_t specific_config);
+
234 void queue_calibrate_command(uint8_t _to_calibrate);
+
235 void queue_tare_command(uint8_t command, uint8_t axis = TARE_AXIS_ALL, uint8_t rotation_vector_basis = TARE_ROTATION_VECTOR);
+ +
237
+ +
239
+
240 volatile uint8_t tx_packet_queued;
+
241 SemaphoreHandle_t tx_semaphore;
+
242 uint8_t rx_buffer[300];
+
243 uint8_t tx_buffer[50];
+
244 uint8_t packet_header_rx[4];
+
245 uint8_t commands[20];
+
246 uint8_t sequence_number[6];
+
247 uint32_t meta_data[9];
+ +
249 uint16_t packet_length_tx = 0;
+
250 uint16_t packet_length_rx = 0;
+
251
+ +
253 spi_bus_config_t bus_config{};
+
254 spi_device_interface_config_t imu_spi_config{};
+
255 spi_device_handle_t spi_hdl{};
+
256 spi_transaction_t spi_transaction{};
+
257
+
258 //These are the raw sensor values (without Q applied) pulled from the user requested Input Report
+
259 uint32_t time_stamp;
+
260 uint16_t raw_accel_X, raw_accel_Y, raw_accel_Z, accel_accuracy;
+
261 uint16_t raw_lin_accel_X, raw_lin_accel_Y, raw_lin_accel_Z, accel_lin_accuracy;
+
262 uint16_t raw_gyro_X, raw_gyro_Y, raw_gyro_Z, gyro_accuracy;
+
263 uint16_t raw_quat_I, raw_quat_J, raw_quat_K, raw_quat_real, raw_quat_radian_accuracy, quat_accuracy;
+
264 uint16_t raw_velocity_gyro_X, raw_velocity_gyro_Y, raw_velocity_gyro_Z;
+
265 uint16_t gravity_X, gravity_Y, gravity_Z, gravity_accuracy;
+
266 uint16_t raw_uncalib_gyro_X, raw_uncalib_gyro_Y, raw_uncalib_gyro_Z, raw_bias_X, raw_bias_Y, raw_bias_Z, uncalib_gyro_accuracy;
+
267 uint16_t raw_magf_X, raw_magf_Y, raw_magf_Z, magf_accuracy;
+
268 uint8_t tap_detector;
+
269 uint16_t step_count;
+ + + + +
274 uint16_t mems_raw_accel_X, mems_raw_accel_Y, mems_raw_accel_Z;
+
275 uint16_t mems_raw_gyro_X, mems_raw_gyro_Y, mems_raw_gyro_Z;
+
276 uint16_t mems_raw_magf_X, mems_raw_magf_Y, mems_raw_magf_Z;
+
277
+
278 //spi task
+
279 TaskHandle_t spi_task_hdl;
+
280 static void spi_task_trampoline(void *arg);
+
281 void spi_task();
+
282
+
283 volatile bool int_asserted;
+
284 static void IRAM_ATTR hint_handler(void *arg);
+ +
286
+
287
+
288 static const constexpr int16_t ROTATION_VECTOR_Q1 = 14;
+
289 static const constexpr int16_t ROTATION_VECTOR_ACCURACY_Q1 = 12;
+
290 static const constexpr int16_t ACCELEROMETER_Q1 = 8;
+
291 static const constexpr int16_t LINEAR_ACCELEROMETER_Q1 = 8;
+
292 static const constexpr int16_t GYRO_Q1 = 9;
+
293 static const constexpr int16_t MAGNETOMETER_Q1 = 4;
+
294 static const constexpr int16_t ANGULAR_VELOCITY_Q1 = 10;
+
295 static const constexpr int16_t GRAVITY_Q1 = 8;
+
296
+
297 static const constexpr uint64_t HOST_INT_TIMEOUT_US = 150000ULL;
+
298
+
299 //Higher level calibration commands, used by queue_calibrate_command
+
300 static const constexpr uint8_t CALIBRATE_ACCEL = 0;
+
301 static const constexpr uint8_t CALIBRATE_GYRO = 1;
+
302 static const constexpr uint8_t CALIBRATE_MAG = 2;
+
303 static const constexpr uint8_t CALIBRATE_PLANAR_ACCEL = 3;
+
304 static const constexpr uint8_t CALIBRATE_ACCEL_GYRO_MAG = 4;
+
305 static const constexpr uint8_t CALIBRATE_STOP = 5;
+
306
+
307 //Command IDs (see Ref. Manual 6.4)
+
308 static const constexpr uint8_t COMMAND_ERRORS = 1;
+
309 static const constexpr uint8_t COMMAND_COUNTER = 2;
+
310 static const constexpr uint8_t COMMAND_TARE = 3;
+
311 static const constexpr uint8_t COMMAND_INITIALIZE = 4;
+
312 static const constexpr uint8_t COMMAND_DCD = 6;
+
313 static const constexpr uint8_t COMMAND_ME_CALIBRATE = 7;
+
314 static const constexpr uint8_t COMMAND_DCD_PERIOD_SAVE = 9;
+
315 static const constexpr uint8_t COMMAND_OSCILLATOR = 10;
+
316 static const constexpr uint8_t COMMAND_CLEAR_DCD = 11;
+
317
+
318 //SHTP channel 2 control report IDs, used in communication with sensor (See Ref. Manual 6.2)
+
319 static const constexpr uint8_t SHTP_REPORT_COMMAND_RESPONSE = 0xF1;
+
320 static const constexpr uint8_t SHTP_REPORT_COMMAND_REQUEST = 0xF2;
+
321 static const constexpr uint8_t SHTP_REPORT_FRS_READ_RESPONSE = 0xF3;
+
322 static const constexpr uint8_t SHTP_REPORT_FRS_READ_REQUEST = 0xF4;
+
323 static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_RESPONSE = 0xF8;
+
324 static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_REQUEST = 0xF9;
+
325 static const constexpr uint8_t SHTP_REPORT_BASE_TIMESTAMP = 0xFB;
+
326 static const constexpr uint8_t SHTP_REPORT_SET_FEATURE_COMMAND = 0xFD;
+
327
+
328
+
329 //Sensor report IDs, used when enabling and reading BNO08x reports
+
330 static const constexpr uint8_t SENSOR_REPORTID_ACCELEROMETER = 0x01;
+
331 static const constexpr uint8_t SENSOR_REPORTID_GYROSCOPE = 0x02;
+
332 static const constexpr uint8_t SENSOR_REPORTID_MAGNETIC_FIELD = 0x03;
+
333 static const constexpr uint8_t SENSOR_REPORTID_LINEAR_ACCELERATION = 0x04;
+
334 static const constexpr uint8_t SENSOR_REPORTID_ROTATION_VECTOR = 0x05;
+
335 static const constexpr uint8_t SENSOR_REPORTID_GRAVITY = 0x06;
+
336 static const constexpr uint8_t SENSOR_REPORTID_UNCALIBRATED_GYRO = 0x07;
+
337 static const constexpr uint8_t SENSOR_REPORTID_GAME_ROTATION_VECTOR = 0x08;
+
338 static const constexpr uint8_t SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR = 0x09;
+
339 static const constexpr uint8_t SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR = 0x2A;
+
340 static const constexpr uint8_t SENSOR_REPORTID_TAP_DETECTOR = 0x10;
+
341 static const constexpr uint8_t SENSOR_REPORTID_STEP_COUNTER = 0x11;
+
342 static const constexpr uint8_t SENSOR_REPORTID_STABILITY_CLASSIFIER = 0x13;
+
343 static const constexpr uint8_t SENSOR_REPORTID_RAW_ACCELEROMETER = 0x14;
+
344 static const constexpr uint8_t SENSOR_REPORTID_RAW_GYROSCOPE = 0x15;
+
345 static const constexpr uint8_t SENSOR_REPORTID_RAW_MAGNETOMETER = 0x16;
+
346 static const constexpr uint8_t SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER = 0x1E;
+
347 static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR = 0x28;
+
348 static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 0x29;
+
349
+
350 //Tare commands used by queue_tare_command
+
351 static const constexpr uint8_t TARE_NOW = 0;
+
352 static const constexpr uint8_t TARE_PERSIST = 1;
+
353 static const constexpr uint8_t TARE_SET_REORIENTATION = 2;
+
354
+
355 static const constexpr uint8_t TARE_AXIS_ALL = 0x07;
+
356 static const constexpr uint8_t TARE_AXIS_Z = 0x04;
+
357
+
358 //Which rotation vector to tare, BNO08x saves them seperately
+
359 static const constexpr uint8_t TARE_ROTATION_VECTOR = 0;
+
360 static const constexpr uint8_t TARE_GAME_ROTATION_VECTOR = 1;
+
361 static const constexpr uint8_t TARE_GEOMAGNETIC_ROTATION_VECTOR = 2;
+
362 static const constexpr uint8_t TARE_GYRO_INTEGRATED_ROTATION_VECTOR = 3;
+
363 static const constexpr uint8_t TARE_AR_VR_STABILIZED_ROTATION_VECTOR = 4;
+
364 static const constexpr uint8_t TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 5;
+
365
+
366 static const constexpr char *TAG = "BNO08x";
+
367};
+
Definition BNO08x.hpp:74
+
static const constexpr uint8_t SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER
See SH2 Ref. Manual 6.5.36.
Definition BNO08x.hpp:346
+
static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_RESPONSE
See SH2 Ref. Manual 6.3.2.
Definition BNO08x.hpp:323
+
void enable_ARVR_stabilized_rotation_vector(uint16_t time_between_reports)
Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6....
Definition BNO08x.cpp:1022
+
static const constexpr int16_t ACCELEROMETER_Q1
Acceleration Q point (See SH-2 Ref. Manual 6.5.9)
Definition BNO08x.hpp:290
+
uint16_t uncalib_gyro_accuracy
Uncalibrated gyro reading (See SH-2 Ref. Manual 6.5.14)
Definition BNO08x.hpp:266
+
void print_header()
Prints the most recently received SHTP header to serial console with ESP_LOG statement.
Definition BNO08x.cpp:2074
+
void enable_activity_classifier(uint16_t time_between_reports, uint32_t activities_to_enable, uint8_t(&activity_confidence_vals)[9])
Sends command to enable activity classifier reports (See Ref. Manual 6.5.36)
Definition BNO08x.cpp:1180
+
void enable_gyro_integrated_rotation_vector(uint16_t timeBetweenReports)
Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6....
Definition BNO08x.cpp:1048
+
static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.43.
Definition BNO08x.hpp:348
+
static const constexpr uint8_t COMMAND_TARE
Command and response to tare command (See Sh2 Ref. Manual 6.4.4)
Definition BNO08x.hpp:310
+
float get_accel_Z()
Get z axis acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:1656
+
float get_uncalibrated_gyro_Z()
Get uncalibrated gyro Z axis angular velocity measurement.
Definition BNO08x.cpp:1926
+
static const constexpr int16_t ROTATION_VECTOR_Q1
Rotation vector Q point (See SH-2 Ref. Manual 6.5.18)
Definition BNO08x.hpp:288
+
static void spi_task_trampoline(void *arg)
Static function used to launch spi task.
Definition BNO08x.cpp:2421
+
int8_t get_stability_classifier()
Get the current stability classifier (Seee Ref. Manual 6.5.31)
Definition BNO08x.cpp:2045
+
void send_packet()
Sends a queued SHTP packet via SPI.
Definition BNO08x.cpp:421
+
float get_range(uint16_t record_ID)
Gets range from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2218
+
float get_linear_accel_Y()
Get y axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
Definition BNO08x.cpp:1704
+
float get_magf_X()
Get X component of magnetic field vector.
Definition BNO08x.cpp:1314
+
static const constexpr uint8_t TARE_PERSIST
See SH2 Ref. Manual 6.4.4.2.
Definition BNO08x.hpp:352
+
uint8_t tap_detector
Tap detector reading (See SH-2 Ref. Manual 6.5.27)
Definition BNO08x.hpp:268
+
uint8_t get_reset_reason()
Get the reason for the most recent reset.
Definition BNO08x.cpp:269
+
float get_quat_I()
Get I component of reported quaternion.
Definition BNO08x.cpp:1553
+
int16_t get_Q3(uint16_t record_ID)
Gets Q3 point from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2188
+
float get_gyro_calibrated_velocity_Z()
Get calibrated gyro z axis angular velocity measurement.
Definition BNO08x.cpp:1862
+
void queue_command(uint8_t command)
Queues a packet containing a command.
Definition BNO08x.cpp:444
+
bool mode_sleep()
Puts BNO08x sensor into sleep/low power mode using executable channel.
Definition BNO08x.cpp:315
+
float get_uncalibrated_gyro_Y()
Get uncalibrated gyro Y axis angular velocity measurement.
Definition BNO08x.cpp:1916
+
uint8_t stability_classifier
Stability status reading (See SH-2 Ref. Manual 6.5.31)
Definition BNO08x.hpp:270
+
float get_pitch()
Get the reported rotation about y axis.
Definition BNO08x.cpp:1443
+
void get_uncalibrated_gyro(float &x, float &y, float &z, float &bx, float &by, float &bz, uint8_t &accuracy)
Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is giv...
Definition BNO08x.cpp:1890
+
void calibrate_planar_accelerometer()
Sends command to calibrate planar accelerometer.
Definition BNO08x.cpp:518
+
static const constexpr uint8_t SHTP_REPORT_SET_FEATURE_COMMAND
See SH2 Ref. Manual 6.5.4.
Definition BNO08x.hpp:326
+
void enable_accelerometer(uint16_t time_between_reports)
Sends command to enable accelerometer reports (See Ref. Manual 6.5.9)
Definition BNO08x.cpp:1061
+
float get_resolution(uint16_t record_ID)
Gets resolution from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2201
+
int16_t get_raw_accel_X()
Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref....
Definition BNO08x.cpp:1734
+
static const constexpr uint8_t SHTP_REPORT_COMMAND_RESPONSE
See SH2 Ref. Manual 6.3.9.
Definition BNO08x.hpp:319
+
static const constexpr uint8_t TARE_AXIS_ALL
Tare all axes (used with tare now command)
Definition BNO08x.hpp:355
+
static const constexpr uint8_t TARE_GEOMAGNETIC_ROTATION_VECTOR
tare geomagnetic rotation vector
Definition BNO08x.hpp:361
+
uint8_t get_quat_accuracy()
Get accuracy of reported quaternion.
Definition BNO08x.cpp:1608
+
static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.42.
Definition BNO08x.hpp:347
+
static const constexpr uint8_t TARE_NOW
See SH2 Ref. Manual 6.4.4.1.
Definition BNO08x.hpp:351
+
uint32_t FRS_read_word(uint16_t record_ID, uint8_t word_number)
Reads meta data word from BNO08x FRS (flash record system) given the record ID and word number....
Definition BNO08x.cpp:2238
+
float q_to_float(int16_t fixed_point_value, uint8_t q_point)
Converts a register value to a float using its associated Q point. (See https://en....
Definition BNO08x.cpp:1273
+
float get_uncalibrated_gyro_X()
Get uncalibrated gyro x axis angular velocity measurement.
Definition BNO08x.cpp:1906
+
bool hard_reset()
Hard resets BNO08x sensor.
Definition BNO08x.cpp:225
+
static const constexpr uint8_t SENSOR_REPORTID_GYROSCOPE
See SH2 Ref. Manual 6.5.13.
Definition BNO08x.hpp:331
+
int16_t get_raw_magf_Y()
Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1804
+
static const constexpr char * TAG
Class tag used for serial print statements.
Definition BNO08x.hpp:366
+
void enable_gravity(uint16_t time_between_reports)
Sends command to enable gravity reading reports (See Ref. Manual 6.5.11)
Definition BNO08x.cpp:1087
+
int16_t get_raw_gyro_Z()
Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1784
+
void spi_task()
Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x.
Definition BNO08x.cpp:2432
+
static const constexpr uint8_t COMMAND_OSCILLATOR
Retrieve oscillator type command (See SH2 Ref. Manual 6.4)
Definition BNO08x.hpp:315
+
static const constexpr uint8_t COMMAND_INITIALIZE
Reinitialize sensor hub components See (SH2 Ref. Manual 6.4.5)
Definition BNO08x.hpp:311
+
static const constexpr uint8_t TARE_AR_VR_STABILIZED_ROTATION_VECTOR
Tare ARVR stabilized rotation vector.
Definition BNO08x.hpp:363
+
uint8_t get_uncalibrated_gyro_accuracy()
Get uncalibrated gyro accuracy.
Definition BNO08x.cpp:1966
+
uint16_t accel_accuracy
Raw acceleration readings (See SH-2 Ref. Manual 6.5.8)
Definition BNO08x.hpp:260
+
uint8_t get_linear_accel_accuracy()
Get accuracy of linear acceleration.
Definition BNO08x.cpp:1724
+
void get_magf(float &x, float &y, float &z, uint8_t &accuracy)
Get the full magnetic field vector.
Definition BNO08x.cpp:1301
+
uint16_t accel_lin_accuracy
Raw linear acceleration (See SH-2 Ref. Manual 6.5.10)
Definition BNO08x.hpp:261
+
uint16_t quat_accuracy
Raw quaternion reading (See SH-2 Ref. Manual 6.5.44)
Definition BNO08x.hpp:263
+
bool data_available()
Checks if BNO08x has asserted interrupt and sent data.
Definition BNO08x.cpp:725
+
uint16_t parse_command_report()
Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)
Definition BNO08x.cpp:966
+
void get_gravity(float &x, float &y, float &z, uint8_t &accuracy)
Get full reported gravity vector, units in m/s^2.
Definition BNO08x.cpp:1362
+
uint8_t get_accel_accuracy()
Get accuracy of linear acceleration.
Definition BNO08x.cpp:1666
+
bool FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read)
Read meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other...
Definition BNO08x.cpp:2286
+
spi_device_interface_config_t imu_spi_config
SPI slave device settings.
Definition BNO08x.hpp:254
+
static const constexpr uint8_t SENSOR_REPORTID_TAP_DETECTOR
See SH2 Ref. Manual 6.5.27.
Definition BNO08x.hpp:340
+
int16_t get_Q1(uint16_t record_ID)
Gets Q1 point from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2158
+
void tare_now(uint8_t axis_sel=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
Sends command to tare an axis (See Ref. Manual 6.4.4.1)
Definition BNO08x.cpp:1234
+
static const constexpr uint8_t SENSOR_REPORTID_ACCELEROMETER
See SH2 Ref. Manual 6.5.9.
Definition BNO08x.hpp:330
+
uint8_t get_tap_detector()
Get if tap has occured.
Definition BNO08x.cpp:2023
+
uint8_t get_magf_accuracy()
Get accuracy of reported magnetic field vector.
Definition BNO08x.cpp:1347
+
static bool isr_service_installed
true of the isr service has been installed, only has to be done once regardless of how many devices a...
Definition BNO08x.hpp:285
+
volatile bool int_asserted
Interrupt asserted flag, sets true after hint_handler ISR launches SPI task and it has run to complet...
Definition BNO08x.hpp:283
+
void queue_tare_command(uint8_t command, uint8_t axis=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
Queues a packet containing a command related to zeroing sensor's axes. (See Ref. Manual 6....
Definition BNO08x.cpp:2385
+
void get_gyro_calibrated_velocity(float &x, float &y, float &z, uint8_t &accuracy)
Get full rotational velocity with drift compensation (units in Rad/s).
Definition BNO08x.cpp:1829
+
static const constexpr uint8_t COMMAND_CLEAR_DCD
Clear DCD & Reset command (See SH2 Ref. Manual 6.4)
Definition BNO08x.hpp:316
+
uint8_t get_activity_classifier()
Get the current activity classifier (Seee Ref. Manual 6.5.36)
Definition BNO08x.cpp:2064
+
float get_uncalibrated_gyro_bias_Z()
Get uncalibrated gyro Z axis drift estimate.
Definition BNO08x.cpp:1956
+
void get_quat(float &i, float &j, float &k, float &real, float &rad_accuracy, uint8_t &accuracy)
Get the full quaternion reading.
Definition BNO08x.cpp:1538
+
void enable_stability_classifier(uint16_t time_between_reports)
Sends command to enable activity stability classifier reports (See Ref. Manual 6.5....
Definition BNO08x.cpp:1165
+
static const constexpr uint8_t SENSOR_REPORTID_LINEAR_ACCELERATION
See SH2 Ref. Manual 6.5.10.
Definition BNO08x.hpp:333
+
static const constexpr uint64_t HOST_INT_TIMEOUT_US
Max wait between HINT being asserted by BNO08x before transaction is considered failed.
Definition BNO08x.hpp:297
+
static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_REQUEST
See SH2 Ref. Manual 6.3.1.
Definition BNO08x.hpp:324
+
float get_gravity_Z()
Get the reported z axis gravity.
Definition BNO08x.cpp:1395
+
static const constexpr uint8_t CALIBRATE_STOP
Stop calibration command used by queue_calibrate_command.
Definition BNO08x.hpp:305
+
uint16_t mems_raw_accel_Z
Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.5.8)
Definition BNO08x.hpp:274
+
static const constexpr uint8_t TARE_SET_REORIENTATION
See SH2 Ref. Manual 6.4.4.3.
Definition BNO08x.hpp:353
+
float get_quat_real()
Get real component of reported quaternion.
Definition BNO08x.cpp:1586
+
volatile uint8_t tx_packet_queued
Whether or not a packet is currently waiting to be sent, a queued packet is sent on assertion of BNO0...
Definition BNO08x.hpp:240
+
TaskHandle_t spi_task_hdl
SPI task handle.
Definition BNO08x.hpp:279
+
float get_quat_radian_accuracy()
Get radian accuracy of reported quaternion.
Definition BNO08x.cpp:1597
+
static bno08x_config_t default_imu_config
default imu config settings
Definition BNO08x.hpp:238
+
void enable_game_rotation_vector(uint16_t time_between_reports)
Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19)
Definition BNO08x.cpp:996
+
float get_yaw()
Get the reported rotation about z axis.
Definition BNO08x.cpp:1473
+
void queue_packet(uint8_t channel_number, uint8_t data_length)
Queues an SHTP packet to be sent via SPI.
Definition BNO08x.cpp:390
+
void queue_feature_command(uint8_t report_ID, uint16_t time_between_reports)
Queues a packet containing a command with a request for sensor reports, reported periodically....
Definition BNO08x.cpp:2409
+
static const constexpr uint8_t SENSOR_REPORTID_MAGNETIC_FIELD
See SH2 Ref. Manual 6.5.16.
Definition BNO08x.hpp:332
+
uint16_t packet_length_tx
Packet length to be sent with send_packet()
Definition BNO08x.hpp:249
+
float get_roll_deg()
Get the reported rotation about x axis.
Definition BNO08x.cpp:1500
+
int16_t get_raw_accel_Z()
Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref....
Definition BNO08x.cpp:1754
+
bool calibration_complete()
Returns true if calibration has completed.
Definition BNO08x.cpp:597
+
float get_uncalibrated_gyro_bias_Y()
Get uncalibrated gyro Y axis drift estimate.
Definition BNO08x.cpp:1946
+
static const constexpr uint8_t SHTP_REPORT_FRS_READ_REQUEST
See SH2 Ref. Manual 6.3.6.
Definition BNO08x.hpp:322
+
uint8_t tx_buffer[50]
buffer used for sending packet with send_packet()
Definition BNO08x.hpp:243
+
uint8_t activity_classifier
Activity status reading (See SH-2 Ref. Manual 6.5.36)
Definition BNO08x.hpp:271
+
void enable_gyro(uint16_t time_between_reports)
Sends command to enable gyro reports (See Ref. Manual 6.5.13)
Definition BNO08x.cpp:1100
+
float get_linear_accel_X()
Get x axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
Definition BNO08x.cpp:1694
+
static const constexpr uint8_t COMMAND_DCD_PERIOD_SAVE
Configure DCD periodic saving (See SH2 Ref. Manual 6.4)
Definition BNO08x.hpp:314
+
uint8_t rx_buffer[300]
buffer used to receive packet with receive_packet()
Definition BNO08x.hpp:242
+
uint16_t parse_input_report()
Parses received input report sent by BNO08x.
Definition BNO08x.cpp:788
+
uint32_t meta_data[9]
First 9 bytes of meta data returned from FRS read operation (we don't really need the rest) (See Ref....
Definition BNO08x.hpp:247
+
static void IRAM_ATTR hint_handler(void *arg)
HINT interrupt service routine, handles falling edge of BNO08x HINT pin.
Definition BNO08x.cpp:2457
+
uint8_t get_gyro_accuracy()
Get calibrated gyro accuracy.
Definition BNO08x.cpp:1872
+
float get_magf_Y()
Get Y component of magnetic field vector.
Definition BNO08x.cpp:1325
+
static const constexpr uint8_t COMMAND_ME_CALIBRATE
Command and response to configure ME calibration (See SH2 Ref. Manual 6.4.7)
Definition BNO08x.hpp:313
+
float get_gravity_X()
Get the reported x axis gravity.
Definition BNO08x.cpp:1375
+
float get_roll()
Get the reported rotation about x axis.
Definition BNO08x.cpp:1415
+
float get_gravity_Y()
Get the reported y axis gravity.
Definition BNO08x.cpp:1385
+
static const constexpr uint8_t SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.44.
Definition BNO08x.hpp:339
+
static const constexpr uint8_t TARE_ROTATION_VECTOR
Tare rotation vector.
Definition BNO08x.hpp:359
+
uint8_t packet_header_rx[4]
SHTP header received with receive_packet()
Definition BNO08x.hpp:244
+
uint16_t mems_raw_magf_Z
Raw magnetometer (compass) readings from MEMS sensor (See SH-2 Ref. Manual 6.5.15)
Definition BNO08x.hpp:276
+
void enable_tap_detector(uint16_t time_between_reports)
Sends command to enable tap detector reports (See Ref. Manual 6.5.27)
Definition BNO08x.cpp:1139
+
static const constexpr int16_t ROTATION_VECTOR_ACCURACY_Q1
Rotation vector accuracy estimate Q point (See SH-2 Ref. Manual 6.5.18)
Definition BNO08x.hpp:289
+
void get_accel(float &x, float &y, float &z, uint8_t &accuracy)
Get full acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:1623
+
int16_t get_Q2(uint16_t record_ID)
Gets Q2 point from BNO08x FRS (flash record system).
Definition BNO08x.cpp:2173
+
static const constexpr uint8_t CALIBRATE_PLANAR_ACCEL
Calibrate planar acceleration command used by queue_calibrate_command.
Definition BNO08x.hpp:303
+
int16_t get_raw_accel_Y()
Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref....
Definition BNO08x.cpp:1744
+
bool soft_reset()
Soft resets BNO08x sensor using executable channel.
Definition BNO08x.cpp:247
+
spi_bus_config_t bus_config
SPI bus GPIO configuration settings.
Definition BNO08x.hpp:253
+
bool wait_for_device_int()
Re-enables interrupts and waits for BNO08x to assert HINT pin.
Definition BNO08x.cpp:191
+
uint16_t gyro_accuracy
Raw gyro reading (See SH-2 Ref. Manual 6.5.13)
Definition BNO08x.hpp:262
+
int16_t get_raw_magf_Z()
Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1814
+
void calibrate_gyro()
Sends command to calibrate gyro.
Definition BNO08x.cpp:494
+
uint16_t get_readings()
Waits for BNO08x HINT pin to assert, and parses the received data.
Definition BNO08x.cpp:735
+
static const constexpr uint8_t TARE_GYRO_INTEGRATED_ROTATION_VECTOR
Tare gyro integrated rotation vector.
Definition BNO08x.hpp:362
+
float get_quat_K()
Get K component of reported quaternion.
Definition BNO08x.cpp:1575
+
float get_quat_J()
Get J component of reported quaternion.
Definition BNO08x.cpp:1564
+
static const constexpr int16_t MAGNETOMETER_Q1
Magnetometer Q point (See SH-2 Ref. Manual 6.5.16)
Definition BNO08x.hpp:293
+
void save_calibration()
Sends command to save internal calibration data (See Ref. Manual 6.4.7).
Definition BNO08x.cpp:622
+
static const constexpr int16_t GYRO_Q1
Gyro Q point (See SH-2 Ref. Manual 6.5.13)
Definition BNO08x.hpp:292
+
uint8_t sequence_number[6]
Sequence num of each com channel, 6 in total.
Definition BNO08x.hpp:246
+
static const constexpr uint8_t SENSOR_REPORTID_RAW_ACCELEROMETER
See SH2 Ref. Manual 6.5.8.
Definition BNO08x.hpp:343
+
static const constexpr uint8_t SENSOR_REPORTID_RAW_GYROSCOPE
See SH2 Ref. Manual 6.5.12.
Definition BNO08x.hpp:344
+
static const constexpr int16_t ANGULAR_VELOCITY_Q1
Angular velocity Q point (See SH-2 Ref. Manual 6.5.44)
Definition BNO08x.hpp:294
+
static const constexpr uint8_t SENSOR_REPORTID_STEP_COUNTER
See SH2 Ref. Manual 6.5.29.
Definition BNO08x.hpp:341
+
static const constexpr uint8_t SENSOR_REPORTID_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.18.
Definition BNO08x.hpp:334
+
static const constexpr uint8_t SHTP_REPORT_COMMAND_REQUEST
See SH2 Ref. Manual 6.3.8.
Definition BNO08x.hpp:320
+
static const constexpr uint8_t SENSOR_REPORTID_GAME_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.19.
Definition BNO08x.hpp:337
+
uint16_t raw_velocity_gyro_Z
Raw gyro angular velocity reading (See SH-2 Ref. Manual 6.5.44)
Definition BNO08x.hpp:264
+
float get_magf_Z()
Get Z component of magnetic field vector.
Definition BNO08x.cpp:1336
+
void queue_request_product_id_command()
Queues a packet containing the request product ID command.
Definition BNO08x.cpp:458
+
float get_gyro_calibrated_velocity_X()
Get calibrated gyro x axis angular velocity measurement.
Definition BNO08x.cpp:1842
+
static const constexpr uint8_t SENSOR_REPORTID_UNCALIBRATED_GYRO
See SH2 Ref. Manual 6.5.14.
Definition BNO08x.hpp:336
+
static const constexpr uint8_t TARE_GAME_ROTATION_VECTOR
Tare game rotation vector.
Definition BNO08x.hpp:360
+
uint32_t time_stamp
Report timestamp (see datasheet 1.3.5.3)
Definition BNO08x.hpp:259
+
float get_accel_X()
Get x axis acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:1636
+
void enable_rotation_vector(uint16_t time_between_reports)
Sends command to enable rotation vector reports (See Ref. Manual 6.5.18)
Definition BNO08x.cpp:1009
+
static const constexpr uint8_t CALIBRATE_MAG
Calibrate magnetometer command used by queue_calibrate_command.
Definition BNO08x.hpp:302
+
spi_transaction_t spi_transaction
SPI transaction handle.
Definition BNO08x.hpp:256
+
bool mode_on()
Turns on/ brings BNO08x sensor out of sleep mode using executable channel.
Definition BNO08x.cpp:293
+
uint8_t command_sequence_number
Sequence num of command, sent within command packet.
Definition BNO08x.hpp:248
+
void calibrate_magnetometer()
Sends command to calibrate magnetometer.
Definition BNO08x.cpp:506
+
uint16_t mems_raw_gyro_Z
Raw gyro readings from MEMS sensor (See SH-2 Ref. Manual 6.5.12)
Definition BNO08x.hpp:275
+
uint16_t magf_accuracy
Calibrated magnetic field reading in uTesla (See SH-2 Ref. Manual 6.5.16)
Definition BNO08x.hpp:267
+
static const constexpr uint8_t SENSOR_REPORTID_RAW_MAGNETOMETER
See SH2 Ref. Manual 6.5.15.
Definition BNO08x.hpp:345
+
void enable_uncalibrated_gyro(uint16_t time_between_reports)
Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.5.14)
Definition BNO08x.cpp:1113
+
void end_calibration()
Sends command to end calibration procedure.
Definition BNO08x.cpp:610
+
uint8_t commands[20]
Command to be sent with send_packet()
Definition BNO08x.hpp:245
+
spi_device_handle_t spi_hdl
SPI device handle.
Definition BNO08x.hpp:255
+
uint8_t get_gravity_accuracy()
Get the reported gravity accuracy.
Definition BNO08x.cpp:1405
+
float get_gyro_velocity_Y()
Get y axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6....
Definition BNO08x.cpp:2003
+
float get_gyro_velocity_X()
Get x axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6....
Definition BNO08x.cpp:1993
+
static const constexpr uint8_t CALIBRATE_ACCEL
Calibrate accelerometer command used by queue_calibrate_command.
Definition BNO08x.hpp:300
+
void enable_magnetometer(uint16_t time_between_reports)
Sends command to enable magnetometer reports (See Ref. Manual 6.5.16)
Definition BNO08x.cpp:1126
+
void queue_calibrate_command(uint8_t _to_calibrate)
Queues a packet containing a command to calibrate the specified sensor.
Definition BNO08x.cpp:532
+
static const constexpr int16_t LINEAR_ACCELEROMETER_Q1
Linear acceleration Q point (See SH-2 Ref. Manual 6.5.10)
Definition BNO08x.hpp:291
+
void enable_raw_magnetometer(uint16_t time_between_reports)
Sends command to enable raw magnetometer reports (See Ref. Manual 6.5.15)
Definition BNO08x.cpp:1220
+
uint8_t calibration_status
Calibration status of device (See SH-2 Ref. Manual 6.4.7.1 & 6.4.7.2)
Definition BNO08x.hpp:273
+
float get_uncalibrated_gyro_bias_X()
Get uncalibrated gyro x axis drift estimate.
Definition BNO08x.cpp:1936
+
void enable_linear_accelerometer(uint16_t time_between_reports)
Sends command to enable linear accelerometer reports (See Ref. Manual 6.5.10)
Definition BNO08x.cpp:1074
+
float get_gyro_calibrated_velocity_Y()
Get calibrated gyro y axis angular velocity measurement.
Definition BNO08x.cpp:1852
+
void enable_step_counter(uint16_t time_between_reports)
Sends command to enable step counter reports (See Ref. Manual 6.5.29)
Definition BNO08x.cpp:1152
+
void get_linear_accel(float &x, float &y, float &z, uint8_t &accuracy)
Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2).
Definition BNO08x.cpp:1681
+
void enable_raw_accelerometer(uint16_t time_between_reports)
Sends command to enable raw accelerometer reports (See Ref. Manual 6.5.8)
Definition BNO08x.cpp:1194
+
uint16_t step_count
Step counter reading (See SH-2 Ref. Manual 6.5.29)
Definition BNO08x.hpp:269
+
uint32_t get_time_stamp()
Return timestamp of most recent report.
Definition BNO08x.cpp:1286
+
void enable_ARVR_stabilized_game_rotation_vector(uint16_t time_between_reports)
Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6....
Definition BNO08x.cpp:1035
+
uint16_t get_step_count()
Get the counted amount of steps.
Definition BNO08x.cpp:2035
+
int16_t get_raw_magf_X()
Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1794
+
bool FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size)
Requests meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and o...
Definition BNO08x.cpp:2257
+
uint16_t gravity_accuracy
Gravity reading in m/s^2 (See SH-2 Ref. Manual 6.5.11)
Definition BNO08x.hpp:265
+
static const constexpr int16_t GRAVITY_Q1
Gravity Q point (See SH-2 Ref. Manual 6.5.11)
Definition BNO08x.hpp:295
+
float get_gyro_velocity_Z()
Get z axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6....
Definition BNO08x.cpp:2013
+
static const constexpr uint8_t SHTP_REPORT_BASE_TIMESTAMP
See SH2 Ref. Manual 7.2.1.
Definition BNO08x.hpp:325
+
bool receive_packet()
Receives a SHTP packet via SPI.
Definition BNO08x.cpp:337
+
bool run_full_calibration_routine()
Runs full calibration routine.
Definition BNO08x.cpp:640
+
bool initialize()
Initializes BNO08x sensor.
Definition BNO08x.cpp:114
+
static const constexpr uint8_t CALIBRATE_GYRO
Calibrate gyro command used by queue_calibrate_command.
Definition BNO08x.hpp:301
+
static const constexpr uint8_t SHTP_REPORT_FRS_READ_RESPONSE
See SH2 Ref. Manual 6.3.7.
Definition BNO08x.hpp:321
+
static const constexpr uint8_t SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR
See SH2 Ref. Manual 6.5.20.
Definition BNO08x.hpp:338
+
static const constexpr uint8_t TARE_AXIS_Z
Tar yaw axis only (used with tare now command)
Definition BNO08x.hpp:356
+
static const constexpr uint8_t TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR
Tare ARVR stabilized game rotation vector.
Definition BNO08x.hpp:364
+
bno08x_config_t imu_config
IMU configuration settings.
Definition BNO08x.hpp:252
+
SemaphoreHandle_t tx_semaphore
Mutex semaphore used to prevent sending or receiving of packets if packet is currently being queued.
Definition BNO08x.hpp:241
+
static const constexpr uint8_t SENSOR_REPORTID_GRAVITY
See SH2 Ref. Manual 6.5.11.
Definition BNO08x.hpp:335
+
void calibrate_accelerometer()
Sends command to calibrate accelerometer.
Definition BNO08x.cpp:482
+
static const constexpr uint8_t COMMAND_DCD
Save DCD command (See SH2 Ref. Manual 6.4.7)
Definition BNO08x.hpp:312
+
int16_t get_raw_gyro_X()
Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1764
+
float get_pitch_deg()
Get the reported rotation about y axis.
Definition BNO08x.cpp:1510
+
static const constexpr uint8_t CALIBRATE_ACCEL_GYRO_MAG
Calibrate accelerometer, gyro, & magnetometer command used by queue_calibrate_command.
Definition BNO08x.hpp:304
+
uint16_t packet_length_rx
Packet length received (calculated from packet_header_rx)
Definition BNO08x.hpp:250
+
float get_yaw_deg()
Get the reported rotation about z axis.
Definition BNO08x.cpp:1520
+
uint8_t * activity_confidences
Confidence of read activities (See SH-2 Ref. Manual 6.5.36)
Definition BNO08x.hpp:272
+
void enable_raw_gyro(uint16_t time_between_reports)
Sends command to enable raw gyro reports (See Ref. Manual 6.5.12)
Definition BNO08x.cpp:1207
+
static const constexpr uint8_t SENSOR_REPORTID_STABILITY_CLASSIFIER
See SH2 Ref. Manual 6.5.31.
Definition BNO08x.hpp:342
+
void save_tare()
Sends command to save tare into non-volatile memory of BNO08x (See Ref. Manual 6.4....
Definition BNO08x.cpp:1246
+
void calibrate_all()
Sends command to calibrate accelerometer, gyro, and magnetometer.
Definition BNO08x.cpp:470
+
float get_accel_Y()
Get y axis acceleration (total acceleration of device, units in m/s^2).
Definition BNO08x.cpp:1646
+
float get_linear_accel_Z()
Get z axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
Definition BNO08x.cpp:1714
+
void clear_tare()
Sends command to clear persistent tare settings in non-volatile memory of BNO08x (See Ref....
Definition BNO08x.cpp:1258
+
void get_gyro_velocity(float &x, float &y, float &z)
Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5....
Definition BNO08x.cpp:1981
+
int16_t get_raw_gyro_Y()
Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6....
Definition BNO08x.cpp:1774
+
void request_calibration_status()
Requests ME calibration status from BNO08x (see Ref. Manual 6.4.7.2)
Definition BNO08x.cpp:579
+
IMU configuration settings passed into constructor.
Definition BNO08x.hpp:42
+
spi_host_device_t spi_peripheral
SPI peripheral to be used.
Definition BNO08x.hpp:43
+
gpio_num_t io_int
Chip select pin (connects to BNO08x CS pin)
Definition BNO08x.hpp:48
+
gpio_num_t io_rst
Host interrupt pin (connects to BNO08x INT pin)
Definition BNO08x.hpp:49
+
gpio_num_t io_sclk
SCLK pin (connects to BNO08x SCL pin)
Definition BNO08x.hpp:46
+
uint64_t sclk_speed
Desired SPI SCLK speed in Hz (max 3MHz)
Definition BNO08x.hpp:51
+
bool debug_en
Whether or not debugging print statements are enabled.
Definition BNO08x.hpp:52
+
gpio_num_t io_mosi
MOSI GPIO pin (connects to BNO08x DI pin)
Definition BNO08x.hpp:44
+
gpio_num_t io_wake
Reset pin (connects to BNO08x RST pin)
Definition BNO08x.hpp:50
+
gpio_num_t io_miso
MISO GPIO pin (connects to BNO08x SDA pin)
Definition BNO08x.hpp:45
+
bno08x_config_t()
Default IMU configuration settings
Definition BNO08x.hpp:55
+
+ + + + diff --git a/documentation/html/annotated.html b/documentation/html/annotated.html new file mode 100644 index 0000000..c5fe971 --- /dev/null +++ b/documentation/html/annotated.html @@ -0,0 +1,88 @@ + + + + + + + +esp32_BNO08x: Class List + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Class List
+
+
+
Here are the classes, structs, unions and interfaces with brief descriptions:
+ + + +
 CBNO08x
 Cbno08x_config_tIMU configuration settings passed into constructor
+
+
+ + + + diff --git a/documentation/html/bc_s.png b/documentation/html/bc_s.png new file mode 100644 index 0000000..224b29a Binary files /dev/null and b/documentation/html/bc_s.png differ diff --git a/documentation/html/bc_sd.png b/documentation/html/bc_sd.png new file mode 100644 index 0000000..31ca888 Binary files /dev/null and b/documentation/html/bc_sd.png differ diff --git a/documentation/html/class_b_n_o08x-members.html b/documentation/html/class_b_n_o08x-members.html new file mode 100644 index 0000000..69e2e4f --- /dev/null +++ b/documentation/html/class_b_n_o08x-members.html @@ -0,0 +1,354 @@ + + + + + + + +esp32_BNO08x: Member List + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
BNO08x Member List
+
+
+ +

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

+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
accel_accuracyBNO08xprivate
accel_lin_accuracyBNO08xprivate
ACCELEROMETER_Q1BNO08xprivatestatic
activity_classifierBNO08xprivate
activity_confidencesBNO08xprivate
ANGULAR_VELOCITY_Q1BNO08xprivatestatic
BNO08x(bno08x_config_t imu_config=default_imu_config)BNO08x
bus_configBNO08xprivate
CALIBRATE_ACCELBNO08xprivatestatic
CALIBRATE_ACCEL_GYRO_MAGBNO08xprivatestatic
calibrate_accelerometer()BNO08x
calibrate_all()BNO08x
CALIBRATE_GYROBNO08xprivatestatic
calibrate_gyro()BNO08x
CALIBRATE_MAGBNO08xprivatestatic
calibrate_magnetometer()BNO08x
CALIBRATE_PLANAR_ACCELBNO08xprivatestatic
calibrate_planar_accelerometer()BNO08x
CALIBRATE_STOPBNO08xprivatestatic
calibration_complete()BNO08x
calibration_statusBNO08xprivate
clear_tare()BNO08x
COMMAND_CLEAR_DCDBNO08xprivatestatic
COMMAND_COUNTER (defined in BNO08x)BNO08xprivatestatic
COMMAND_DCDBNO08xprivatestatic
COMMAND_DCD_PERIOD_SAVEBNO08xprivatestatic
COMMAND_ERRORS (defined in BNO08x)BNO08xprivatestatic
COMMAND_INITIALIZEBNO08xprivatestatic
COMMAND_ME_CALIBRATEBNO08xprivatestatic
COMMAND_OSCILLATORBNO08xprivatestatic
command_sequence_numberBNO08xprivate
COMMAND_TAREBNO08xprivatestatic
commandsBNO08xprivate
data_available()BNO08x
default_imu_configBNO08xprivatestatic
enable_accelerometer(uint16_t time_between_reports)BNO08x
enable_activity_classifier(uint16_t time_between_reports, uint32_t activities_to_enable, uint8_t(&activity_confidence_vals)[9])BNO08x
enable_ARVR_stabilized_game_rotation_vector(uint16_t time_between_reports)BNO08x
enable_ARVR_stabilized_rotation_vector(uint16_t time_between_reports)BNO08x
enable_game_rotation_vector(uint16_t time_between_reports)BNO08x
enable_gravity(uint16_t time_between_reports)BNO08x
enable_gyro(uint16_t time_between_reports)BNO08x
enable_gyro_integrated_rotation_vector(uint16_t timeBetweenReports)BNO08x
enable_linear_accelerometer(uint16_t time_between_reports)BNO08x
enable_magnetometer(uint16_t time_between_reports)BNO08x
enable_raw_accelerometer(uint16_t time_between_reports)BNO08x
enable_raw_gyro(uint16_t time_between_reports)BNO08x
enable_raw_magnetometer(uint16_t time_between_reports)BNO08x
enable_rotation_vector(uint16_t time_between_reports)BNO08x
enable_stability_classifier(uint16_t time_between_reports)BNO08x
enable_step_counter(uint16_t time_between_reports)BNO08x
enable_tap_detector(uint16_t time_between_reports)BNO08x
enable_uncalibrated_gyro(uint16_t time_between_reports)BNO08x
end_calibration()BNO08x
FRS_read_data(uint16_t record_ID, uint8_t start_location, uint8_t words_to_read)BNO08x
FRS_read_request(uint16_t record_ID, uint16_t read_offset, uint16_t block_size)BNO08x
FRS_read_word(uint16_t record_ID, uint8_t word_number)BNO08x
FRS_RECORDID_ACCELEROMETER (defined in BNO08x)BNO08xstatic
FRS_RECORDID_GYROSCOPE_CALIBRATED (defined in BNO08x)BNO08xstatic
FRS_RECORDID_MAGNETIC_FIELD_CALIBRATED (defined in BNO08x)BNO08xstatic
FRS_RECORDID_ROTATION_VECTOR (defined in BNO08x)BNO08xstatic
get_accel(float &x, float &y, float &z, uint8_t &accuracy)BNO08x
get_accel_accuracy()BNO08x
get_accel_X()BNO08x
get_accel_Y()BNO08x
get_accel_Z()BNO08x
get_activity_classifier()BNO08x
get_gravity(float &x, float &y, float &z, uint8_t &accuracy)BNO08x
get_gravity_accuracy()BNO08x
get_gravity_X()BNO08x
get_gravity_Y()BNO08x
get_gravity_Z()BNO08x
get_gyro_accuracy()BNO08x
get_gyro_calibrated_velocity(float &x, float &y, float &z, uint8_t &accuracy)BNO08x
get_gyro_calibrated_velocity_X()BNO08x
get_gyro_calibrated_velocity_Y()BNO08x
get_gyro_calibrated_velocity_Z()BNO08x
get_gyro_velocity(float &x, float &y, float &z)BNO08x
get_gyro_velocity_X()BNO08x
get_gyro_velocity_Y()BNO08x
get_gyro_velocity_Z()BNO08x
get_linear_accel(float &x, float &y, float &z, uint8_t &accuracy)BNO08x
get_linear_accel_accuracy()BNO08x
get_linear_accel_X()BNO08x
get_linear_accel_Y()BNO08x
get_linear_accel_Z()BNO08x
get_magf(float &x, float &y, float &z, uint8_t &accuracy)BNO08x
get_magf_accuracy()BNO08x
get_magf_X()BNO08x
get_magf_Y()BNO08x
get_magf_Z()BNO08x
get_pitch()BNO08x
get_pitch_deg()BNO08x
get_Q1(uint16_t record_ID)BNO08x
get_Q2(uint16_t record_ID)BNO08x
get_Q3(uint16_t record_ID)BNO08x
get_quat(float &i, float &j, float &k, float &real, float &rad_accuracy, uint8_t &accuracy)BNO08x
get_quat_accuracy()BNO08x
get_quat_I()BNO08x
get_quat_J()BNO08x
get_quat_K()BNO08x
get_quat_radian_accuracy()BNO08x
get_quat_real()BNO08x
get_range(uint16_t record_ID)BNO08x
get_raw_accel_X()BNO08x
get_raw_accel_Y()BNO08x
get_raw_accel_Z()BNO08x
get_raw_gyro_X()BNO08x
get_raw_gyro_Y()BNO08x
get_raw_gyro_Z()BNO08x
get_raw_magf_X()BNO08x
get_raw_magf_Y()BNO08x
get_raw_magf_Z()BNO08x
get_readings()BNO08x
get_reset_reason()BNO08x
get_resolution(uint16_t record_ID)BNO08x
get_roll()BNO08x
get_roll_deg()BNO08x
get_stability_classifier()BNO08x
get_step_count()BNO08x
get_tap_detector()BNO08x
get_time_stamp()BNO08x
get_uncalibrated_gyro(float &x, float &y, float &z, float &bx, float &by, float &bz, uint8_t &accuracy)BNO08x
get_uncalibrated_gyro_accuracy()BNO08x
get_uncalibrated_gyro_bias_X()BNO08x
get_uncalibrated_gyro_bias_Y()BNO08x
get_uncalibrated_gyro_bias_Z()BNO08x
get_uncalibrated_gyro_X()BNO08x
get_uncalibrated_gyro_Y()BNO08x
get_uncalibrated_gyro_Z()BNO08x
get_yaw()BNO08x
get_yaw_deg()BNO08x
gravity_accuracyBNO08xprivate
GRAVITY_Q1BNO08xprivatestatic
gravity_X (defined in BNO08x)BNO08xprivate
gravity_Y (defined in BNO08x)BNO08xprivate
gravity_Z (defined in BNO08x)BNO08xprivate
gyro_accuracyBNO08xprivate
GYRO_Q1BNO08xprivatestatic
hard_reset()BNO08x
hint_handler(void *arg)BNO08xprivatestatic
HOST_INT_TIMEOUT_USBNO08xprivatestatic
imu_configBNO08xprivate
imu_spi_configBNO08xprivate
initialize()BNO08x
int_assertedBNO08xprivate
isr_service_installedBNO08xprivatestatic
LINEAR_ACCELEROMETER_Q1BNO08xprivatestatic
magf_accuracyBNO08xprivate
MAGNETOMETER_Q1BNO08xprivatestatic
mems_raw_accel_X (defined in BNO08x)BNO08xprivate
mems_raw_accel_Y (defined in BNO08x)BNO08xprivate
mems_raw_accel_ZBNO08xprivate
mems_raw_gyro_X (defined in BNO08x)BNO08xprivate
mems_raw_gyro_Y (defined in BNO08x)BNO08xprivate
mems_raw_gyro_ZBNO08xprivate
mems_raw_magf_X (defined in BNO08x)BNO08xprivate
mems_raw_magf_Y (defined in BNO08x)BNO08xprivate
mems_raw_magf_ZBNO08xprivate
meta_dataBNO08xprivate
mode_on()BNO08x
mode_sleep()BNO08x
packet_header_rxBNO08xprivate
packet_length_rxBNO08xprivate
packet_length_txBNO08xprivate
parse_command_report()BNO08x
parse_input_report()BNO08x
print_header()BNO08x
print_packet() (defined in BNO08x)BNO08x
q_to_float(int16_t fixed_point_value, uint8_t q_point)BNO08x
quat_accuracyBNO08xprivate
queue_calibrate_command(uint8_t _to_calibrate)BNO08xprivate
queue_command(uint8_t command)BNO08xprivate
queue_feature_command(uint8_t report_ID, uint16_t time_between_reports)BNO08xprivate
queue_feature_command(uint8_t report_ID, uint16_t time_between_reports, uint32_t specific_config)BNO08xprivate
queue_packet(uint8_t channel_number, uint8_t data_length)BNO08xprivate
queue_request_product_id_command()BNO08xprivate
queue_tare_command(uint8_t command, uint8_t axis=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)BNO08xprivate
raw_accel_X (defined in BNO08x)BNO08xprivate
raw_accel_Y (defined in BNO08x)BNO08xprivate
raw_accel_Z (defined in BNO08x)BNO08xprivate
raw_bias_X (defined in BNO08x)BNO08xprivate
raw_bias_Y (defined in BNO08x)BNO08xprivate
raw_bias_Z (defined in BNO08x)BNO08xprivate
raw_gyro_X (defined in BNO08x)BNO08xprivate
raw_gyro_Y (defined in BNO08x)BNO08xprivate
raw_gyro_Z (defined in BNO08x)BNO08xprivate
raw_lin_accel_X (defined in BNO08x)BNO08xprivate
raw_lin_accel_Y (defined in BNO08x)BNO08xprivate
raw_lin_accel_Z (defined in BNO08x)BNO08xprivate
raw_magf_X (defined in BNO08x)BNO08xprivate
raw_magf_Y (defined in BNO08x)BNO08xprivate
raw_magf_Z (defined in BNO08x)BNO08xprivate
raw_quat_I (defined in BNO08x)BNO08xprivate
raw_quat_J (defined in BNO08x)BNO08xprivate
raw_quat_K (defined in BNO08x)BNO08xprivate
raw_quat_radian_accuracy (defined in BNO08x)BNO08xprivate
raw_quat_real (defined in BNO08x)BNO08xprivate
raw_uncalib_gyro_X (defined in BNO08x)BNO08xprivate
raw_uncalib_gyro_Y (defined in BNO08x)BNO08xprivate
raw_uncalib_gyro_Z (defined in BNO08x)BNO08xprivate
raw_velocity_gyro_X (defined in BNO08x)BNO08xprivate
raw_velocity_gyro_Y (defined in BNO08x)BNO08xprivate
raw_velocity_gyro_ZBNO08xprivate
receive_packet()BNO08xprivate
request_calibration_status()BNO08x
ROTATION_VECTOR_ACCURACY_Q1BNO08xprivatestatic
ROTATION_VECTOR_Q1BNO08xprivatestatic
run_full_calibration_routine()BNO08x
rx_bufferBNO08xprivate
save_calibration()BNO08x
save_tare()BNO08x
send_packet()BNO08xprivate
SENSOR_REPORTID_ACCELEROMETERBNO08xprivatestatic
SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTORBNO08xprivatestatic
SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTORBNO08xprivatestatic
SENSOR_REPORTID_GAME_ROTATION_VECTORBNO08xprivatestatic
SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTORBNO08xprivatestatic
SENSOR_REPORTID_GRAVITYBNO08xprivatestatic
SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTORBNO08xprivatestatic
SENSOR_REPORTID_GYROSCOPEBNO08xprivatestatic
SENSOR_REPORTID_LINEAR_ACCELERATIONBNO08xprivatestatic
SENSOR_REPORTID_MAGNETIC_FIELDBNO08xprivatestatic
SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIERBNO08xprivatestatic
SENSOR_REPORTID_RAW_ACCELEROMETERBNO08xprivatestatic
SENSOR_REPORTID_RAW_GYROSCOPEBNO08xprivatestatic
SENSOR_REPORTID_RAW_MAGNETOMETERBNO08xprivatestatic
SENSOR_REPORTID_ROTATION_VECTORBNO08xprivatestatic
SENSOR_REPORTID_STABILITY_CLASSIFIERBNO08xprivatestatic
SENSOR_REPORTID_STEP_COUNTERBNO08xprivatestatic
SENSOR_REPORTID_TAP_DETECTORBNO08xprivatestatic
SENSOR_REPORTID_UNCALIBRATED_GYROBNO08xprivatestatic
sequence_numberBNO08xprivate
SHTP_REPORT_BASE_TIMESTAMPBNO08xprivatestatic
SHTP_REPORT_COMMAND_REQUESTBNO08xprivatestatic
SHTP_REPORT_COMMAND_RESPONSEBNO08xprivatestatic
SHTP_REPORT_FRS_READ_REQUESTBNO08xprivatestatic
SHTP_REPORT_FRS_READ_RESPONSEBNO08xprivatestatic
SHTP_REPORT_PRODUCT_ID_REQUESTBNO08xprivatestatic
SHTP_REPORT_PRODUCT_ID_RESPONSEBNO08xprivatestatic
SHTP_REPORT_SET_FEATURE_COMMANDBNO08xprivatestatic
soft_reset()BNO08x
spi_hdlBNO08xprivate
spi_task()BNO08xprivate
spi_task_hdlBNO08xprivate
spi_task_trampoline(void *arg)BNO08xprivatestatic
spi_transactionBNO08xprivate
stability_classifierBNO08xprivate
step_countBNO08xprivate
TAGBNO08xprivatestatic
tap_detectorBNO08xprivate
TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTORBNO08xprivatestatic
TARE_AR_VR_STABILIZED_ROTATION_VECTORBNO08xprivatestatic
TARE_AXIS_ALLBNO08xprivatestatic
TARE_AXIS_ZBNO08xprivatestatic
TARE_GAME_ROTATION_VECTORBNO08xprivatestatic
TARE_GEOMAGNETIC_ROTATION_VECTORBNO08xprivatestatic
TARE_GYRO_INTEGRATED_ROTATION_VECTORBNO08xprivatestatic
TARE_NOWBNO08xprivatestatic
tare_now(uint8_t axis_sel=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)BNO08x
TARE_PERSISTBNO08xprivatestatic
TARE_ROTATION_VECTORBNO08xprivatestatic
TARE_SET_REORIENTATIONBNO08xprivatestatic
time_stampBNO08xprivate
tx_bufferBNO08xprivate
tx_packet_queuedBNO08xprivate
tx_semaphoreBNO08xprivate
uncalib_gyro_accuracyBNO08xprivate
wait_for_device_int()BNO08xprivate
+ + + + diff --git a/documentation/html/class_b_n_o08x.html b/documentation/html/class_b_n_o08x.html new file mode 100644 index 0000000..4b11a74 --- /dev/null +++ b/documentation/html/class_b_n_o08x.html @@ -0,0 +1,4391 @@ + + + + + + + +esp32_BNO08x: BNO08x Class Reference + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+ +
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Public Member Functions

 BNO08x (bno08x_config_t imu_config=default_imu_config)
 BNO08x imu constructor.
 
bool initialize ()
 Initializes BNO08x sensor.
 
bool hard_reset ()
 Hard resets BNO08x sensor.
 
bool soft_reset ()
 Soft resets BNO08x sensor using executable channel.
 
uint8_t get_reset_reason ()
 Get the reason for the most recent reset.
 
bool mode_sleep ()
 Puts BNO08x sensor into sleep/low power mode using executable channel.
 
bool mode_on ()
 Turns on/ brings BNO08x sensor out of sleep mode using executable channel.
 
float q_to_float (int16_t fixed_point_value, uint8_t q_point)
 Converts a register value to a float using its associated Q point. (See https://en.wikipedia.org/wiki/Q_(number_format))
 
bool run_full_calibration_routine ()
 Runs full calibration routine.
 
void calibrate_all ()
 Sends command to calibrate accelerometer, gyro, and magnetometer.
 
void calibrate_accelerometer ()
 Sends command to calibrate accelerometer.
 
void calibrate_gyro ()
 Sends command to calibrate gyro.
 
void calibrate_magnetometer ()
 Sends command to calibrate magnetometer.
 
void calibrate_planar_accelerometer ()
 Sends command to calibrate planar accelerometer.
 
void request_calibration_status ()
 Requests ME calibration status from BNO08x (see Ref. Manual 6.4.7.2)
 
bool calibration_complete ()
 Returns true if calibration has completed.
 
void end_calibration ()
 Sends command to end calibration procedure.
 
void save_calibration ()
 Sends command to save internal calibration data (See Ref. Manual 6.4.7).
 
void enable_rotation_vector (uint16_t time_between_reports)
 Sends command to enable rotation vector reports (See Ref. Manual 6.5.18)
 
void enable_game_rotation_vector (uint16_t time_between_reports)
 Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19)
 
void enable_ARVR_stabilized_rotation_vector (uint16_t time_between_reports)
 Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6.5.42)
 
void enable_ARVR_stabilized_game_rotation_vector (uint16_t time_between_reports)
 Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6.5.43)
 
void enable_gyro_integrated_rotation_vector (uint16_t timeBetweenReports)
 Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6.5.44)
 
void enable_accelerometer (uint16_t time_between_reports)
 Sends command to enable accelerometer reports (See Ref. Manual 6.5.9)
 
void enable_linear_accelerometer (uint16_t time_between_reports)
 Sends command to enable linear accelerometer reports (See Ref. Manual 6.5.10)
 
void enable_gravity (uint16_t time_between_reports)
 Sends command to enable gravity reading reports (See Ref. Manual 6.5.11)
 
void enable_gyro (uint16_t time_between_reports)
 Sends command to enable gyro reports (See Ref. Manual 6.5.13)
 
void enable_uncalibrated_gyro (uint16_t time_between_reports)
 Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.5.14)
 
void enable_magnetometer (uint16_t time_between_reports)
 Sends command to enable magnetometer reports (See Ref. Manual 6.5.16)
 
void enable_tap_detector (uint16_t time_between_reports)
 Sends command to enable tap detector reports (See Ref. Manual 6.5.27)
 
void enable_step_counter (uint16_t time_between_reports)
 Sends command to enable step counter reports (See Ref. Manual 6.5.29)
 
void enable_stability_classifier (uint16_t time_between_reports)
 Sends command to enable activity stability classifier reports (See Ref. Manual 6.5.31)
 
void enable_activity_classifier (uint16_t time_between_reports, uint32_t activities_to_enable, uint8_t(&activity_confidence_vals)[9])
 Sends command to enable activity classifier reports (See Ref. Manual 6.5.36)
 
void enable_raw_accelerometer (uint16_t time_between_reports)
 Sends command to enable raw accelerometer reports (See Ref. Manual 6.5.8)
 
void enable_raw_gyro (uint16_t time_between_reports)
 Sends command to enable raw gyro reports (See Ref. Manual 6.5.12)
 
void enable_raw_magnetometer (uint16_t time_between_reports)
 Sends command to enable raw magnetometer reports (See Ref. Manual 6.5.15)
 
void tare_now (uint8_t axis_sel=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
 Sends command to tare an axis (See Ref. Manual 6.4.4.1)
 
void save_tare ()
 Sends command to save tare into non-volatile memory of BNO08x (See Ref. Manual 6.4.4.2)
 
void clear_tare ()
 Sends command to clear persistent tare settings in non-volatile memory of BNO08x (See Ref. Manual 6.4.4.3)
 
bool data_available ()
 Checks if BNO08x has asserted interrupt and sent data.
 
uint16_t parse_input_report ()
 Parses received input report sent by BNO08x.
 
uint16_t parse_command_report ()
 Parses received command report sent by BNO08x (See Ref. Manual 6.3.9)
 
uint16_t get_readings ()
 Waits for BNO08x HINT pin to assert, and parses the received data.
 
uint32_t get_time_stamp ()
 Return timestamp of most recent report.
 
void get_magf (float &x, float &y, float &z, uint8_t &accuracy)
 Get the full magnetic field vector.
 
float get_magf_X ()
 Get X component of magnetic field vector.
 
float get_magf_Y ()
 Get Y component of magnetic field vector.
 
float get_magf_Z ()
 Get Z component of magnetic field vector.
 
uint8_t get_magf_accuracy ()
 Get accuracy of reported magnetic field vector.
 
void get_gravity (float &x, float &y, float &z, uint8_t &accuracy)
 Get full reported gravity vector, units in m/s^2.
 
float get_gravity_X ()
 Get the reported x axis gravity.
 
float get_gravity_Y ()
 Get the reported y axis gravity.
 
float get_gravity_Z ()
 Get the reported z axis gravity.
 
uint8_t get_gravity_accuracy ()
 Get the reported gravity accuracy.
 
float get_roll ()
 Get the reported rotation about x axis.
 
float get_pitch ()
 Get the reported rotation about y axis.
 
float get_yaw ()
 Get the reported rotation about z axis.
 
float get_roll_deg ()
 Get the reported rotation about x axis.
 
float get_pitch_deg ()
 Get the reported rotation about y axis.
 
float get_yaw_deg ()
 Get the reported rotation about z axis.
 
void get_quat (float &i, float &j, float &k, float &real, float &rad_accuracy, uint8_t &accuracy)
 Get the full quaternion reading.
 
float get_quat_I ()
 Get I component of reported quaternion.
 
float get_quat_J ()
 Get J component of reported quaternion.
 
float get_quat_K ()
 Get K component of reported quaternion.
 
float get_quat_real ()
 Get real component of reported quaternion.
 
float get_quat_radian_accuracy ()
 Get radian accuracy of reported quaternion.
 
uint8_t get_quat_accuracy ()
 Get accuracy of reported quaternion.
 
void get_accel (float &x, float &y, float &z, uint8_t &accuracy)
 Get full acceleration (total acceleration of device, units in m/s^2).
 
float get_accel_X ()
 Get x axis acceleration (total acceleration of device, units in m/s^2).
 
float get_accel_Y ()
 Get y axis acceleration (total acceleration of device, units in m/s^2).
 
float get_accel_Z ()
 Get z axis acceleration (total acceleration of device, units in m/s^2).
 
uint8_t get_accel_accuracy ()
 Get accuracy of linear acceleration.
 
void get_linear_accel (float &x, float &y, float &z, uint8_t &accuracy)
 Get full linear acceleration (acceleration of the device minus gravity, units in m/s^2).
 
float get_linear_accel_X ()
 Get x axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
 
float get_linear_accel_Y ()
 Get y axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
 
float get_linear_accel_Z ()
 Get z axis linear acceleration (acceleration of device minus gravity, units in m/s^2)
 
uint8_t get_linear_accel_accuracy ()
 Get accuracy of linear acceleration.
 
int16_t get_raw_accel_X ()
 Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8)
 
int16_t get_raw_accel_Y ()
 Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8)
 
int16_t get_raw_accel_Z ()
 Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.5.8)
 
int16_t get_raw_gyro_X ()
 Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)
 
int16_t get_raw_gyro_Y ()
 Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)
 
int16_t get_raw_gyro_Z ()
 Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.5.12)
 
int16_t get_raw_magf_X ()
 Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15)
 
int16_t get_raw_magf_Y ()
 Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15)
 
int16_t get_raw_magf_Z ()
 Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6.5.15)
 
void get_gyro_calibrated_velocity (float &x, float &y, float &z, uint8_t &accuracy)
 Get full rotational velocity with drift compensation (units in Rad/s).
 
float get_gyro_calibrated_velocity_X ()
 Get calibrated gyro x axis angular velocity measurement.
 
float get_gyro_calibrated_velocity_Y ()
 Get calibrated gyro y axis angular velocity measurement.
 
float get_gyro_calibrated_velocity_Z ()
 Get calibrated gyro z axis angular velocity measurement.
 
uint8_t get_gyro_accuracy ()
 Get calibrated gyro accuracy.
 
void get_uncalibrated_gyro (float &x, float &y, float &z, float &bx, float &by, float &bz, uint8_t &accuracy)
 Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is given but not applied.
 
float get_uncalibrated_gyro_X ()
 Get uncalibrated gyro x axis angular velocity measurement.
 
float get_uncalibrated_gyro_Y ()
 Get uncalibrated gyro Y axis angular velocity measurement.
 
float get_uncalibrated_gyro_Z ()
 Get uncalibrated gyro Z axis angular velocity measurement.
 
float get_uncalibrated_gyro_bias_X ()
 Get uncalibrated gyro x axis drift estimate.
 
float get_uncalibrated_gyro_bias_Y ()
 Get uncalibrated gyro Y axis drift estimate.
 
float get_uncalibrated_gyro_bias_Z ()
 Get uncalibrated gyro Z axis drift estimate.
 
uint8_t get_uncalibrated_gyro_accuracy ()
 Get uncalibrated gyro accuracy.
 
void get_gyro_velocity (float &x, float &y, float &z)
 Full rotational velocity from gyro-integrated rotation vector (See Ref. Manual 6.5.44)
 
float get_gyro_velocity_X ()
 Get x axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44)
 
float get_gyro_velocity_Y ()
 Get y axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44)
 
float get_gyro_velocity_Z ()
 Get z axis angular velocity from gyro-integrated rotation vector. (See Ref. Manual 6.5.44)
 
uint8_t get_tap_detector ()
 Get if tap has occured.
 
uint16_t get_step_count ()
 Get the counted amount of steps.
 
int8_t get_stability_classifier ()
 Get the current stability classifier (Seee Ref. Manual 6.5.31)
 
uint8_t get_activity_classifier ()
 Get the current activity classifier (Seee Ref. Manual 6.5.36)
 
void print_header ()
 Prints the most recently received SHTP header to serial console with ESP_LOG statement.
 
+void print_packet ()
 
int16_t get_Q1 (uint16_t record_ID)
 Gets Q1 point from BNO08x FRS (flash record system).
 
int16_t get_Q2 (uint16_t record_ID)
 Gets Q2 point from BNO08x FRS (flash record system).
 
int16_t get_Q3 (uint16_t record_ID)
 Gets Q3 point from BNO08x FRS (flash record system).
 
float get_resolution (uint16_t record_ID)
 Gets resolution from BNO08x FRS (flash record system).
 
float get_range (uint16_t record_ID)
 Gets range from BNO08x FRS (flash record system).
 
uint32_t FRS_read_word (uint16_t record_ID, uint8_t word_number)
 Reads meta data word from BNO08x FRS (flash record system) given the record ID and word number. (See Ref. Manual 5.1 & 6.3.7)
 
bool FRS_read_request (uint16_t record_ID, uint16_t read_offset, uint16_t block_size)
 Requests meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.1 & 6.3.6)
 
bool FRS_read_data (uint16_t record_ID, uint8_t start_location, uint8_t words_to_read)
 Read meta data from BNO08x FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.1 & 6.3.7)
 
+ + + + + + + + + +

+Static Public Attributes

+static const constexpr uint16_t FRS_RECORDID_ACCELEROMETER = 0xE302
 
+static const constexpr uint16_t FRS_RECORDID_GYROSCOPE_CALIBRATED = 0xE306
 
+static const constexpr uint16_t FRS_RECORDID_MAGNETIC_FIELD_CALIBRATED = 0xE309
 
+static const constexpr uint16_t FRS_RECORDID_ROTATION_VECTOR = 0xE30B
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Private Member Functions

bool wait_for_device_int ()
 Re-enables interrupts and waits for BNO08x to assert HINT pin.
 
bool receive_packet ()
 Receives a SHTP packet via SPI.
 
void send_packet ()
 Sends a queued SHTP packet via SPI.
 
void queue_packet (uint8_t channel_number, uint8_t data_length)
 Queues an SHTP packet to be sent via SPI.
 
void queue_command (uint8_t command)
 Queues a packet containing a command.
 
void queue_feature_command (uint8_t report_ID, uint16_t time_between_reports)
 Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.5.4)
 
void queue_feature_command (uint8_t report_ID, uint16_t time_between_reports, uint32_t specific_config)
 Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.5.4)
 
void queue_calibrate_command (uint8_t _to_calibrate)
 Queues a packet containing a command to calibrate the specified sensor.
 
void queue_tare_command (uint8_t command, uint8_t axis=TARE_AXIS_ALL, uint8_t rotation_vector_basis=TARE_ROTATION_VECTOR)
 Queues a packet containing a command related to zeroing sensor's axes. (See Ref. Manual 6.4.4.1)
 
void queue_request_product_id_command ()
 Queues a packet containing the request product ID command.
 
void spi_task ()
 Task responsible for SPI transactions. Executed when HINT in is asserted by BNO08x.
 
+ + + + + + + +

+Static Private Member Functions

static void spi_task_trampoline (void *arg)
 Static function used to launch spi task.
 
static void IRAM_ATTR hint_handler (void *arg)
 HINT interrupt service routine, handles falling edge of BNO08x HINT pin.
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Private Attributes

+volatile uint8_t tx_packet_queued
 Whether or not a packet is currently waiting to be sent, a queued packet is sent on assertion of BNO08x HINT pin)
 
+SemaphoreHandle_t tx_semaphore
 Mutex semaphore used to prevent sending or receiving of packets if packet is currently being queued.
 
+uint8_t rx_buffer [300]
 buffer used to receive packet with receive_packet()
 
+uint8_t tx_buffer [50]
 buffer used for sending packet with send_packet()
 
+uint8_t packet_header_rx [4]
 SHTP header received with receive_packet()
 
+uint8_t commands [20]
 Command to be sent with send_packet()
 
+uint8_t sequence_number [6]
 Sequence num of each com channel, 6 in total.
 
+uint32_t meta_data [9]
 First 9 bytes of meta data returned from FRS read operation (we don't really need the rest) (See Ref. Manual 5.1)
 
+uint8_t command_sequence_number = 0
 Sequence num of command, sent within command packet.
+
 
+uint16_t packet_length_tx = 0
 Packet length to be sent with send_packet()
 
+uint16_t packet_length_rx = 0
 Packet length received (calculated from packet_header_rx)
 
+bno08x_config_t imu_config {}
 IMU configuration settings.
 
+spi_bus_config_t bus_config {}
 SPI bus GPIO configuration settings.
 
+spi_device_interface_config_t imu_spi_config {}
 SPI slave device settings.
 
+spi_device_handle_t spi_hdl {}
 SPI device handle.
 
+spi_transaction_t spi_transaction {}
 SPI transaction handle.
 
+uint32_t time_stamp
 Report timestamp (see datasheet 1.3.5.3)
 
+uint16_t raw_accel_X
 
+uint16_t raw_accel_Y
 
+uint16_t raw_accel_Z
 
+uint16_t accel_accuracy
 Raw acceleration readings (See SH-2 Ref. Manual 6.5.8)
 
+uint16_t raw_lin_accel_X
 
+uint16_t raw_lin_accel_Y
 
+uint16_t raw_lin_accel_Z
 
+uint16_t accel_lin_accuracy
 Raw linear acceleration (See SH-2 Ref. Manual 6.5.10)
 
+uint16_t raw_gyro_X
 
+uint16_t raw_gyro_Y
 
+uint16_t raw_gyro_Z
 
+uint16_t gyro_accuracy
 Raw gyro reading (See SH-2 Ref. Manual 6.5.13)
 
+uint16_t raw_quat_I
 
+uint16_t raw_quat_J
 
+uint16_t raw_quat_K
 
+uint16_t raw_quat_real
 
+uint16_t raw_quat_radian_accuracy
 
+uint16_t quat_accuracy
 Raw quaternion reading (See SH-2 Ref. Manual 6.5.44)
 
+uint16_t raw_velocity_gyro_X
 
+uint16_t raw_velocity_gyro_Y
 
+uint16_t raw_velocity_gyro_Z
 Raw gyro angular velocity reading (See SH-2 Ref. Manual 6.5.44)
 
+uint16_t gravity_X
 
+uint16_t gravity_Y
 
+uint16_t gravity_Z
 
+uint16_t gravity_accuracy
 Gravity reading in m/s^2 (See SH-2 Ref. Manual 6.5.11)
 
+uint16_t raw_uncalib_gyro_X
 
+uint16_t raw_uncalib_gyro_Y
 
+uint16_t raw_uncalib_gyro_Z
 
+uint16_t raw_bias_X
 
+uint16_t raw_bias_Y
 
+uint16_t raw_bias_Z
 
+uint16_t uncalib_gyro_accuracy
 Uncalibrated gyro reading (See SH-2 Ref. Manual 6.5.14)
 
+uint16_t raw_magf_X
 
+uint16_t raw_magf_Y
 
+uint16_t raw_magf_Z
 
+uint16_t magf_accuracy
 Calibrated magnetic field reading in uTesla (See SH-2 Ref. Manual 6.5.16)
 
+uint8_t tap_detector
 Tap detector reading (See SH-2 Ref. Manual 6.5.27)
 
+uint16_t step_count
 Step counter reading (See SH-2 Ref. Manual 6.5.29)
 
+uint8_t stability_classifier
 Stability status reading (See SH-2 Ref. Manual 6.5.31)
 
+uint8_t activity_classifier
 Activity status reading (See SH-2 Ref. Manual 6.5.36)
 
+uint8_t * activity_confidences
 Confidence of read activities (See SH-2 Ref. Manual 6.5.36)
 
+uint8_t calibration_status
 Calibration status of device (See SH-2 Ref. Manual 6.4.7.1 & 6.4.7.2)
+
 
+uint16_t mems_raw_accel_X
 
+uint16_t mems_raw_accel_Y
 
+uint16_t mems_raw_accel_Z
 Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.5.8)
 
+uint16_t mems_raw_gyro_X
 
+uint16_t mems_raw_gyro_Y
 
+uint16_t mems_raw_gyro_Z
 Raw gyro readings from MEMS sensor (See SH-2 Ref. Manual 6.5.12)
 
+uint16_t mems_raw_magf_X
 
+uint16_t mems_raw_magf_Y
 
+uint16_t mems_raw_magf_Z
 Raw magnetometer (compass) readings from MEMS sensor (See SH-2 Ref. Manual 6.5.15)
 
+TaskHandle_t spi_task_hdl
 SPI task handle.
 
+volatile bool int_asserted
 Interrupt asserted flag, sets true after hint_handler ISR launches SPI task and it has run to completion.
 
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

+Static Private Attributes

+static bno08x_config_t default_imu_config
 default imu config settings
 
+static bool isr_service_installed = {false}
 true of the isr service has been installed, only has to be done once regardless of how many devices are used
 
+static const constexpr int16_t ROTATION_VECTOR_Q1 = 14
 Rotation vector Q point (See SH-2 Ref. Manual 6.5.18)
 
+static const constexpr int16_t ROTATION_VECTOR_ACCURACY_Q1 = 12
 Rotation vector accuracy estimate Q point (See SH-2 Ref. Manual 6.5.18)
 
+static const constexpr int16_t ACCELEROMETER_Q1 = 8
 Acceleration Q point (See SH-2 Ref. Manual 6.5.9)
 
+static const constexpr int16_t LINEAR_ACCELEROMETER_Q1 = 8
 Linear acceleration Q point (See SH-2 Ref. Manual 6.5.10)
 
+static const constexpr int16_t GYRO_Q1 = 9
 Gyro Q point (See SH-2 Ref. Manual 6.5.13)
 
+static const constexpr int16_t MAGNETOMETER_Q1 = 4
 Magnetometer Q point (See SH-2 Ref. Manual 6.5.16)
 
+static const constexpr int16_t ANGULAR_VELOCITY_Q1 = 10
 Angular velocity Q point (See SH-2 Ref. Manual 6.5.44)
 
+static const constexpr int16_t GRAVITY_Q1 = 8
 Gravity Q point (See SH-2 Ref. Manual 6.5.11)
 
+static const constexpr uint64_t HOST_INT_TIMEOUT_US = 150000ULL
 Max wait between HINT being asserted by BNO08x before transaction is considered failed.
 
+static const constexpr uint8_t CALIBRATE_ACCEL = 0
 Calibrate accelerometer command used by queue_calibrate_command.
 
+static const constexpr uint8_t CALIBRATE_GYRO = 1
 Calibrate gyro command used by queue_calibrate_command.
 
+static const constexpr uint8_t CALIBRATE_MAG = 2
 Calibrate magnetometer command used by queue_calibrate_command.
 
+static const constexpr uint8_t CALIBRATE_PLANAR_ACCEL = 3
 Calibrate planar acceleration command used by queue_calibrate_command.
 
+static const constexpr uint8_t CALIBRATE_ACCEL_GYRO_MAG = 4
 Calibrate accelerometer, gyro, & magnetometer command used by queue_calibrate_command.
 
+static const constexpr uint8_t CALIBRATE_STOP = 5
 Stop calibration command used by queue_calibrate_command.
 
+static const constexpr uint8_t COMMAND_ERRORS = 1
 
+static const constexpr uint8_t COMMAND_COUNTER = 2
 
+static const constexpr uint8_t COMMAND_TARE = 3
 Command and response to tare command (See Sh2 Ref. Manual 6.4.4)
 
+static const constexpr uint8_t COMMAND_INITIALIZE = 4
 Reinitialize sensor hub components See (SH2 Ref. Manual 6.4.5)
 
+static const constexpr uint8_t COMMAND_DCD = 6
 Save DCD command (See SH2 Ref. Manual 6.4.7)
 
+static const constexpr uint8_t COMMAND_ME_CALIBRATE = 7
 Command and response to configure ME calibration (See SH2 Ref. Manual 6.4.7)
 
+static const constexpr uint8_t COMMAND_DCD_PERIOD_SAVE = 9
 Configure DCD periodic saving (See SH2 Ref. Manual 6.4)
 
+static const constexpr uint8_t COMMAND_OSCILLATOR = 10
 Retrieve oscillator type command (See SH2 Ref. Manual 6.4)
 
+static const constexpr uint8_t COMMAND_CLEAR_DCD = 11
 Clear DCD & Reset command (See SH2 Ref. Manual 6.4)
 
+static const constexpr uint8_t SHTP_REPORT_COMMAND_RESPONSE = 0xF1
 See SH2 Ref. Manual 6.3.9.
 
+static const constexpr uint8_t SHTP_REPORT_COMMAND_REQUEST = 0xF2
 See SH2 Ref. Manual 6.3.8.
 
+static const constexpr uint8_t SHTP_REPORT_FRS_READ_RESPONSE = 0xF3
 See SH2 Ref. Manual 6.3.7.
 
+static const constexpr uint8_t SHTP_REPORT_FRS_READ_REQUEST = 0xF4
 See SH2 Ref. Manual 6.3.6.
 
+static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_RESPONSE = 0xF8
 See SH2 Ref. Manual 6.3.2.
 
+static const constexpr uint8_t SHTP_REPORT_PRODUCT_ID_REQUEST = 0xF9
 See SH2 Ref. Manual 6.3.1.
 
+static const constexpr uint8_t SHTP_REPORT_BASE_TIMESTAMP = 0xFB
 See SH2 Ref. Manual 7.2.1.
 
+static const constexpr uint8_t SHTP_REPORT_SET_FEATURE_COMMAND = 0xFD
 See SH2 Ref. Manual 6.5.4.
 
+static const constexpr uint8_t SENSOR_REPORTID_ACCELEROMETER = 0x01
 See SH2 Ref. Manual 6.5.9.
 
+static const constexpr uint8_t SENSOR_REPORTID_GYROSCOPE = 0x02
 See SH2 Ref. Manual 6.5.13.
 
+static const constexpr uint8_t SENSOR_REPORTID_MAGNETIC_FIELD = 0x03
 See SH2 Ref. Manual 6.5.16.
 
+static const constexpr uint8_t SENSOR_REPORTID_LINEAR_ACCELERATION = 0x04
 See SH2 Ref. Manual 6.5.10.
 
+static const constexpr uint8_t SENSOR_REPORTID_ROTATION_VECTOR = 0x05
 See SH2 Ref. Manual 6.5.18.
 
+static const constexpr uint8_t SENSOR_REPORTID_GRAVITY = 0x06
 See SH2 Ref. Manual 6.5.11.
 
+static const constexpr uint8_t SENSOR_REPORTID_UNCALIBRATED_GYRO = 0x07
 See SH2 Ref. Manual 6.5.14.
 
+static const constexpr uint8_t SENSOR_REPORTID_GAME_ROTATION_VECTOR = 0x08
 See SH2 Ref. Manual 6.5.19.
 
+static const constexpr uint8_t SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR = 0x09
 See SH2 Ref. Manual 6.5.20.
 
+static const constexpr uint8_t SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR = 0x2A
 See SH2 Ref. Manual 6.5.44.
 
+static const constexpr uint8_t SENSOR_REPORTID_TAP_DETECTOR = 0x10
 See SH2 Ref. Manual 6.5.27.
 
+static const constexpr uint8_t SENSOR_REPORTID_STEP_COUNTER = 0x11
 See SH2 Ref. Manual 6.5.29.
 
+static const constexpr uint8_t SENSOR_REPORTID_STABILITY_CLASSIFIER = 0x13
 See SH2 Ref. Manual 6.5.31.
 
+static const constexpr uint8_t SENSOR_REPORTID_RAW_ACCELEROMETER = 0x14
 See SH2 Ref. Manual 6.5.8.
 
+static const constexpr uint8_t SENSOR_REPORTID_RAW_GYROSCOPE = 0x15
 See SH2 Ref. Manual 6.5.12.
 
+static const constexpr uint8_t SENSOR_REPORTID_RAW_MAGNETOMETER = 0x16
 See SH2 Ref. Manual 6.5.15.
 
+static const constexpr uint8_t SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER = 0x1E
 See SH2 Ref. Manual 6.5.36.
 
+static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR = 0x28
 See SH2 Ref. Manual 6.5.42.
 
+static const constexpr uint8_t SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 0x29
 See SH2 Ref. Manual 6.5.43.
 
+static const constexpr uint8_t TARE_NOW = 0
 See SH2 Ref. Manual 6.4.4.1.
 
+static const constexpr uint8_t TARE_PERSIST = 1
 See SH2 Ref. Manual 6.4.4.2.
 
+static const constexpr uint8_t TARE_SET_REORIENTATION = 2
 See SH2 Ref. Manual 6.4.4.3.
 
+static const constexpr uint8_t TARE_AXIS_ALL = 0x07
 Tare all axes (used with tare now command)
 
+static const constexpr uint8_t TARE_AXIS_Z = 0x04
 Tar yaw axis only (used with tare now command)
 
+static const constexpr uint8_t TARE_ROTATION_VECTOR = 0
 Tare rotation vector.
 
+static const constexpr uint8_t TARE_GAME_ROTATION_VECTOR = 1
 Tare game rotation vector.
 
+static const constexpr uint8_t TARE_GEOMAGNETIC_ROTATION_VECTOR = 2
 tare geomagnetic rotation vector
 
+static const constexpr uint8_t TARE_GYRO_INTEGRATED_ROTATION_VECTOR = 3
 Tare gyro integrated rotation vector.
 
+static const constexpr uint8_t TARE_AR_VR_STABILIZED_ROTATION_VECTOR = 4
 Tare ARVR stabilized rotation vector.
 
+static const constexpr uint8_t TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR = 5
 Tare ARVR stabilized game rotation vector.
 
+static const constexpr char * TAG = "BNO08x"
 Class tag used for serial print statements.
 
+

Constructor & Destructor Documentation

+ +

◆ BNO08x()

+ +
+
+ + + + + + + + +
BNO08x::BNO08x (bno08x_config_t imu_config = default_imu_config)
+
+ +

BNO08x imu constructor.

+

Construct a BNO08x object for managing a BNO08x sensor. Initializes required GPIO pins, interrupts, SPI peripheral, and local task for SPI transactions.

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

Member Function Documentation

+ +

◆ calibrate_accelerometer()

+ +
+
+ + + + + + + +
void BNO08x::calibrate_accelerometer ()
+
+ +

Sends command to calibrate accelerometer.

+
Returns
void, nothing to return
+ +
+
+ +

◆ calibrate_all()

+ +
+
+ + + + + + + +
void BNO08x::calibrate_all ()
+
+ +

Sends command to calibrate accelerometer, gyro, and magnetometer.

+
Returns
void, nothing to return
+ +
+
+ +

◆ calibrate_gyro()

+ +
+
+ + + + + + + +
void BNO08x::calibrate_gyro ()
+
+ +

Sends command to calibrate gyro.

+
Returns
void, nothing to return
+ +
+
+ +

◆ calibrate_magnetometer()

+ +
+
+ + + + + + + +
void BNO08x::calibrate_magnetometer ()
+
+ +

Sends command to calibrate magnetometer.

+
Returns
void, nothing to return
+ +
+
+ +

◆ calibrate_planar_accelerometer()

+ +
+
+ + + + + + + +
void BNO08x::calibrate_planar_accelerometer ()
+
+ +

Sends command to calibrate planar accelerometer.

+
Returns
void, nothing to return
+ +
+
+ +

◆ calibration_complete()

+ +
+
+ + + + + + + +
bool BNO08x::calibration_complete ()
+
+ +

Returns true if calibration has completed.

+
Returns
void, nothing to return
+ +
+
+ +

◆ clear_tare()

+ +
+
+ + + + + + + +
void BNO08x::clear_tare ()
+
+ +

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

+
Returns
void, nothing to return
+ +
+
+ +

◆ data_available()

+ +
+
+ + + + + + + +
bool BNO08x::data_available ()
+
+ +

Checks if BNO08x has asserted interrupt and sent data.

+
Returns
true if new data has been parsed and saved
+ +
+
+ +

◆ enable_accelerometer()

+ +
+
+ + + + + + + + +
void BNO08x::enable_accelerometer (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_activity_classifier()

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

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

+
Parameters
+ + + + +
time_between_reportsDesired time between reports in miliseconds.
activities_to_enableDesired activities to enable (0x1F enables all).
activity_confidence_valsReturned activity level confidences.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_ARVR_stabilized_game_rotation_vector()

+ +
+
+ + + + + + + + +
void BNO08x::enable_ARVR_stabilized_game_rotation_vector (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_ARVR_stabilized_rotation_vector()

+ +
+
+ + + + + + + + +
void BNO08x::enable_ARVR_stabilized_rotation_vector (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_game_rotation_vector()

+ +
+
+ + + + + + + + +
void BNO08x::enable_game_rotation_vector (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_gravity()

+ +
+
+ + + + + + + + +
void BNO08x::enable_gravity (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_gyro()

+ +
+
+ + + + + + + + +
void BNO08x::enable_gyro (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_gyro_integrated_rotation_vector()

+ +
+
+ + + + + + + + +
void BNO08x::enable_gyro_integrated_rotation_vector (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_linear_accelerometer()

+ +
+
+ + + + + + + + +
void BNO08x::enable_linear_accelerometer (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_magnetometer()

+ +
+
+ + + + + + + + +
void BNO08x::enable_magnetometer (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_raw_accelerometer()

+ +
+
+ + + + + + + + +
void BNO08x::enable_raw_accelerometer (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_raw_gyro()

+ +
+
+ + + + + + + + +
void BNO08x::enable_raw_gyro (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_raw_magnetometer()

+ +
+
+ + + + + + + + +
void BNO08x::enable_raw_magnetometer (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_rotation_vector()

+ +
+
+ + + + + + + + +
void BNO08x::enable_rotation_vector (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_stability_classifier()

+ +
+
+ + + + + + + + +
void BNO08x::enable_stability_classifier (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_step_counter()

+ +
+
+ + + + + + + + +
void BNO08x::enable_step_counter (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_tap_detector()

+ +
+
+ + + + + + + + +
void BNO08x::enable_tap_detector (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ enable_uncalibrated_gyro()

+ +
+
+ + + + + + + + +
void BNO08x::enable_uncalibrated_gyro (uint16_t time_between_reports)
+
+ +

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

+
Parameters
+ + +
time_between_reportsDesired time between reports in miliseconds.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ end_calibration()

+ +
+
+ + + + + + + +
void BNO08x::end_calibration ()
+
+ +

Sends command to end calibration procedure.

+
Returns
void, nothing to return
+ +
+
+ +

◆ FRS_read_data()

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

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

+

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

+
Parameters
+ + + + +
record_IDWhich record ID/ sensor to request meta data from.
start_locationStart byte location.
words_to_readLength of words to read.
+
+
+
Returns
True if meta data read successfully.
+ +
+
+ +

◆ FRS_read_request()

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

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

+

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

+
Parameters
+ + + + +
record_IDWhich record ID/ sensor to request meta data from.
start_locationStart byte location.
words_to_readLength of words to read.
+
+
+
Returns
True if read request acknowledged (HINT was asserted)
+ +
+
+ +

◆ FRS_read_word()

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

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

+

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

+
Parameters
+ + + +
record_IDWhich record ID/ sensor to request meta data from.
word_numberDesired word to read.
+
+
+
Returns
Requested meta data word, 0 if failed.
+ +
+
+ +

◆ get_accel()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void BNO08x::get_accel (float & x,
float & y,
float & z,
uint8_t & accuracy 
)
+
+ +

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

+
Parameters
+ + + + + +
xReference variable to save X axis acceleration.
yReference variable to save Y axis acceleration.
zReference variable to save Z axis acceleration.
accuracyReference variable to save reported acceleration accuracy.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ get_accel_accuracy()

+ +
+
+ + + + + + + +
uint8_t BNO08x::get_accel_accuracy ()
+
+ +

Get accuracy of linear acceleration.

+
Returns
Accuracy of linear acceleration.
+ +
+
+ +

◆ get_accel_X()

+ +
+
+ + + + + + + +
float BNO08x::get_accel_X ()
+
+ +

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

+
Returns
The angular reported x axis acceleration.
+ +
+
+ +

◆ get_accel_Y()

+ +
+
+ + + + + + + +
float BNO08x::get_accel_Y ()
+
+ +

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

+
Returns
The angular reported y axis acceleration.
+ +
+
+ +

◆ get_accel_Z()

+ +
+
+ + + + + + + +
float BNO08x::get_accel_Z ()
+
+ +

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

+
Returns
The angular reported z axis acceleration.
+ +
+
+ +

◆ get_activity_classifier()

+ +
+
+ + + + + + + +
uint8_t BNO08x::get_activity_classifier ()
+
+ +

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

+
Returns
The current activity: 0 = unknown 1 = in vehicle 2 = on bicycle 3 = on foot 4 = still 5 = tilting 6 = walking 7 = runnning 8 = on stairs
+ +
+
+ +

◆ get_gravity()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void BNO08x::get_gravity (float & x,
float & y,
float & z,
uint8_t & accuracy 
)
+
+ +

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

+
Parameters
+ + + + + +
xReference variable to save X axis gravity.
yReference variable to save Y axis axis gravity.
zReference variable to save Z axis axis gravity.
accuracyReference variable to save reported gravity accuracy.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ get_gravity_accuracy()

+ +
+
+ + + + + + + +
uint8_t BNO08x::get_gravity_accuracy ()
+
+ +

Get the reported gravity accuracy.

+
Returns
Accuracy of reported gravity.
+
+ +
+
+ +

◆ get_gravity_X()

+ +
+
+ + + + + + + +
float BNO08x::get_gravity_X ()
+
+ +

Get the reported x axis gravity.

+
Returns
x axis gravity in m/s^2
+ +
+
+ +

◆ get_gravity_Y()

+ +
+
+ + + + + + + +
float BNO08x::get_gravity_Y ()
+
+ +

Get the reported y axis gravity.

+
Returns
y axis gravity in m/s^2
+ +
+
+ +

◆ get_gravity_Z()

+ +
+
+ + + + + + + +
float BNO08x::get_gravity_Z ()
+
+ +

Get the reported z axis gravity.

+
Returns
z axis gravity in m/s^2
+ +
+
+ +

◆ get_gyro_accuracy()

+ +
+
+ + + + + + + +
uint8_t BNO08x::get_gyro_accuracy ()
+
+ +

Get calibrated gyro accuracy.

+
Returns
Accuracy of calibrated gyro.
+ +
+
+ +

◆ get_gyro_calibrated_velocity()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void BNO08x::get_gyro_calibrated_velocity (float & x,
float & y,
float & z,
uint8_t & accuracy 
)
+
+ +

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

+
Parameters
+ + + + + +
xReference variable to save X axis angular velocity
yReference variable to save Y axis angular velocity
zReference variable to save Z axis angular velocity
accuracyReference variable to save reported gyro accuracy.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ get_gyro_calibrated_velocity_X()

+ +
+
+ + + + + + + +
float BNO08x::get_gyro_calibrated_velocity_X ()
+
+ +

Get calibrated gyro x axis angular velocity measurement.

+
Returns
The angular reported x axis angular velocity from calibrated gyro (drift compensation applied).
+ +
+
+ +

◆ get_gyro_calibrated_velocity_Y()

+ +
+
+ + + + + + + +
float BNO08x::get_gyro_calibrated_velocity_Y ()
+
+ +

Get calibrated gyro y axis angular velocity measurement.

+
Returns
The angular reported y axis angular velocity from calibrated gyro (drift compensation applied).
+ +
+
+ +

◆ get_gyro_calibrated_velocity_Z()

+ +
+
+ + + + + + + +
float BNO08x::get_gyro_calibrated_velocity_Z ()
+
+ +

Get calibrated gyro z axis angular velocity measurement.

+
Returns
The angular reported z axis angular velocity from calibrated gyro (drift compensation applied).
+ +
+
+ +

◆ get_gyro_velocity()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + +
void BNO08x::get_gyro_velocity (float & x,
float & y,
float & z 
)
+
+ +

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

+
Parameters
+ + + + +
xReference variable to save X axis angular velocity
yReference variable to save Y axis angular velocity
zReference variable to save Z axis angular velocity
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ get_gyro_velocity_X()

+ +
+
+ + + + + + + +
float BNO08x::get_gyro_velocity_X ()
+
+ +

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

+
Returns
The reported x axis angular velocity.
+ +
+
+ +

◆ get_gyro_velocity_Y()

+ +
+
+ + + + + + + +
float BNO08x::get_gyro_velocity_Y ()
+
+ +

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

+
Returns
The reported y axis angular velocity.
+ +
+
+ +

◆ get_gyro_velocity_Z()

+ +
+
+ + + + + + + +
float BNO08x::get_gyro_velocity_Z ()
+
+ +

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

+
Returns
The reported Z axis angular velocity.
+ +
+
+ +

◆ get_linear_accel()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void BNO08x::get_linear_accel (float & x,
float & y,
float & z,
uint8_t & accuracy 
)
+
+ +

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

+
Parameters
+ + + + + +
xReference variable to save X axis acceleration.
yReference variable to save Y axis acceleration.
zReference variable to save Z axis acceleration.
accuracyReference variable to save reported linear acceleration accuracy.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ get_linear_accel_accuracy()

+ +
+
+ + + + + + + +
uint8_t BNO08x::get_linear_accel_accuracy ()
+
+ +

Get accuracy of linear acceleration.

+
Returns
Accuracy of linear acceleration.
+ +
+
+ +

◆ get_linear_accel_X()

+ +
+
+ + + + + + + +
float BNO08x::get_linear_accel_X ()
+
+ +

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

+
Returns
The angular reported x axis linear acceleration.
+ +
+
+ +

◆ get_linear_accel_Y()

+ +
+
+ + + + + + + +
float BNO08x::get_linear_accel_Y ()
+
+ +

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

+
Returns
The angular reported y axis linear acceleration.
+ +
+
+ +

◆ get_linear_accel_Z()

+ +
+
+ + + + + + + +
float BNO08x::get_linear_accel_Z ()
+
+ +

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

+
Returns
The angular reported z axis linear acceleration.
+ +
+
+ +

◆ get_magf()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void BNO08x::get_magf (float & x,
float & y,
float & z,
uint8_t & accuracy 
)
+
+ +

Get the full magnetic field vector.

+
Parameters
+ + + + + +
xReference variable to save reported x magnitude.
yReference variable to save reported y magnitude.
xReference variable to save reported z magnitude.
accuracyReference variable save reported accuracy.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ get_magf_accuracy()

+ +
+
+ + + + + + + +
uint8_t BNO08x::get_magf_accuracy ()
+
+ +

Get accuracy of reported magnetic field vector.

+
Returns
The accuracy of reported magnetic field vector.
+ +
+
+ +

◆ get_magf_X()

+ +
+
+ + + + + + + +
float BNO08x::get_magf_X ()
+
+ +

Get X component of magnetic field vector.

+
Returns
The reported X component of magnetic field vector.
+ +
+
+ +

◆ get_magf_Y()

+ +
+
+ + + + + + + +
float BNO08x::get_magf_Y ()
+
+ +

Get Y component of magnetic field vector.

+
Returns
The reported Y component of magnetic field vector.
+ +
+
+ +

◆ get_magf_Z()

+ +
+
+ + + + + + + +
float BNO08x::get_magf_Z ()
+
+ +

Get Z component of magnetic field vector.

+
Returns
The reported Z component of magnetic field vector.
+ +
+
+ +

◆ get_pitch()

+ +
+
+ + + + + + + +
float BNO08x::get_pitch ()
+
+ +

Get the reported rotation about y axis.

+
Returns
Rotation about the y axis in radians.
+ +
+
+ +

◆ get_pitch_deg()

+ +
+
+ + + + + + + +
float BNO08x::get_pitch_deg ()
+
+ +

Get the reported rotation about y axis.

+
Returns
Rotation about the y axis in degrees.
+ +
+
+ +

◆ get_Q1()

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

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

+

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

+
Parameters
+ + +
record_IDWhich record ID/ sensor to get Q1 value for.
+
+
+
Returns
Q1 value for requested sensor.
+ +
+
+ +

◆ get_Q2()

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

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

+

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

+
Parameters
+ + +
record_IDWhich record ID/ sensor to get Q2 value for.
+
+
+
Returns
Q2 value for requested sensor.
+ +
+
+ +

◆ get_Q3()

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

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

+

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

+
Parameters
+ + +
record_IDWhich record ID/ sensor to get Q3 value for.
+
+
+
Returns
Q3 value for requested sensor.
+ +
+
+ +

◆ get_quat()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void BNO08x::get_quat (float & i,
float & j,
float & k,
float & real,
float & rad_accuracy,
uint8_t & accuracy 
)
+
+ +

Get the full quaternion reading.

+
Parameters
+ + + + + + + +
iReference variable to save reported i component of quaternion.
jReference variable to save reported j component of quaternion.
kReference variable to save reported k component of quaternion.
realReference variable to save reported real component of quaternion.
rad_accuracyReference variable to save reported raw quaternion radian accuracy.
accuracyReference variable to save reported quaternion accuracy.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ get_quat_accuracy()

+ +
+
+ + + + + + + +
uint8_t BNO08x::get_quat_accuracy ()
+
+ +

Get accuracy of reported quaternion.

+
Returns
The accuracy of reported quaternion.
+ +
+
+ +

◆ get_quat_I()

+ +
+
+ + + + + + + +
float BNO08x::get_quat_I ()
+
+ +

Get I component of reported quaternion.

+
Returns
The I component of reported quaternion.
+ +
+
+ +

◆ get_quat_J()

+ +
+
+ + + + + + + +
float BNO08x::get_quat_J ()
+
+ +

Get J component of reported quaternion.

+
Returns
The J component of reported quaternion.
+ +
+
+ +

◆ get_quat_K()

+ +
+
+ + + + + + + +
float BNO08x::get_quat_K ()
+
+ +

Get K component of reported quaternion.

+
Returns
The K component of reported quaternion.
+ +
+
+ +

◆ get_quat_radian_accuracy()

+ +
+
+ + + + + + + +
float BNO08x::get_quat_radian_accuracy ()
+
+ +

Get radian accuracy of reported quaternion.

+
Returns
The radian accuracy of reported quaternion.
+ +
+
+ +

◆ get_quat_real()

+ +
+
+ + + + + + + +
float BNO08x::get_quat_real ()
+
+ +

Get real component of reported quaternion.

+
Returns
The real component of reported quaternion.
+ +
+
+ +

◆ get_range()

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

Gets range from BNO08x FRS (flash record system).

+
Parameters
+ + +
record_IDWhich record ID/ sensor to get range value for.
+
+
+
Returns
The range value for the requested sensor.
+ +
+
+ +

◆ get_raw_accel_X()

+ +
+
+ + + + + + + +
int16_t BNO08x::get_raw_accel_X ()
+
+ +

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

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

◆ get_raw_accel_Y()

+ +
+
+ + + + + + + +
int16_t BNO08x::get_raw_accel_Y ()
+
+ +

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

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

◆ get_raw_accel_Z()

+ +
+
+ + + + + + + +
int16_t BNO08x::get_raw_accel_Z ()
+
+ +

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

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

◆ get_raw_gyro_X()

+ +
+
+ + + + + + + +
int16_t BNO08x::get_raw_gyro_X ()
+
+ +

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

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

◆ get_raw_gyro_Y()

+ +
+
+ + + + + + + +
int16_t BNO08x::get_raw_gyro_Y ()
+
+ +

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

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

◆ get_raw_gyro_Z()

+ +
+
+ + + + + + + +
int16_t BNO08x::get_raw_gyro_Z ()
+
+ +

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

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

◆ get_raw_magf_X()

+ +
+
+ + + + + + + +
int16_t BNO08x::get_raw_magf_X ()
+
+ +

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

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

◆ get_raw_magf_Y()

+ +
+
+ + + + + + + +
int16_t BNO08x::get_raw_magf_Y ()
+
+ +

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

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

◆ get_raw_magf_Z()

+ +
+
+ + + + + + + +
int16_t BNO08x::get_raw_magf_Z ()
+
+ +

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

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

◆ get_readings()

+ +
+
+ + + + + + + +
uint16_t BNO08x::get_readings ()
+
+ +

Waits for BNO08x HINT pin to assert, and parses the received data.

+
Returns
void, nothing to return
+ +
+
+ +

◆ get_reset_reason()

+ +
+
+ + + + + + + +
uint8_t BNO08x::get_reset_reason ()
+
+ +

Get the reason for the most recent reset.

+
Returns
The reason for the most recent recent reset ( 1 = POR (power on reset), 2 = internal reset, 3 = watchdog timer, 4 = external reset 5 = other)
+ +
+
+ +

◆ get_resolution()

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

Gets resolution from BNO08x FRS (flash record system).

+
Parameters
+ + +
record_IDWhich record ID/ sensor to get resolution value for.
+
+
+
Returns
The resolution value for the requested sensor.
+ +
+
+ +

◆ get_roll()

+ +
+
+ + + + + + + +
float BNO08x::get_roll ()
+
+ +

Get the reported rotation about x axis.

+
Returns
Rotation about the x axis in radians.
+ +
+
+ +

◆ get_roll_deg()

+ +
+
+ + + + + + + +
float BNO08x::get_roll_deg ()
+
+ +

Get the reported rotation about x axis.

+
Returns
Rotation about the x axis in degrees.
+ +
+
+ +

◆ get_stability_classifier()

+ +
+
+ + + + + + + +
int8_t BNO08x::get_stability_classifier ()
+
+ +

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

+
Returns
The current stability (0 = unknown, 1 = on table, 2 = stationary)
+ +
+
+ +

◆ get_step_count()

+ +
+
+ + + + + + + +
uint16_t BNO08x::get_step_count ()
+
+ +

Get the counted amount of steps.

+
Returns
The current amount of counted steps.
+ +
+
+ +

◆ get_tap_detector()

+ +
+
+ + + + + + + +
uint8_t BNO08x::get_tap_detector ()
+
+ +

Get if tap has occured.

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

◆ get_time_stamp()

+ +
+
+ + + + + + + +
uint32_t BNO08x::get_time_stamp ()
+
+ +

Return timestamp of most recent report.

+
Returns
void, nothing to return
+ +
+
+ +

◆ get_uncalibrated_gyro()

+ +
+
+ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +
void BNO08x::get_uncalibrated_gyro (float & x,
float & y,
float & z,
float & b_x,
float & b_y,
float & b_z,
uint8_t & accuracy 
)
+
+ +

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

+
Parameters
+ + + + + + + + +
xReference variable to save X axis angular velocity
yReference variable to save Y axis angular velocity
zReference variable to save Z axis angular velocity
b_xReference variable to save X axis drift estimate
b_yReference variable to save Y axis drift estimate
b_zReference variable to save Z axis drift estimate
accuracyReference variable to save reported gyro accuracy.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ get_uncalibrated_gyro_accuracy()

+ +
+
+ + + + + + + +
uint8_t BNO08x::get_uncalibrated_gyro_accuracy ()
+
+ +

Get uncalibrated gyro accuracy.

+
Returns
Accuracy of uncalibrated gyro.
+ +
+
+ +

◆ get_uncalibrated_gyro_bias_X()

+ +
+
+ + + + + + + +
float BNO08x::get_uncalibrated_gyro_bias_X ()
+
+ +

Get uncalibrated gyro x axis drift estimate.

+
Returns
The angular reported x axis drift estimate.
+ +
+
+ +

◆ get_uncalibrated_gyro_bias_Y()

+ +
+
+ + + + + + + +
float BNO08x::get_uncalibrated_gyro_bias_Y ()
+
+ +

Get uncalibrated gyro Y axis drift estimate.

+
Returns
The angular reported Y axis drift estimate.
+ +
+
+ +

◆ get_uncalibrated_gyro_bias_Z()

+ +
+
+ + + + + + + +
float BNO08x::get_uncalibrated_gyro_bias_Z ()
+
+ +

Get uncalibrated gyro Z axis drift estimate.

+
Returns
The angular reported Z axis drift estimate.
+ +
+
+ +

◆ get_uncalibrated_gyro_X()

+ +
+
+ + + + + + + +
float BNO08x::get_uncalibrated_gyro_X ()
+
+ +

Get uncalibrated gyro x axis angular velocity measurement.

+
Returns
The angular reported x axis angular velocity from uncalibrated gyro.
+ +
+
+ +

◆ get_uncalibrated_gyro_Y()

+ +
+
+ + + + + + + +
float BNO08x::get_uncalibrated_gyro_Y ()
+
+ +

Get uncalibrated gyro Y axis angular velocity measurement.

+
Returns
The angular reported Y axis angular velocity from uncalibrated gyro.
+ +
+
+ +

◆ get_uncalibrated_gyro_Z()

+ +
+
+ + + + + + + +
float BNO08x::get_uncalibrated_gyro_Z ()
+
+ +

Get uncalibrated gyro Z axis angular velocity measurement.

+
Returns
The angular reported Z axis angular velocity from uncalibrated gyro.
+ +
+
+ +

◆ get_yaw()

+ +
+
+ + + + + + + +
float BNO08x::get_yaw ()
+
+ +

Get the reported rotation about z axis.

+
Returns
Rotation about the z axis in radians.
+ +
+
+ +

◆ get_yaw_deg()

+ +
+
+ + + + + + + +
float BNO08x::get_yaw_deg ()
+
+ +

Get the reported rotation about z axis.

+
Returns
Rotation about the z axis in degrees.
+ +
+
+ +

◆ hard_reset()

+ +
+
+ + + + + + + +
bool BNO08x::hard_reset ()
+
+ +

Hard resets BNO08x sensor.

+
Returns
void, nothing to return
+ +
+
+ +

◆ hint_handler()

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

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

+

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

+
Returns
void, nothing to return
+ +
+
+ +

◆ initialize()

+ +
+
+ + + + + + + +
bool BNO08x::initialize ()
+
+ +

Initializes BNO08x sensor.

+

Resets sensor and goes through initializing process outlined in BNO08x datasheet.

+
Returns
void, nothing to return
+ +
+
+ +

◆ mode_on()

+ +
+
+ + + + + + + +
bool BNO08x::mode_on ()
+
+ +

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

+
Returns
True if exiting sleep mode was success.
+ +
+
+ +

◆ mode_sleep()

+ +
+
+ + + + + + + +
bool BNO08x::mode_sleep ()
+
+ +

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

+
Returns
True if entering sleep mode was success.
+ +
+
+ +

◆ parse_command_report()

+ +
+
+ + + + + + + +
uint16_t BNO08x::parse_command_report ()
+
+ +

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

+
Returns
The command report ID, 0 if invalid.
+ +
+
+ +

◆ parse_input_report()

+ +
+
+ + + + + + + +
uint16_t BNO08x::parse_input_report ()
+
+ +

Parses received input report sent by BNO08x.

+

Unit responds with packet that contains the following:

+

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

+
Returns
void, nothing to return
+ +
+
+ +

◆ print_header()

+ +
+
+ + + + + + + +
void BNO08x::print_header ()
+
+ +

Prints the most recently received SHTP header to serial console with ESP_LOG statement.

+
Returns
void, nothing to return
+ +
+
+ +

◆ q_to_float()

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

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

+
Parameters
+ + + +
q_pointQ point value associated with register.
fixed_point_valueThe fixed point value to convert.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ queue_calibrate_command()

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

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

+
Parameters
+ + +
sensor_to_calibrateThe sensor to calibrate.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ queue_command()

+ +
+
+ + + + + +
+ + + + + + + + +
void BNO08x::queue_command (uint8_t command)
+
+private
+
+ +

Queues a packet containing a command.

+
Parameters
+ + +
commandThe command to be sent.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ queue_feature_command() [1/2]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void BNO08x::queue_feature_command (uint8_t report_ID,
uint16_t time_between_reports 
)
+
+private
+
+ +

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

+
Parameters
+ + + +
report_IDID of sensor report being requested.
time_between_reportsDesired time between reports.
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ queue_feature_command() [2/2]

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + + + + + + + +
void BNO08x::queue_feature_command (uint8_t report_ID,
uint16_t time_between_reports,
uint32_t specific_config 
)
+
+private
+
+ +

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

+
Parameters
+ + + + +
report_IDID of sensor report to be enabled.
time_between_reportsDesired time between reports in miliseconds.
specific_configSpecific config word (used with personal activity classifier)
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ queue_packet()

+ +
+
+ + + + + +
+ + + + + + + + + + + + + + + + + + +
void BNO08x::queue_packet (uint8_t channel_number,
uint8_t data_length 
)
+
+private
+
+ +

Queues an SHTP packet to be sent via SPI.

+
Returns
void, nothing to return
+ +
+
+ +

◆ queue_request_product_id_command()

+ +
+
+ + + + + +
+ + + + + + + +
void BNO08x::queue_request_product_id_command ()
+
+private
+
+ +

Queues a packet containing the request product ID command.

+
Returns
void, nothing to return
+ +
+
+ +

◆ queue_tare_command()

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

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

+
Parameters
+ + + + +
commandTare command to be sent.
+
axisSpecified axis (can be z or all at once)
rotation_vector_basisWhich rotation vector type to zero axes of, BNO08x saves seperate data for Rotation Vector, Gaming Rotation Vector, etc..)
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ receive_packet()

+ +
+
+ + + + + +
+ + + + + + + +
bool BNO08x::receive_packet ()
+
+private
+
+ +

Receives a SHTP packet via SPI.

+
Returns
void, nothing to return
+ +
+
+ +

◆ request_calibration_status()

+ +
+
+ + + + + + + +
void BNO08x::request_calibration_status ()
+
+ +

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

+
Returns
void, nothing to return
+ +
+
+ +

◆ run_full_calibration_routine()

+ +
+
+ + + + + + + +
bool BNO08x::run_full_calibration_routine ()
+
+ +

Runs full calibration routine.

+

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

+
Returns
void, nothing to return
+ +
+
+ +

◆ save_calibration()

+ +
+
+ + + + + + + +
void BNO08x::save_calibration ()
+
+ +

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

+
Returns
void, nothing to return
+ +
+
+ +

◆ save_tare()

+ +
+
+ + + + + + + +
void BNO08x::save_tare ()
+
+ +

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

+
Returns
void, nothing to return
+ +
+
+ +

◆ send_packet()

+ +
+
+ + + + + +
+ + + + + + + +
void BNO08x::send_packet ()
+
+private
+
+ +

Sends a queued SHTP packet via SPI.

+
Returns
void, nothing to return
+ +
+
+ +

◆ soft_reset()

+ +
+
+ + + + + + + +
bool BNO08x::soft_reset ()
+
+ +

Soft resets BNO08x sensor using executable channel.

+
Returns
True if reset was success.
+ +
+
+ +

◆ spi_task()

+ +
+
+ + + + + +
+ + + + + + + +
void BNO08x::spi_task ()
+
+private
+
+ +

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

+
Returns
void, nothing to return
+ +
+
+ +

◆ spi_task_trampoline()

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

Static function used to launch spi task.

+

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

+
Returns
void, nothing to return
+ +
+
+ +

◆ tare_now()

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

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

+
Parameters
+ + + +
axis_selWhich axes to zero, can be TARE_AXIS_ALL (all axes) or TARE_AXIS_Z (only yaw)
rotation_vector_basisWhich rotation vector type to zero axes can be TARE_ROTATION_VECTOR, TARE_GAME_ROTATION_VECTOR, TARE_GEOMAGNETIC_ROTATION_VECTOR, etc..
+
+
+
Returns
void, nothing to return
+ +
+
+ +

◆ wait_for_device_int()

+ +
+
+ + + + + +
+ + + + + + + +
bool BNO08x::wait_for_device_int ()
+
+private
+
+ +

Re-enables interrupts and waits for BNO08x to assert HINT pin.

+
Returns
void, nothing to return
+ +
+
+
The documentation for this class was generated from the following files:
    +
  • D:/development/git/esp32_BNO08x/BNO08x.hpp
  • +
  • D:/development/git/esp32_BNO08x/BNO08x.cpp
  • +
+
+ + + + diff --git a/documentation/html/classes.html b/documentation/html/classes.html new file mode 100644 index 0000000..092d17d --- /dev/null +++ b/documentation/html/classes.html @@ -0,0 +1,88 @@ + + + + + + + +esp32_BNO08x: Class Index + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Class Index
+
+ + + + + diff --git a/documentation/html/closed.png b/documentation/html/closed.png new file mode 100644 index 0000000..98cc2c9 Binary files /dev/null and b/documentation/html/closed.png differ diff --git a/documentation/html/dir_275089585c7fc1b5fd5d7d42c69cb1da.html b/documentation/html/dir_275089585c7fc1b5fd5d7d42c69cb1da.html new file mode 100644 index 0000000..9c8b04c --- /dev/null +++ b/documentation/html/dir_275089585c7fc1b5fd5d7d42c69cb1da.html @@ -0,0 +1,86 @@ + + + + + + + +esp32_BNO08x: D: Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
D: Directory Reference
+
+
+
+ + + + diff --git a/documentation/html/dir_575a586a6cee2959cc416e08c83a9494.html b/documentation/html/dir_575a586a6cee2959cc416e08c83a9494.html new file mode 100644 index 0000000..b7ce909 --- /dev/null +++ b/documentation/html/dir_575a586a6cee2959cc416e08c83a9494.html @@ -0,0 +1,92 @@ + + + + + + + +esp32_BNO08x: D:/development/git/esp32_BNO08x Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
esp32_BNO08x Directory Reference
+
+
+ + + + +

+Files

 BNO08x.hpp
 
+
+ + + + diff --git a/documentation/html/dir_b281f91a3dfded60c30f3d31da444793.html b/documentation/html/dir_b281f91a3dfded60c30f3d31da444793.html new file mode 100644 index 0000000..3492f7a --- /dev/null +++ b/documentation/html/dir_b281f91a3dfded60c30f3d31da444793.html @@ -0,0 +1,92 @@ + + + + + + + +esp32_BNO08x: D:/development/git Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
git Directory Reference
+
+
+ + + + +

+Directories

 esp32_BNO08x
 
+
+ + + + diff --git a/documentation/html/dir_ebea21e7cbc239e4b984a419d2ec33b9.html b/documentation/html/dir_ebea21e7cbc239e4b984a419d2ec33b9.html new file mode 100644 index 0000000..3cfc9cc --- /dev/null +++ b/documentation/html/dir_ebea21e7cbc239e4b984a419d2ec33b9.html @@ -0,0 +1,86 @@ + + + + + + + +esp32_BNO08x: D:/development Directory Reference + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ + +
+
+
development Directory Reference
+
+
+
+ + + + diff --git a/documentation/html/doc.svg b/documentation/html/doc.svg new file mode 100644 index 0000000..0b928a5 --- /dev/null +++ b/documentation/html/doc.svg @@ -0,0 +1,12 @@ + + + + + + + + + + + diff --git a/documentation/html/docd.svg b/documentation/html/docd.svg new file mode 100644 index 0000000..ac18b27 --- /dev/null +++ b/documentation/html/docd.svg @@ -0,0 +1,12 @@ + + + + + + + + + + + diff --git a/documentation/html/doxygen.css b/documentation/html/doxygen.css new file mode 100644 index 0000000..0caa19b --- /dev/null +++ b/documentation/html/doxygen.css @@ -0,0 +1,2017 @@ +/* The standard CSS for doxygen 1.9.7*/ + +html { +/* page base colors */ +--page-background-color: white; +--page-foreground-color: black; +--page-link-color: #3D578C; +--page-visited-link-color: #4665A2; + +/* index */ +--index-odd-item-bg-color: #F8F9FC; +--index-even-item-bg-color: white; +--index-header-color: black; +--index-separator-color: #A0A0A0; + +/* header */ +--header-background-color: #F9FAFC; +--header-separator-color: #C4CFE5; +--header-gradient-image: url('nav_h.png'); +--group-header-separator-color: #879ECB; +--group-header-color: #354C7B; +--inherit-header-color: gray; + +--footer-foreground-color: #2A3D61; +--footer-logo-width: 104px; +--citation-label-color: #334975; +--glow-color: cyan; + +--title-background-color: white; +--title-separator-color: #5373B4; +--directory-separator-color: #9CAFD4; +--separator-color: #4A6AAA; + +--blockquote-background-color: #F7F8FB; +--blockquote-border-color: #9CAFD4; + +--scrollbar-thumb-color: #9CAFD4; +--scrollbar-background-color: #F9FAFC; + +--icon-background-color: #728DC1; +--icon-foreground-color: white; +--icon-doc-image: url('doc.svg'); +--icon-folder-open-image: url('folderopen.svg'); +--icon-folder-closed-image: url('folderclosed.svg'); + +/* brief member declaration list */ +--memdecl-background-color: #F9FAFC; +--memdecl-separator-color: #DEE4F0; +--memdecl-foreground-color: #555; +--memdecl-template-color: #4665A2; + +/* detailed member list */ +--memdef-border-color: #A8B8D9; +--memdef-title-background-color: #E2E8F2; +--memdef-title-gradient-image: url('nav_f.png'); +--memdef-proto-background-color: #DFE5F1; +--memdef-proto-text-color: #253555; +--memdef-proto-text-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); +--memdef-doc-background-color: white; +--memdef-param-name-color: #602020; +--memdef-template-color: #4665A2; + +/* tables */ +--table-cell-border-color: #2D4068; +--table-header-background-color: #374F7F; +--table-header-foreground-color: #FFFFFF; + +/* labels */ +--label-background-color: #728DC1; +--label-left-top-border-color: #5373B4; +--label-right-bottom-border-color: #C4CFE5; +--label-foreground-color: white; + +/** navigation bar/tree/menu */ +--nav-background-color: #F9FAFC; +--nav-foreground-color: #364D7C; +--nav-gradient-image: url('tab_b.png'); +--nav-gradient-hover-image: url('tab_h.png'); +--nav-gradient-active-image: url('tab_a.png'); +--nav-gradient-active-image-parent: url("../tab_a.png"); +--nav-separator-image: url('tab_s.png'); +--nav-breadcrumb-image: url('bc_s.png'); +--nav-breadcrumb-border-color: #C2CDE4; +--nav-splitbar-image: url('splitbar.png'); +--nav-font-size-level1: 13px; +--nav-font-size-level2: 10px; +--nav-font-size-level3: 9px; +--nav-text-normal-color: #283A5D; +--nav-text-hover-color: white; +--nav-text-active-color: white; +--nav-text-normal-shadow: 0px 1px 1px rgba(255, 255, 255, 0.9); +--nav-text-hover-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); +--nav-text-active-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); +--nav-menu-button-color: #364D7C; +--nav-menu-background-color: white; +--nav-menu-foreground-color: #555555; +--nav-menu-toggle-color: rgba(255, 255, 255, 0.5); +--nav-arrow-color: #9CAFD4; +--nav-arrow-selected-color: #9CAFD4; + +/* table of contents */ +--toc-background-color: #F4F6FA; +--toc-border-color: #D8DFEE; +--toc-header-color: #4665A2; +--toc-down-arrow-image: url("data:image/svg+xml;utf8,&%238595;"); + +/** search field */ +--search-background-color: white; +--search-foreground-color: #909090; +--search-magnification-image: url('mag.svg'); +--search-magnification-select-image: url('mag_sel.svg'); +--search-active-color: black; +--search-filter-background-color: #F9FAFC; +--search-filter-foreground-color: black; +--search-filter-border-color: #90A5CE; +--search-filter-highlight-text-color: white; +--search-filter-highlight-bg-color: #3D578C; +--search-results-foreground-color: #425E97; +--search-results-background-color: #EEF1F7; +--search-results-border-color: black; +--search-box-shadow: inset 0.5px 0.5px 3px 0px #555; + +/** code fragments */ +--code-keyword-color: #008000; +--code-type-keyword-color: #604020; +--code-flow-keyword-color: #E08000; +--code-comment-color: #800000; +--code-preprocessor-color: #806020; +--code-string-literal-color: #002080; +--code-char-literal-color: #008080; +--code-xml-cdata-color: black; +--code-vhdl-digit-color: #FF00FF; +--code-vhdl-char-color: #000000; +--code-vhdl-keyword-color: #700070; +--code-vhdl-logic-color: #FF0000; +--code-link-color: #4665A2; +--code-external-link-color: #4665A2; +--fragment-foreground-color: black; +--fragment-background-color: #FBFCFD; +--fragment-border-color: #C4CFE5; +--fragment-lineno-border-color: #00FF00; +--fragment-lineno-background-color: #E8E8E8; +--fragment-lineno-foreground-color: black; +--fragment-lineno-link-fg-color: #4665A2; +--fragment-lineno-link-bg-color: #D8D8D8; +--fragment-lineno-link-hover-fg-color: #4665A2; +--fragment-lineno-link-hover-bg-color: #C8C8C8; +--tooltip-foreground-color: black; +--tooltip-background-color: white; +--tooltip-border-color: gray; +--tooltip-doc-color: grey; +--tooltip-declaration-color: #006318; +--tooltip-link-color: #4665A2; +--tooltip-shadow: 1px 1px 7px gray; + +/** font-family */ +--font-family-normal: Roboto,sans-serif; +--font-family-monospace: 'JetBrains Mono',Consolas,Monaco,'Andale Mono','Ubuntu Mono',monospace,fixed; +--font-family-nav: 'Lucida Grande',Geneva,Helvetica,Arial,sans-serif; +--font-family-title: Tahoma,Arial,sans-serif; +--font-family-toc: Verdana,'DejaVu Sans',Geneva,sans-serif; +--font-family-search: Arial,Verdana,sans-serif; +--font-family-icon: Arial,Helvetica; +--font-family-tooltip: Roboto,sans-serif; + +} + +@media (prefers-color-scheme: dark) { + html:not(.dark-mode) { + color-scheme: dark; + +/* page base colors */ +--page-background-color: black; +--page-foreground-color: #C9D1D9; +--page-link-color: #90A5CE; +--page-visited-link-color: #A3B4D7; + +/* index */ +--index-odd-item-bg-color: #0B101A; +--index-even-item-bg-color: black; +--index-header-color: #C4CFE5; +--index-separator-color: #334975; + +/* header */ +--header-background-color: #070B11; +--header-separator-color: #141C2E; +--header-gradient-image: url('nav_hd.png'); +--group-header-separator-color: #283A5D; +--group-header-color: #90A5CE; +--inherit-header-color: #A0A0A0; + +--footer-foreground-color: #5B7AB7; +--footer-logo-width: 60px; +--citation-label-color: #90A5CE; +--glow-color: cyan; + +--title-background-color: #090D16; +--title-separator-color: #354C79; +--directory-separator-color: #283A5D; +--separator-color: #283A5D; + +--blockquote-background-color: #101826; +--blockquote-border-color: #283A5D; + +--scrollbar-thumb-color: #283A5D; +--scrollbar-background-color: #070B11; + +--icon-background-color: #334975; +--icon-foreground-color: #C4CFE5; +--icon-doc-image: url('docd.svg'); +--icon-folder-open-image: url('folderopend.svg'); +--icon-folder-closed-image: url('folderclosedd.svg'); + +/* brief member declaration list */ +--memdecl-background-color: #0B101A; +--memdecl-separator-color: #2C3F65; +--memdecl-foreground-color: #BBB; +--memdecl-template-color: #7C95C6; + +/* detailed member list */ +--memdef-border-color: #233250; +--memdef-title-background-color: #1B2840; +--memdef-title-gradient-image: url('nav_fd.png'); +--memdef-proto-background-color: #19243A; +--memdef-proto-text-color: #9DB0D4; +--memdef-proto-text-shadow: 0px 1px 1px rgba(0, 0, 0, 0.9); +--memdef-doc-background-color: black; +--memdef-param-name-color: #D28757; +--memdef-template-color: #7C95C6; + +/* tables */ +--table-cell-border-color: #283A5D; +--table-header-background-color: #283A5D; +--table-header-foreground-color: #C4CFE5; + +/* labels */ +--label-background-color: #354C7B; +--label-left-top-border-color: #4665A2; +--label-right-bottom-border-color: #283A5D; +--label-foreground-color: #CCCCCC; + +/** navigation bar/tree/menu */ +--nav-background-color: #101826; +--nav-foreground-color: #364D7C; +--nav-gradient-image: url('tab_bd.png'); +--nav-gradient-hover-image: url('tab_hd.png'); +--nav-gradient-active-image: url('tab_ad.png'); +--nav-gradient-active-image-parent: url("../tab_ad.png"); +--nav-separator-image: url('tab_sd.png'); +--nav-breadcrumb-image: url('bc_sd.png'); +--nav-breadcrumb-border-color: #2A3D61; +--nav-splitbar-image: url('splitbard.png'); +--nav-font-size-level1: 13px; +--nav-font-size-level2: 10px; +--nav-font-size-level3: 9px; +--nav-text-normal-color: #B6C4DF; +--nav-text-hover-color: #DCE2EF; +--nav-text-active-color: #DCE2EF; +--nav-text-normal-shadow: 0px 1px 1px black; +--nav-text-hover-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); +--nav-text-active-shadow: 0px 1px 1px rgba(0, 0, 0, 1.0); +--nav-menu-button-color: #B6C4DF; +--nav-menu-background-color: #05070C; +--nav-menu-foreground-color: #BBBBBB; +--nav-menu-toggle-color: rgba(255, 255, 255, 0.2); +--nav-arrow-color: #334975; +--nav-arrow-selected-color: #90A5CE; + +/* table of contents */ +--toc-background-color: #151E30; +--toc-border-color: #202E4A; +--toc-header-color: #A3B4D7; +--toc-down-arrow-image: url("data:image/svg+xml;utf8,&%238595;"); + +/** search field */ +--search-background-color: black; +--search-foreground-color: #C5C5C5; +--search-magnification-image: url('mag_d.svg'); +--search-magnification-select-image: url('mag_seld.svg'); +--search-active-color: #C5C5C5; +--search-filter-background-color: #101826; +--search-filter-foreground-color: #90A5CE; +--search-filter-border-color: #7C95C6; +--search-filter-highlight-text-color: #BCC9E2; +--search-filter-highlight-bg-color: #283A5D; +--search-results-background-color: #101826; +--search-results-foreground-color: #90A5CE; +--search-results-border-color: #7C95C6; +--search-box-shadow: inset 0.5px 0.5px 3px 0px #2F436C; + +/** code fragments */ +--code-keyword-color: #CC99CD; +--code-type-keyword-color: #AB99CD; +--code-flow-keyword-color: #E08000; +--code-comment-color: #717790; +--code-preprocessor-color: #65CABE; +--code-string-literal-color: #7EC699; +--code-char-literal-color: #00E0F0; +--code-xml-cdata-color: #C9D1D9; +--code-vhdl-digit-color: #FF00FF; +--code-vhdl-char-color: #000000; +--code-vhdl-keyword-color: #700070; +--code-vhdl-logic-color: #FF0000; +--code-link-color: #79C0FF; +--code-external-link-color: #79C0FF; +--fragment-foreground-color: #C9D1D9; +--fragment-background-color: black; +--fragment-border-color: #30363D; +--fragment-lineno-border-color: #30363D; +--fragment-lineno-background-color: black; +--fragment-lineno-foreground-color: #6E7681; +--fragment-lineno-link-fg-color: #6E7681; +--fragment-lineno-link-bg-color: #303030; +--fragment-lineno-link-hover-fg-color: #8E96A1; +--fragment-lineno-link-hover-bg-color: #505050; +--tooltip-foreground-color: #C9D1D9; +--tooltip-background-color: #202020; +--tooltip-border-color: #C9D1D9; +--tooltip-doc-color: #D9E1E9; +--tooltip-declaration-color: #20C348; +--tooltip-link-color: #79C0FF; +--tooltip-shadow: none; + +/** font-family */ +--font-family-normal: Roboto,sans-serif; +--font-family-monospace: 'JetBrains Mono',Consolas,Monaco,'Andale Mono','Ubuntu Mono',monospace,fixed; +--font-family-nav: 'Lucida Grande',Geneva,Helvetica,Arial,sans-serif; +--font-family-title: Tahoma,Arial,sans-serif; +--font-family-toc: Verdana,'DejaVu Sans',Geneva,sans-serif; +--font-family-search: Arial,Verdana,sans-serif; +--font-family-icon: Arial,Helvetica; +--font-family-tooltip: Roboto,sans-serif; + +}} +body { + background-color: var(--page-background-color); + color: var(--page-foreground-color); +} + +body, table, div, p, dl { + font-weight: 400; + font-size: 14px; + font-family: var(--font-family-normal); + line-height: 22px; +} + +/* @group Heading Levels */ + +.title { + font-weight: 400; + font-size: 14px; + font-family: var(--font-family-normal); + line-height: 28px; + font-size: 150%; + font-weight: bold; + margin: 10px 2px; +} + +h1.groupheader { + font-size: 150%; +} + +h2.groupheader { + border-bottom: 1px solid var(--group-header-separator-color); + color: var(--group-header-color); + font-size: 150%; + font-weight: normal; + margin-top: 1.75em; + padding-top: 8px; + padding-bottom: 4px; + width: 100%; +} + +h3.groupheader { + font-size: 100%; +} + +h1, h2, h3, h4, h5, h6 { + -webkit-transition: text-shadow 0.5s linear; + -moz-transition: text-shadow 0.5s linear; + -ms-transition: text-shadow 0.5s linear; + -o-transition: text-shadow 0.5s linear; + transition: text-shadow 0.5s linear; + margin-right: 15px; +} + +h1.glow, h2.glow, h3.glow, h4.glow, h5.glow, h6.glow { + text-shadow: 0 0 15px var(--glow-color); +} + +dt { + font-weight: bold; +} + +p.startli, p.startdd { + margin-top: 2px; +} + +th p.starttd, th p.intertd, th p.endtd { + font-size: 100%; + font-weight: 700; +} + +p.starttd { + margin-top: 0px; +} + +p.endli { + margin-bottom: 0px; +} + +p.enddd { + margin-bottom: 4px; +} + +p.endtd { + margin-bottom: 2px; +} + +p.interli { +} + +p.interdd { +} + +p.intertd { +} + +/* @end */ + +caption { + font-weight: bold; +} + +span.legend { + font-size: 70%; + text-align: center; +} + +h3.version { + font-size: 90%; + text-align: center; +} + +div.navtab { + padding-right: 15px; + text-align: right; + line-height: 110%; +} + +div.navtab table { + border-spacing: 0; +} + +td.navtab { + padding-right: 6px; + padding-left: 6px; +} + +td.navtabHL { + background-image: var(--nav-gradient-active-image); + background-repeat:repeat-x; + padding-right: 6px; + padding-left: 6px; +} + +td.navtabHL a, td.navtabHL a:visited { + color: var(--nav-text-hover-color); + text-shadow: var(--nav-text-hover-shadow); +} + +a.navtab { + font-weight: bold; +} + +div.qindex{ + text-align: center; + width: 100%; + line-height: 140%; + font-size: 130%; + color: var(--index-separator-color); +} + +dt.alphachar{ + font-size: 180%; + font-weight: bold; +} + +.alphachar a{ + color: var(--index-header-color); +} + +.alphachar a:hover, .alphachar a:visited{ + text-decoration: none; +} + +.classindex dl { + padding: 25px; + column-count:1 +} + +.classindex dd { + display:inline-block; + margin-left: 50px; + width: 90%; + line-height: 1.15em; +} + +.classindex dl.even { + background-color: var(--index-even-item-bg-color); +} + +.classindex dl.odd { + background-color: var(--index-odd-item-bg-color); +} + +@media(min-width: 1120px) { + .classindex dl { + column-count:2 + } +} + +@media(min-width: 1320px) { + .classindex dl { + column-count:3 + } +} + + +/* @group Link Styling */ + +a { + color: var(--page-link-color); + font-weight: normal; + text-decoration: none; +} + +.contents a:visited { + color: var(--page-visited-link-color); +} + +a:hover { + text-decoration: underline; +} + +a.el { + font-weight: bold; +} + +a.elRef { +} + +a.code, a.code:visited, a.line, a.line:visited { + color: var(--code-link-color); +} + +a.codeRef, a.codeRef:visited, a.lineRef, a.lineRef:visited { + color: var(--code-external-link-color); +} + +a.code.hl_class { /* style for links to class names in code snippets */ } +a.code.hl_struct { /* style for links to struct names in code snippets */ } +a.code.hl_union { /* style for links to union names in code snippets */ } +a.code.hl_interface { /* style for links to interface names in code snippets */ } +a.code.hl_protocol { /* style for links to protocol names in code snippets */ } +a.code.hl_category { /* style for links to category names in code snippets */ } +a.code.hl_exception { /* style for links to exception names in code snippets */ } +a.code.hl_service { /* style for links to service names in code snippets */ } +a.code.hl_singleton { /* style for links to singleton names in code snippets */ } +a.code.hl_concept { /* style for links to concept names in code snippets */ } +a.code.hl_namespace { /* style for links to namespace names in code snippets */ } +a.code.hl_package { /* style for links to package names in code snippets */ } +a.code.hl_define { /* style for links to macro names in code snippets */ } +a.code.hl_function { /* style for links to function names in code snippets */ } +a.code.hl_variable { /* style for links to variable names in code snippets */ } +a.code.hl_typedef { /* style for links to typedef names in code snippets */ } +a.code.hl_enumvalue { /* style for links to enum value names in code snippets */ } +a.code.hl_enumeration { /* style for links to enumeration names in code snippets */ } +a.code.hl_signal { /* style for links to Qt signal names in code snippets */ } +a.code.hl_slot { /* style for links to Qt slot names in code snippets */ } +a.code.hl_friend { /* style for links to friend names in code snippets */ } +a.code.hl_dcop { /* style for links to KDE3 DCOP names in code snippets */ } +a.code.hl_property { /* style for links to property names in code snippets */ } +a.code.hl_event { /* style for links to event names in code snippets */ } +a.code.hl_sequence { /* style for links to sequence names in code snippets */ } +a.code.hl_dictionary { /* style for links to dictionary names in code snippets */ } + +/* @end */ + +dl.el { + margin-left: -1cm; +} + +ul { + overflow: visible; +} + +ul.multicol { + -moz-column-gap: 1em; + -webkit-column-gap: 1em; + column-gap: 1em; + -moz-column-count: 3; + -webkit-column-count: 3; + column-count: 3; + list-style-type: none; +} + +#side-nav ul { + overflow: visible; /* reset ul rule for scroll bar in GENERATE_TREEVIEW window */ +} + +#main-nav ul { + overflow: visible; /* reset ul rule for the navigation bar drop down lists */ +} + +.fragment { + text-align: left; + direction: ltr; + overflow-x: auto; /*Fixed: fragment lines overlap floating elements*/ + overflow-y: hidden; +} + +pre.fragment { + border: 1px solid var(--fragment-border-color); + background-color: var(--fragment-background-color); + color: var(--fragment-foreground-color); + padding: 4px 6px; + margin: 4px 8px 4px 2px; + overflow: auto; + word-wrap: break-word; + font-size: 9pt; + line-height: 125%; + font-family: var(--font-family-monospace); + font-size: 105%; +} + +div.fragment { + padding: 0 0 1px 0; /*Fixed: last line underline overlap border*/ + margin: 4px 8px 4px 2px; + color: var(--fragment-foreground-color); + background-color: var(--fragment-background-color); + border: 1px solid var(--fragment-border-color); +} + +div.line { + font-family: var(--font-family-monospace); + font-size: 13px; + min-height: 13px; + line-height: 1.2; + text-wrap: unrestricted; + white-space: -moz-pre-wrap; /* Moz */ + white-space: -pre-wrap; /* Opera 4-6 */ + white-space: -o-pre-wrap; /* Opera 7 */ + white-space: pre-wrap; /* CSS3 */ + word-wrap: break-word; /* IE 5.5+ */ + text-indent: -53px; + padding-left: 53px; + padding-bottom: 0px; + margin: 0px; + -webkit-transition-property: background-color, box-shadow; + -webkit-transition-duration: 0.5s; + -moz-transition-property: background-color, box-shadow; + -moz-transition-duration: 0.5s; + -ms-transition-property: background-color, box-shadow; + -ms-transition-duration: 0.5s; + -o-transition-property: background-color, box-shadow; + -o-transition-duration: 0.5s; + transition-property: background-color, box-shadow; + transition-duration: 0.5s; +} + +div.line:after { + content:"\000A"; + white-space: pre; +} + +div.line.glow { + background-color: var(--glow-color); + box-shadow: 0 0 10px var(--glow-color); +} + + +span.lineno { + padding-right: 4px; + margin-right: 9px; + text-align: right; + border-right: 2px solid var(--fragment-lineno-border-color); + color: var(--fragment-lineno-foreground-color); + background-color: var(--fragment-lineno-background-color); + white-space: pre; +} +span.lineno a, span.lineno a:visited { + color: var(--fragment-lineno-link-fg-color); + background-color: var(--fragment-lineno-link-bg-color); +} + +span.lineno a:hover { + color: var(--fragment-lineno-link-hover-fg-color); + background-color: var(--fragment-lineno-link-hover-bg-color); +} + +.lineno { + -webkit-touch-callout: none; + -webkit-user-select: none; + -khtml-user-select: none; + -moz-user-select: none; + -ms-user-select: none; + user-select: none; +} + +div.classindex ul { + list-style: none; + padding-left: 0; +} + +div.classindex span.ai { + display: inline-block; +} + +div.groupHeader { + margin-left: 16px; + margin-top: 12px; + font-weight: bold; +} + +div.groupText { + margin-left: 16px; + font-style: italic; +} + +body { + color: var(--page-foreground-color); + margin: 0; +} + +div.contents { + margin-top: 10px; + margin-left: 12px; + margin-right: 8px; +} + +p.formulaDsp { + text-align: center; +} + +img.dark-mode-visible { + display: none; +} +img.light-mode-visible { + display: none; +} + +img.formulaDsp { + +} + +img.formulaInl, img.inline { + vertical-align: middle; +} + +div.center { + text-align: center; + margin-top: 0px; + margin-bottom: 0px; + padding: 0px; +} + +div.center img { + border: 0px; +} + +address.footer { + text-align: right; + padding-right: 12px; +} + +img.footer { + border: 0px; + vertical-align: middle; + width: var(--footer-logo-width); +} + +.compoundTemplParams { + color: var(--memdecl-template-color); + font-size: 80%; + line-height: 120%; +} + +/* @group Code Colorization */ + +span.keyword { + color: var(--code-keyword-color); +} + +span.keywordtype { + color: var(--code-type-keyword-color); +} + +span.keywordflow { + color: var(--code-flow-keyword-color); +} + +span.comment { + color: var(--code-comment-color); +} + +span.preprocessor { + color: var(--code-preprocessor-color); +} + +span.stringliteral { + color: var(--code-string-literal-color); +} + +span.charliteral { + color: var(--code-char-literal-color); +} + +span.xmlcdata { + color: var(--code-xml-cdata-color); +} + +span.vhdldigit { + color: var(--code-vhdl-digit-color); +} + +span.vhdlchar { + color: var(--code-vhdl-char-color); +} + +span.vhdlkeyword { + color: var(--code-vhdl-keyword-color); +} + +span.vhdllogic { + color: var(--code-vhdl-logic-color); +} + +blockquote { + background-color: var(--blockquote-background-color); + border-left: 2px solid var(--blockquote-border-color); + margin: 0 24px 0 4px; + padding: 0 12px 0 16px; +} + +/* @end */ + +td.tiny { + font-size: 75%; +} + +.dirtab { + padding: 4px; + border-collapse: collapse; + border: 1px solid var(--table-cell-border-color); +} + +th.dirtab { + background-color: var(--table-header-background-color); + color: var(--table-header-foreground-color); + font-weight: bold; +} + +hr { + height: 0px; + border: none; + border-top: 1px solid var(--separator-color); +} + +hr.footer { + height: 1px; +} + +/* @group Member Descriptions */ + +table.memberdecls { + border-spacing: 0px; + padding: 0px; +} + +.memberdecls td, .fieldtable tr { + -webkit-transition-property: background-color, box-shadow; + -webkit-transition-duration: 0.5s; + -moz-transition-property: background-color, box-shadow; + -moz-transition-duration: 0.5s; + -ms-transition-property: background-color, box-shadow; + -ms-transition-duration: 0.5s; + -o-transition-property: background-color, box-shadow; + -o-transition-duration: 0.5s; + transition-property: background-color, box-shadow; + transition-duration: 0.5s; +} + +.memberdecls td.glow, .fieldtable tr.glow { + background-color: var(--glow-color); + box-shadow: 0 0 15px var(--glow-color); +} + +.mdescLeft, .mdescRight, +.memItemLeft, .memItemRight, +.memTemplItemLeft, .memTemplItemRight, .memTemplParams { + background-color: var(--memdecl-background-color); + border: none; + margin: 4px; + padding: 1px 0 0 8px; +} + +.mdescLeft, .mdescRight { + padding: 0px 8px 4px 8px; + color: var(--memdecl-foreground-color); +} + +.memSeparator { + border-bottom: 1px solid var(--memdecl-separator-color); + line-height: 1px; + margin: 0px; + padding: 0px; +} + +.memItemLeft, .memTemplItemLeft { + white-space: nowrap; +} + +.memItemRight, .memTemplItemRight { + width: 100%; +} + +.memTemplParams { + color: var(--memdecl-template-color); + white-space: nowrap; + font-size: 80%; +} + +/* @end */ + +/* @group Member Details */ + +/* Styles for detailed member documentation */ + +.memtitle { + padding: 8px; + border-top: 1px solid var(--memdef-border-color); + border-left: 1px solid var(--memdef-border-color); + border-right: 1px solid var(--memdef-border-color); + border-top-right-radius: 4px; + border-top-left-radius: 4px; + margin-bottom: -1px; + background-image: var(--memdef-title-gradient-image); + background-repeat: repeat-x; + background-color: var(--memdef-title-background-color); + line-height: 1.25; + font-weight: 300; + float:left; +} + +.permalink +{ + font-size: 65%; + display: inline-block; + vertical-align: middle; +} + +.memtemplate { + font-size: 80%; + color: var(--memdef-template-color); + font-weight: normal; + margin-left: 9px; +} + +.mempage { + width: 100%; +} + +.memitem { + padding: 0; + margin-bottom: 10px; + margin-right: 5px; + -webkit-transition: box-shadow 0.5s linear; + -moz-transition: box-shadow 0.5s linear; + -ms-transition: box-shadow 0.5s linear; + -o-transition: box-shadow 0.5s linear; + transition: box-shadow 0.5s linear; + display: table !important; + width: 100%; +} + +.memitem.glow { + box-shadow: 0 0 15px var(--glow-color); +} + +.memname { + font-weight: 400; + margin-left: 6px; +} + +.memname td { + vertical-align: bottom; +} + +.memproto, dl.reflist dt { + border-top: 1px solid var(--memdef-border-color); + border-left: 1px solid var(--memdef-border-color); + border-right: 1px solid var(--memdef-border-color); + padding: 6px 0px 6px 0px; + color: var(--memdef-proto-text-color); + font-weight: bold; + text-shadow: var(--memdef-proto-text-shadow); + background-color: var(--memdef-proto-background-color); + box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); + border-top-right-radius: 4px; +} + +.overload { + font-family: var(--font-family-monospace); + font-size: 65%; +} + +.memdoc, dl.reflist dd { + border-bottom: 1px solid var(--memdef-border-color); + border-left: 1px solid var(--memdef-border-color); + border-right: 1px solid var(--memdef-border-color); + padding: 6px 10px 2px 10px; + border-top-width: 0; + background-image:url('nav_g.png'); + background-repeat:repeat-x; + background-color: var(--memdef-doc-background-color); + /* opera specific markup */ + border-bottom-left-radius: 4px; + border-bottom-right-radius: 4px; + box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); + /* firefox specific markup */ + -moz-border-radius-bottomleft: 4px; + -moz-border-radius-bottomright: 4px; + -moz-box-shadow: rgba(0, 0, 0, 0.15) 5px 5px 5px; + /* webkit specific markup */ + -webkit-border-bottom-left-radius: 4px; + -webkit-border-bottom-right-radius: 4px; + -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); +} + +dl.reflist dt { + padding: 5px; +} + +dl.reflist dd { + margin: 0px 0px 10px 0px; + padding: 5px; +} + +.paramkey { + text-align: right; +} + +.paramtype { + white-space: nowrap; +} + +.paramname { + color: var(--memdef-param-name-color); + white-space: nowrap; +} +.paramname em { + font-style: normal; +} +.paramname code { + line-height: 14px; +} + +.params, .retval, .exception, .tparams { + margin-left: 0px; + padding-left: 0px; +} + +.params .paramname, .retval .paramname, .tparams .paramname, .exception .paramname { + font-weight: bold; + vertical-align: top; +} + +.params .paramtype, .tparams .paramtype { + font-style: italic; + vertical-align: top; +} + +.params .paramdir, .tparams .paramdir { + font-family: var(--font-family-monospace); + vertical-align: top; +} + +table.mlabels { + border-spacing: 0px; +} + +td.mlabels-left { + width: 100%; + padding: 0px; +} + +td.mlabels-right { + vertical-align: bottom; + padding: 0px; + white-space: nowrap; +} + +span.mlabels { + margin-left: 8px; +} + +span.mlabel { + background-color: var(--label-background-color); + border-top:1px solid var(--label-left-top-border-color); + border-left:1px solid var(--label-left-top-border-color); + border-right:1px solid var(--label-right-bottom-border-color); + border-bottom:1px solid var(--label-right-bottom-border-color); + text-shadow: none; + color: var(--label-foreground-color); + margin-right: 4px; + padding: 2px 3px; + border-radius: 3px; + font-size: 7pt; + white-space: nowrap; + vertical-align: middle; +} + + + +/* @end */ + +/* these are for tree view inside a (index) page */ + +div.directory { + margin: 10px 0px; + border-top: 1px solid var(--directory-separator-color); + border-bottom: 1px solid var(--directory-separator-color); + width: 100%; +} + +.directory table { + border-collapse:collapse; +} + +.directory td { + margin: 0px; + padding: 0px; + vertical-align: top; +} + +.directory td.entry { + white-space: nowrap; + padding-right: 6px; + padding-top: 3px; +} + +.directory td.entry a { + outline:none; +} + +.directory td.entry a img { + border: none; +} + +.directory td.desc { + width: 100%; + padding-left: 6px; + padding-right: 6px; + padding-top: 3px; + border-left: 1px solid rgba(0,0,0,0.05); +} + +.directory tr.odd { + padding-left: 6px; + background-color: var(--index-odd-item-bg-color); +} + +.directory tr.even { + padding-left: 6px; + background-color: var(--index-even-item-bg-color); +} + +.directory img { + vertical-align: -30%; +} + +.directory .levels { + white-space: nowrap; + width: 100%; + text-align: right; + font-size: 9pt; +} + +.directory .levels span { + cursor: pointer; + padding-left: 2px; + padding-right: 2px; + color: var(--page-link-color); +} + +.arrow { + color: var(--nav-arrow-color); + -webkit-user-select: none; + -khtml-user-select: none; + -moz-user-select: none; + -ms-user-select: none; + user-select: none; + cursor: pointer; + font-size: 80%; + display: inline-block; + width: 16px; + height: 22px; +} + +.icon { + font-family: var(--font-family-icon); + line-height: normal; + font-weight: bold; + font-size: 12px; + height: 14px; + width: 16px; + display: inline-block; + background-color: var(--icon-background-color); + color: var(--icon-foreground-color); + text-align: center; + border-radius: 4px; + margin-left: 2px; + margin-right: 2px; +} + +.icona { + width: 24px; + height: 22px; + display: inline-block; +} + +.iconfopen { + width: 24px; + height: 18px; + margin-bottom: 4px; + background-image:var(--icon-folder-open-image); + background-repeat: repeat-y; + vertical-align:top; + display: inline-block; +} + +.iconfclosed { + width: 24px; + height: 18px; + margin-bottom: 4px; + background-image:var(--icon-folder-closed-image); + background-repeat: repeat-y; + vertical-align:top; + display: inline-block; +} + +.icondoc { + width: 24px; + height: 18px; + margin-bottom: 4px; + background-image:var(--icon-doc-image); + background-position: 0px -4px; + background-repeat: repeat-y; + vertical-align:top; + display: inline-block; +} + +/* @end */ + +div.dynheader { + margin-top: 8px; + -webkit-touch-callout: none; + -webkit-user-select: none; + -khtml-user-select: none; + -moz-user-select: none; + -ms-user-select: none; + user-select: none; +} + +address { + font-style: normal; + color: var(--footer-foreground-color); +} + +table.doxtable caption { + caption-side: top; +} + +table.doxtable { + border-collapse:collapse; + margin-top: 4px; + margin-bottom: 4px; +} + +table.doxtable td, table.doxtable th { + border: 1px solid var(--table-cell-border-color); + padding: 3px 7px 2px; +} + +table.doxtable th { + background-color: var(--table-header-background-color); + color: var(--table-header-foreground-color); + font-size: 110%; + padding-bottom: 4px; + padding-top: 5px; +} + +table.fieldtable { + margin-bottom: 10px; + border: 1px solid var(--memdef-border-color); + border-spacing: 0px; + border-radius: 4px; + box-shadow: 2px 2px 2px rgba(0, 0, 0, 0.15); +} + +.fieldtable td, .fieldtable th { + padding: 3px 7px 2px; +} + +.fieldtable td.fieldtype, .fieldtable td.fieldname { + white-space: nowrap; + border-right: 1px solid var(--memdef-border-color); + border-bottom: 1px solid var(--memdef-border-color); + vertical-align: top; +} + +.fieldtable td.fieldname { + padding-top: 3px; +} + +.fieldtable td.fielddoc { + border-bottom: 1px solid var(--memdef-border-color); +} + +.fieldtable td.fielddoc p:first-child { + margin-top: 0px; +} + +.fieldtable td.fielddoc p:last-child { + margin-bottom: 2px; +} + +.fieldtable tr:last-child td { + border-bottom: none; +} + +.fieldtable th { + background-image: var(--memdef-title-gradient-image); + background-repeat:repeat-x; + background-color: var(--memdef-title-background-color); + font-size: 90%; + color: var(--memdef-proto-text-color); + padding-bottom: 4px; + padding-top: 5px; + text-align:left; + font-weight: 400; + border-top-left-radius: 4px; + border-top-right-radius: 4px; + border-bottom: 1px solid var(--memdef-border-color); +} + + +.tabsearch { + top: 0px; + left: 10px; + height: 36px; + background-image: var(--nav-gradient-image); + z-index: 101; + overflow: hidden; + font-size: 13px; +} + +.navpath ul +{ + font-size: 11px; + background-image: var(--nav-gradient-image); + background-repeat:repeat-x; + background-position: 0 -5px; + height:30px; + line-height:30px; + color:var(--nav-text-normal-color); + border:solid 1px var(--nav-breadcrumb-border-color); + overflow:hidden; + margin:0px; + padding:0px; +} + +.navpath li +{ + list-style-type:none; + float:left; + padding-left:10px; + padding-right:15px; + background-image:var(--nav-breadcrumb-image); + background-repeat:no-repeat; + background-position:right; + color: var(--nav-foreground-color); +} + +.navpath li.navelem a +{ + height:32px; + display:block; + text-decoration: none; + outline: none; + color: var(--nav-text-normal-color); + font-family: var(--font-family-nav); + text-shadow: var(--nav-text-normal-shadow); + text-decoration: none; +} + +.navpath li.navelem a:hover +{ + color: var(--nav-text-hover-color); + text-shadow: var(--nav-text-hover-shadow); +} + +.navpath li.footer +{ + list-style-type:none; + float:right; + padding-left:10px; + padding-right:15px; + background-image:none; + background-repeat:no-repeat; + background-position:right; + color: var(--footer-foreground-color); + font-size: 8pt; +} + + +div.summary +{ + float: right; + font-size: 8pt; + padding-right: 5px; + width: 50%; + text-align: right; +} + +div.summary a +{ + white-space: nowrap; +} + +table.classindex +{ + margin: 10px; + white-space: nowrap; + margin-left: 3%; + margin-right: 3%; + width: 94%; + border: 0; + border-spacing: 0; + padding: 0; +} + +div.ingroups +{ + font-size: 8pt; + width: 50%; + text-align: left; +} + +div.ingroups a +{ + white-space: nowrap; +} + +div.header +{ + background-image: var(--header-gradient-image); + background-repeat:repeat-x; + background-color: var(--header-background-color); + margin: 0px; + border-bottom: 1px solid var(--header-separator-color); +} + +div.headertitle +{ + padding: 5px 5px 5px 10px; +} + +.PageDocRTL-title div.headertitle { + text-align: right; + direction: rtl; +} + +dl { + padding: 0 0 0 0; +} + +/* dl.note, dl.warning, dl.attention, dl.pre, dl.post, dl.invariant, dl.deprecated, dl.todo, dl.test, dl.bug, dl.examples */ +dl.section { + margin-left: 0px; + padding-left: 0px; +} + +dl.note { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #D0C000; +} + +dl.warning, dl.attention { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #FF0000; +} + +dl.pre, dl.post, dl.invariant { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #00D000; +} + +dl.deprecated { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #505050; +} + +dl.todo { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #00C0E0; +} + +dl.test { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #3030E0; +} + +dl.bug { + margin-left: -7px; + padding-left: 3px; + border-left: 4px solid; + border-color: #C08050; +} + +dl.section dd { + margin-bottom: 6px; +} + + +#projectrow +{ + height: 56px; +} + +#projectlogo +{ + text-align: center; + vertical-align: bottom; + border-collapse: separate; +} + +#projectlogo img +{ + border: 0px none; +} + +#projectalign +{ + vertical-align: middle; + padding-left: 0.5em; +} + +#projectname +{ + font-size: 200%; + font-family: var(--font-family-title); + margin: 0px; + padding: 2px 0px; +} + +#projectbrief +{ + font-size: 90%; + font-family: var(--font-family-title); + margin: 0px; + padding: 0px; +} + +#projectnumber +{ + font-size: 50%; + font-family: 50% var(--font-family-title); + margin: 0px; + padding: 0px; +} + +#titlearea +{ + padding: 0px; + margin: 0px; + width: 100%; + border-bottom: 1px solid var(--title-separator-color); + background-color: var(--title-background-color); +} + +.image +{ + text-align: center; +} + +.dotgraph +{ + text-align: center; +} + +.mscgraph +{ + text-align: center; +} + +.plantumlgraph +{ + text-align: center; +} + +.diagraph +{ + text-align: center; +} + +.caption +{ + font-weight: bold; +} + +dl.citelist { + margin-bottom:50px; +} + +dl.citelist dt { + color:var(--citation-label-color); + float:left; + font-weight:bold; + margin-right:10px; + padding:5px; + text-align:right; + width:52px; +} + +dl.citelist dd { + margin:2px 0 2px 72px; + padding:5px 0; +} + +div.toc { + padding: 14px 25px; + background-color: var(--toc-background-color); + border: 1px solid var(--toc-border-color); + border-radius: 7px 7px 7px 7px; + float: right; + height: auto; + margin: 0 8px 10px 10px; + width: 200px; +} + +div.toc li { + background: var(--toc-down-arrow-image) no-repeat scroll 0 5px transparent; + font: 10px/1.2 var(--font-family-toc); + margin-top: 5px; + padding-left: 10px; + padding-top: 2px; +} + +div.toc h3 { + font: bold 12px/1.2 var(--font-family-toc); + color: var(--toc-header-color); + border-bottom: 0 none; + margin: 0; +} + +div.toc ul { + list-style: none outside none; + border: medium none; + padding: 0px; +} + +div.toc li.level1 { + margin-left: 0px; +} + +div.toc li.level2 { + margin-left: 15px; +} + +div.toc li.level3 { + margin-left: 15px; +} + +div.toc li.level4 { + margin-left: 15px; +} + +span.emoji { + /* font family used at the site: https://unicode.org/emoji/charts/full-emoji-list.html + * font-family: "Noto Color Emoji", "Apple Color Emoji", "Segoe UI Emoji", Times, Symbola, Aegyptus, Code2000, Code2001, Code2002, Musica, serif, LastResort; + */ +} + +span.obfuscator { + display: none; +} + +.inherit_header { + font-weight: bold; + color: var(--inherit-header-color); + cursor: pointer; + -webkit-touch-callout: none; + -webkit-user-select: none; + -khtml-user-select: none; + -moz-user-select: none; + -ms-user-select: none; + user-select: none; +} + +.inherit_header td { + padding: 6px 0px 2px 5px; +} + +.inherit { + display: none; +} + +tr.heading h2 { + margin-top: 12px; + margin-bottom: 4px; +} + +/* tooltip related style info */ + +.ttc { + position: absolute; + display: none; +} + +#powerTip { + cursor: default; + /*white-space: nowrap;*/ + color: var(--tooltip-foreground-color); + background-color: var(--tooltip-background-color); + border: 1px solid var(--tooltip-border-color); + border-radius: 4px 4px 4px 4px; + box-shadow: var(--tooltip-shadow); + display: none; + font-size: smaller; + max-width: 80%; + opacity: 0.9; + padding: 1ex 1em 1em; + position: absolute; + z-index: 2147483647; +} + +#powerTip div.ttdoc { + color: var(--tooltip-doc-color); + font-style: italic; +} + +#powerTip div.ttname a { + font-weight: bold; +} + +#powerTip a { + color: var(--tooltip-link-color); +} + +#powerTip div.ttname { + font-weight: bold; +} + +#powerTip div.ttdeci { + color: var(--tooltip-declaration-color); +} + +#powerTip div { + margin: 0px; + padding: 0px; + font-size: 12px; + font-family: var(--font-family-tooltip); + line-height: 16px; +} + +#powerTip:before, #powerTip:after { + content: ""; + position: absolute; + margin: 0px; +} + +#powerTip.n:after, #powerTip.n:before, +#powerTip.s:after, #powerTip.s:before, +#powerTip.w:after, #powerTip.w:before, +#powerTip.e:after, #powerTip.e:before, +#powerTip.ne:after, #powerTip.ne:before, +#powerTip.se:after, #powerTip.se:before, +#powerTip.nw:after, #powerTip.nw:before, +#powerTip.sw:after, #powerTip.sw:before { + border: solid transparent; + content: " "; + height: 0; + width: 0; + position: absolute; +} + +#powerTip.n:after, #powerTip.s:after, +#powerTip.w:after, #powerTip.e:after, +#powerTip.nw:after, #powerTip.ne:after, +#powerTip.sw:after, #powerTip.se:after { + border-color: rgba(255, 255, 255, 0); +} + +#powerTip.n:before, #powerTip.s:before, +#powerTip.w:before, #powerTip.e:before, +#powerTip.nw:before, #powerTip.ne:before, +#powerTip.sw:before, #powerTip.se:before { + border-color: rgba(128, 128, 128, 0); +} + +#powerTip.n:after, #powerTip.n:before, +#powerTip.ne:after, #powerTip.ne:before, +#powerTip.nw:after, #powerTip.nw:before { + top: 100%; +} + +#powerTip.n:after, #powerTip.ne:after, #powerTip.nw:after { + border-top-color: var(--tooltip-background-color); + border-width: 10px; + margin: 0px -10px; +} +#powerTip.n:before, #powerTip.ne:before, #powerTip.nw:before { + border-top-color: var(--tooltip-border-color); + border-width: 11px; + margin: 0px -11px; +} +#powerTip.n:after, #powerTip.n:before { + left: 50%; +} + +#powerTip.nw:after, #powerTip.nw:before { + right: 14px; +} + +#powerTip.ne:after, #powerTip.ne:before { + left: 14px; +} + +#powerTip.s:after, #powerTip.s:before, +#powerTip.se:after, #powerTip.se:before, +#powerTip.sw:after, #powerTip.sw:before { + bottom: 100%; +} + +#powerTip.s:after, #powerTip.se:after, #powerTip.sw:after { + border-bottom-color: var(--tooltip-background-color); + border-width: 10px; + margin: 0px -10px; +} + +#powerTip.s:before, #powerTip.se:before, #powerTip.sw:before { + border-bottom-color: var(--tooltip-border-color); + border-width: 11px; + margin: 0px -11px; +} + +#powerTip.s:after, #powerTip.s:before { + left: 50%; +} + +#powerTip.sw:after, #powerTip.sw:before { + right: 14px; +} + +#powerTip.se:after, #powerTip.se:before { + left: 14px; +} + +#powerTip.e:after, #powerTip.e:before { + left: 100%; +} +#powerTip.e:after { + border-left-color: var(--tooltip-border-color); + border-width: 10px; + top: 50%; + margin-top: -10px; +} +#powerTip.e:before { + border-left-color: var(--tooltip-border-color); + border-width: 11px; + top: 50%; + margin-top: -11px; +} + +#powerTip.w:after, #powerTip.w:before { + right: 100%; +} +#powerTip.w:after { + border-right-color: var(--tooltip-border-color); + border-width: 10px; + top: 50%; + margin-top: -10px; +} +#powerTip.w:before { + border-right-color: var(--tooltip-border-color); + border-width: 11px; + top: 50%; + margin-top: -11px; +} + +@media print +{ + #top { display: none; } + #side-nav { display: none; } + #nav-path { display: none; } + body { overflow:visible; } + h1, h2, h3, h4, h5, h6 { page-break-after: avoid; } + .summary { display: none; } + .memitem { page-break-inside: avoid; } + #doc-content + { + margin-left:0 !important; + height:auto !important; + width:auto !important; + overflow:inherit; + display:inline; + } +} + +/* @group Markdown */ + +table.markdownTable { + border-collapse:collapse; + margin-top: 4px; + margin-bottom: 4px; +} + +table.markdownTable td, table.markdownTable th { + border: 1px solid var(--table-cell-border-color); + padding: 3px 7px 2px; +} + +table.markdownTable tr { +} + +th.markdownTableHeadLeft, th.markdownTableHeadRight, th.markdownTableHeadCenter, th.markdownTableHeadNone { + background-color: var(--table-header-background-color); + color: var(--table-header-foreground-color); + font-size: 110%; + padding-bottom: 4px; + padding-top: 5px; +} + +th.markdownTableHeadLeft, td.markdownTableBodyLeft { + text-align: left +} + +th.markdownTableHeadRight, td.markdownTableBodyRight { + text-align: right +} + +th.markdownTableHeadCenter, td.markdownTableBodyCenter { + text-align: center +} + +tt, code, kbd, samp +{ + display: inline-block; +} +/* @end */ + +u { + text-decoration: underline; +} + +details>summary { + list-style-type: none; +} + +details > summary::-webkit-details-marker { + display: none; +} + +details>summary::before { + content: "\25ba"; + padding-right:4px; + font-size: 80%; +} + +details[open]>summary::before { + content: "\25bc"; + padding-right:4px; + font-size: 80%; +} + +body { + scrollbar-color: var(--scrollbar-thumb-color) var(--scrollbar-background-color); +} + +::-webkit-scrollbar { + background-color: var(--scrollbar-background-color); + height: 12px; + width: 12px; +} +::-webkit-scrollbar-thumb { + border-radius: 6px; + box-shadow: inset 0 0 12px 12px var(--scrollbar-thumb-color); + border: solid 2px transparent; +} +::-webkit-scrollbar-corner { + background-color: var(--scrollbar-background-color); +} + diff --git a/documentation/html/doxygen.svg b/documentation/html/doxygen.svg new file mode 100644 index 0000000..79a7635 --- /dev/null +++ b/documentation/html/doxygen.svg @@ -0,0 +1,28 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + diff --git a/documentation/html/dynsections.js b/documentation/html/dynsections.js new file mode 100644 index 0000000..f579fbf --- /dev/null +++ b/documentation/html/dynsections.js @@ -0,0 +1,123 @@ +/* + @licstart The following is the entire license notice for the JavaScript code in this file. + + The MIT License (MIT) + + Copyright (C) 1997-2020 by Dimitri van Heesch + + Permission is hereby granted, free of charge, to any person obtaining a copy of this software + and associated documentation files (the "Software"), to deal in the Software without restriction, + including without limitation the rights to use, copy, modify, merge, publish, distribute, + sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all copies or + substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING + BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, + DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + @licend The above is the entire license notice for the JavaScript code in this file + */ +function toggleVisibility(linkObj) +{ + var base = $(linkObj).attr('id'); + var summary = $('#'+base+'-summary'); + var content = $('#'+base+'-content'); + var trigger = $('#'+base+'-trigger'); + var src=$(trigger).attr('src'); + if (content.is(':visible')===true) { + content.hide(); + summary.show(); + $(linkObj).addClass('closed').removeClass('opened'); + $(trigger).attr('src',src.substring(0,src.length-8)+'closed.png'); + } else { + content.show(); + summary.hide(); + $(linkObj).removeClass('closed').addClass('opened'); + $(trigger).attr('src',src.substring(0,src.length-10)+'open.png'); + } + return false; +} + +function updateStripes() +{ + $('table.directory tr'). + removeClass('even').filter(':visible:even').addClass('even'); + $('table.directory tr'). + removeClass('odd').filter(':visible:odd').addClass('odd'); +} + +function toggleLevel(level) +{ + $('table.directory tr').each(function() { + var l = this.id.split('_').length-1; + var i = $('#img'+this.id.substring(3)); + var a = $('#arr'+this.id.substring(3)); + if (l + + + + + + +esp32_BNO08x: File List + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
File List
+
+
+
Here is a list of all documented files with brief descriptions:
+
[detail level 12345]
+ + + + + +
  D:
  development
  git
  esp32_BNO08x
 BNO08x.hpp
+
+
+ + + + diff --git a/documentation/html/folderclosed.svg b/documentation/html/folderclosed.svg new file mode 100644 index 0000000..b04bed2 --- /dev/null +++ b/documentation/html/folderclosed.svg @@ -0,0 +1,11 @@ + + + + + + + + + + diff --git a/documentation/html/folderclosedd.svg b/documentation/html/folderclosedd.svg new file mode 100644 index 0000000..52f0166 --- /dev/null +++ b/documentation/html/folderclosedd.svg @@ -0,0 +1,11 @@ + + + + + + + + + + diff --git a/documentation/html/folderopen.svg b/documentation/html/folderopen.svg new file mode 100644 index 0000000..f6896dd --- /dev/null +++ b/documentation/html/folderopen.svg @@ -0,0 +1,17 @@ + + + + + + + + + + diff --git a/documentation/html/folderopend.svg b/documentation/html/folderopend.svg new file mode 100644 index 0000000..2d1f06e --- /dev/null +++ b/documentation/html/folderopend.svg @@ -0,0 +1,12 @@ + + + + + + + + + + + diff --git a/documentation/html/functions.html b/documentation/html/functions.html new file mode 100644 index 0000000..6bd5221 --- /dev/null +++ b/documentation/html/functions.html @@ -0,0 +1,89 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- a -

    +
  • accel_accuracy : BNO08x
  • +
  • accel_lin_accuracy : BNO08x
  • +
  • ACCELEROMETER_Q1 : BNO08x
  • +
  • activity_classifier : BNO08x
  • +
  • activity_confidences : BNO08x
  • +
  • ANGULAR_VELOCITY_Q1 : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_b.html b/documentation/html/functions_b.html new file mode 100644 index 0000000..5471984 --- /dev/null +++ b/documentation/html/functions_b.html @@ -0,0 +1,86 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- b -

+
+ + + + diff --git a/documentation/html/functions_c.html b/documentation/html/functions_c.html new file mode 100644 index 0000000..de7b91c --- /dev/null +++ b/documentation/html/functions_c.html @@ -0,0 +1,106 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- c -

    +
  • CALIBRATE_ACCEL : BNO08x
  • +
  • CALIBRATE_ACCEL_GYRO_MAG : BNO08x
  • +
  • calibrate_accelerometer() : BNO08x
  • +
  • calibrate_all() : BNO08x
  • +
  • calibrate_gyro() : BNO08x
  • +
  • CALIBRATE_GYRO : BNO08x
  • +
  • CALIBRATE_MAG : BNO08x
  • +
  • calibrate_magnetometer() : BNO08x
  • +
  • CALIBRATE_PLANAR_ACCEL : BNO08x
  • +
  • calibrate_planar_accelerometer() : BNO08x
  • +
  • CALIBRATE_STOP : BNO08x
  • +
  • calibration_complete() : BNO08x
  • +
  • calibration_status : BNO08x
  • +
  • clear_tare() : BNO08x
  • +
  • COMMAND_CLEAR_DCD : BNO08x
  • +
  • COMMAND_DCD : BNO08x
  • +
  • COMMAND_DCD_PERIOD_SAVE : BNO08x
  • +
  • COMMAND_INITIALIZE : BNO08x
  • +
  • COMMAND_ME_CALIBRATE : BNO08x
  • +
  • COMMAND_OSCILLATOR : BNO08x
  • +
  • command_sequence_number : BNO08x
  • +
  • COMMAND_TARE : BNO08x
  • +
  • commands : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_d.html b/documentation/html/functions_d.html new file mode 100644 index 0000000..cd75416 --- /dev/null +++ b/documentation/html/functions_d.html @@ -0,0 +1,86 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- d -

+
+ + + + diff --git a/documentation/html/functions_e.html b/documentation/html/functions_e.html new file mode 100644 index 0000000..c01b98b --- /dev/null +++ b/documentation/html/functions_e.html @@ -0,0 +1,102 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- e -

    +
  • enable_accelerometer() : BNO08x
  • +
  • enable_activity_classifier() : BNO08x
  • +
  • enable_ARVR_stabilized_game_rotation_vector() : BNO08x
  • +
  • enable_ARVR_stabilized_rotation_vector() : BNO08x
  • +
  • enable_game_rotation_vector() : BNO08x
  • +
  • enable_gravity() : BNO08x
  • +
  • enable_gyro() : BNO08x
  • +
  • enable_gyro_integrated_rotation_vector() : BNO08x
  • +
  • enable_linear_accelerometer() : BNO08x
  • +
  • enable_magnetometer() : BNO08x
  • +
  • enable_raw_accelerometer() : BNO08x
  • +
  • enable_raw_gyro() : BNO08x
  • +
  • enable_raw_magnetometer() : BNO08x
  • +
  • enable_rotation_vector() : BNO08x
  • +
  • enable_stability_classifier() : BNO08x
  • +
  • enable_step_counter() : BNO08x
  • +
  • enable_tap_detector() : BNO08x
  • +
  • enable_uncalibrated_gyro() : BNO08x
  • +
  • end_calibration() : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_f.html b/documentation/html/functions_f.html new file mode 100644 index 0000000..d713d2a --- /dev/null +++ b/documentation/html/functions_f.html @@ -0,0 +1,86 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- f -

+
+ + + + diff --git a/documentation/html/functions_func.html b/documentation/html/functions_func.html new file mode 100644 index 0000000..b3541fa --- /dev/null +++ b/documentation/html/functions_func.html @@ -0,0 +1,268 @@ + + + + + + + +esp32_BNO08x: Class Members - Functions + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented functions with links to the class documentation for each member:
+ +

- b -

+ + +

- c -

    +
  • calibrate_accelerometer() : BNO08x
  • +
  • calibrate_all() : BNO08x
  • +
  • calibrate_gyro() : BNO08x
  • +
  • calibrate_magnetometer() : BNO08x
  • +
  • calibrate_planar_accelerometer() : BNO08x
  • +
  • calibration_complete() : BNO08x
  • +
  • clear_tare() : BNO08x
  • +
+ + +

- d -

    +
  • data_available() : BNO08x
  • +
+ + +

- e -

    +
  • enable_accelerometer() : BNO08x
  • +
  • enable_activity_classifier() : BNO08x
  • +
  • enable_ARVR_stabilized_game_rotation_vector() : BNO08x
  • +
  • enable_ARVR_stabilized_rotation_vector() : BNO08x
  • +
  • enable_game_rotation_vector() : BNO08x
  • +
  • enable_gravity() : BNO08x
  • +
  • enable_gyro() : BNO08x
  • +
  • enable_gyro_integrated_rotation_vector() : BNO08x
  • +
  • enable_linear_accelerometer() : BNO08x
  • +
  • enable_magnetometer() : BNO08x
  • +
  • enable_raw_accelerometer() : BNO08x
  • +
  • enable_raw_gyro() : BNO08x
  • +
  • enable_raw_magnetometer() : BNO08x
  • +
  • enable_rotation_vector() : BNO08x
  • +
  • enable_stability_classifier() : BNO08x
  • +
  • enable_step_counter() : BNO08x
  • +
  • enable_tap_detector() : BNO08x
  • +
  • enable_uncalibrated_gyro() : BNO08x
  • +
  • end_calibration() : BNO08x
  • +
+ + +

- f -

+ + +

- g -

    +
  • get_accel() : BNO08x
  • +
  • get_accel_accuracy() : BNO08x
  • +
  • get_accel_X() : BNO08x
  • +
  • get_accel_Y() : BNO08x
  • +
  • get_accel_Z() : BNO08x
  • +
  • get_activity_classifier() : BNO08x
  • +
  • get_gravity() : BNO08x
  • +
  • get_gravity_accuracy() : BNO08x
  • +
  • get_gravity_X() : BNO08x
  • +
  • get_gravity_Y() : BNO08x
  • +
  • get_gravity_Z() : BNO08x
  • +
  • get_gyro_accuracy() : BNO08x
  • +
  • get_gyro_calibrated_velocity() : BNO08x
  • +
  • get_gyro_calibrated_velocity_X() : BNO08x
  • +
  • get_gyro_calibrated_velocity_Y() : BNO08x
  • +
  • get_gyro_calibrated_velocity_Z() : BNO08x
  • +
  • get_gyro_velocity() : BNO08x
  • +
  • get_gyro_velocity_X() : BNO08x
  • +
  • get_gyro_velocity_Y() : BNO08x
  • +
  • get_gyro_velocity_Z() : BNO08x
  • +
  • get_linear_accel() : BNO08x
  • +
  • get_linear_accel_accuracy() : BNO08x
  • +
  • get_linear_accel_X() : BNO08x
  • +
  • get_linear_accel_Y() : BNO08x
  • +
  • get_linear_accel_Z() : BNO08x
  • +
  • get_magf() : BNO08x
  • +
  • get_magf_accuracy() : BNO08x
  • +
  • get_magf_X() : BNO08x
  • +
  • get_magf_Y() : BNO08x
  • +
  • get_magf_Z() : BNO08x
  • +
  • get_pitch() : BNO08x
  • +
  • get_pitch_deg() : BNO08x
  • +
  • get_Q1() : BNO08x
  • +
  • get_Q2() : BNO08x
  • +
  • get_Q3() : BNO08x
  • +
  • get_quat() : BNO08x
  • +
  • get_quat_accuracy() : BNO08x
  • +
  • get_quat_I() : BNO08x
  • +
  • get_quat_J() : BNO08x
  • +
  • get_quat_K() : BNO08x
  • +
  • get_quat_radian_accuracy() : BNO08x
  • +
  • get_quat_real() : BNO08x
  • +
  • get_range() : BNO08x
  • +
  • get_raw_accel_X() : BNO08x
  • +
  • get_raw_accel_Y() : BNO08x
  • +
  • get_raw_accel_Z() : BNO08x
  • +
  • get_raw_gyro_X() : BNO08x
  • +
  • get_raw_gyro_Y() : BNO08x
  • +
  • get_raw_gyro_Z() : BNO08x
  • +
  • get_raw_magf_X() : BNO08x
  • +
  • get_raw_magf_Y() : BNO08x
  • +
  • get_raw_magf_Z() : BNO08x
  • +
  • get_readings() : BNO08x
  • +
  • get_reset_reason() : BNO08x
  • +
  • get_resolution() : BNO08x
  • +
  • get_roll() : BNO08x
  • +
  • get_roll_deg() : BNO08x
  • +
  • get_stability_classifier() : BNO08x
  • +
  • get_step_count() : BNO08x
  • +
  • get_tap_detector() : BNO08x
  • +
  • get_time_stamp() : BNO08x
  • +
  • get_uncalibrated_gyro() : BNO08x
  • +
  • get_uncalibrated_gyro_accuracy() : BNO08x
  • +
  • get_uncalibrated_gyro_bias_X() : BNO08x
  • +
  • get_uncalibrated_gyro_bias_Y() : BNO08x
  • +
  • get_uncalibrated_gyro_bias_Z() : BNO08x
  • +
  • get_uncalibrated_gyro_X() : BNO08x
  • +
  • get_uncalibrated_gyro_Y() : BNO08x
  • +
  • get_uncalibrated_gyro_Z() : BNO08x
  • +
  • get_yaw() : BNO08x
  • +
  • get_yaw_deg() : BNO08x
  • +
+ + +

- h -

+ + +

- i -

+ + +

- m -

+ + +

- p -

    +
  • parse_command_report() : BNO08x
  • +
  • parse_input_report() : BNO08x
  • +
  • print_header() : BNO08x
  • +
+ + +

- q -

    +
  • q_to_float() : BNO08x
  • +
  • queue_calibrate_command() : BNO08x
  • +
  • queue_command() : BNO08x
  • +
  • queue_feature_command() : BNO08x
  • +
  • queue_packet() : BNO08x
  • +
  • queue_request_product_id_command() : BNO08x
  • +
  • queue_tare_command() : BNO08x
  • +
+ + +

- r -

    +
  • receive_packet() : BNO08x
  • +
  • request_calibration_status() : BNO08x
  • +
  • run_full_calibration_routine() : BNO08x
  • +
+ + +

- s -

+ + +

- t -

+ + +

- w -

    +
  • wait_for_device_int() : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_g.html b/documentation/html/functions_g.html new file mode 100644 index 0000000..4489658 --- /dev/null +++ b/documentation/html/functions_g.html @@ -0,0 +1,158 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- g -

    +
  • get_accel() : BNO08x
  • +
  • get_accel_accuracy() : BNO08x
  • +
  • get_accel_X() : BNO08x
  • +
  • get_accel_Y() : BNO08x
  • +
  • get_accel_Z() : BNO08x
  • +
  • get_activity_classifier() : BNO08x
  • +
  • get_gravity() : BNO08x
  • +
  • get_gravity_accuracy() : BNO08x
  • +
  • get_gravity_X() : BNO08x
  • +
  • get_gravity_Y() : BNO08x
  • +
  • get_gravity_Z() : BNO08x
  • +
  • get_gyro_accuracy() : BNO08x
  • +
  • get_gyro_calibrated_velocity() : BNO08x
  • +
  • get_gyro_calibrated_velocity_X() : BNO08x
  • +
  • get_gyro_calibrated_velocity_Y() : BNO08x
  • +
  • get_gyro_calibrated_velocity_Z() : BNO08x
  • +
  • get_gyro_velocity() : BNO08x
  • +
  • get_gyro_velocity_X() : BNO08x
  • +
  • get_gyro_velocity_Y() : BNO08x
  • +
  • get_gyro_velocity_Z() : BNO08x
  • +
  • get_linear_accel() : BNO08x
  • +
  • get_linear_accel_accuracy() : BNO08x
  • +
  • get_linear_accel_X() : BNO08x
  • +
  • get_linear_accel_Y() : BNO08x
  • +
  • get_linear_accel_Z() : BNO08x
  • +
  • get_magf() : BNO08x
  • +
  • get_magf_accuracy() : BNO08x
  • +
  • get_magf_X() : BNO08x
  • +
  • get_magf_Y() : BNO08x
  • +
  • get_magf_Z() : BNO08x
  • +
  • get_pitch() : BNO08x
  • +
  • get_pitch_deg() : BNO08x
  • +
  • get_Q1() : BNO08x
  • +
  • get_Q2() : BNO08x
  • +
  • get_Q3() : BNO08x
  • +
  • get_quat() : BNO08x
  • +
  • get_quat_accuracy() : BNO08x
  • +
  • get_quat_I() : BNO08x
  • +
  • get_quat_J() : BNO08x
  • +
  • get_quat_K() : BNO08x
  • +
  • get_quat_radian_accuracy() : BNO08x
  • +
  • get_quat_real() : BNO08x
  • +
  • get_range() : BNO08x
  • +
  • get_raw_accel_X() : BNO08x
  • +
  • get_raw_accel_Y() : BNO08x
  • +
  • get_raw_accel_Z() : BNO08x
  • +
  • get_raw_gyro_X() : BNO08x
  • +
  • get_raw_gyro_Y() : BNO08x
  • +
  • get_raw_gyro_Z() : BNO08x
  • +
  • get_raw_magf_X() : BNO08x
  • +
  • get_raw_magf_Y() : BNO08x
  • +
  • get_raw_magf_Z() : BNO08x
  • +
  • get_readings() : BNO08x
  • +
  • get_reset_reason() : BNO08x
  • +
  • get_resolution() : BNO08x
  • +
  • get_roll() : BNO08x
  • +
  • get_roll_deg() : BNO08x
  • +
  • get_stability_classifier() : BNO08x
  • +
  • get_step_count() : BNO08x
  • +
  • get_tap_detector() : BNO08x
  • +
  • get_time_stamp() : BNO08x
  • +
  • get_uncalibrated_gyro() : BNO08x
  • +
  • get_uncalibrated_gyro_accuracy() : BNO08x
  • +
  • get_uncalibrated_gyro_bias_X() : BNO08x
  • +
  • get_uncalibrated_gyro_bias_Y() : BNO08x
  • +
  • get_uncalibrated_gyro_bias_Z() : BNO08x
  • +
  • get_uncalibrated_gyro_X() : BNO08x
  • +
  • get_uncalibrated_gyro_Y() : BNO08x
  • +
  • get_uncalibrated_gyro_Z() : BNO08x
  • +
  • get_yaw() : BNO08x
  • +
  • get_yaw_deg() : BNO08x
  • +
  • gravity_accuracy : BNO08x
  • +
  • GRAVITY_Q1 : BNO08x
  • +
  • gyro_accuracy : BNO08x
  • +
  • GYRO_Q1 : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_h.html b/documentation/html/functions_h.html new file mode 100644 index 0000000..d1fc493 --- /dev/null +++ b/documentation/html/functions_h.html @@ -0,0 +1,86 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- h -

+
+ + + + diff --git a/documentation/html/functions_i.html b/documentation/html/functions_i.html new file mode 100644 index 0000000..841c195 --- /dev/null +++ b/documentation/html/functions_i.html @@ -0,0 +1,94 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- i -

+
+ + + + diff --git a/documentation/html/functions_l.html b/documentation/html/functions_l.html new file mode 100644 index 0000000..e641671 --- /dev/null +++ b/documentation/html/functions_l.html @@ -0,0 +1,84 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- l -

    +
  • LINEAR_ACCELEROMETER_Q1 : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_m.html b/documentation/html/functions_m.html new file mode 100644 index 0000000..ed15977 --- /dev/null +++ b/documentation/html/functions_m.html @@ -0,0 +1,91 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- m -

+
+ + + + diff --git a/documentation/html/functions_p.html b/documentation/html/functions_p.html new file mode 100644 index 0000000..ac33675 --- /dev/null +++ b/documentation/html/functions_p.html @@ -0,0 +1,89 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- p -

    +
  • packet_header_rx : BNO08x
  • +
  • packet_length_rx : BNO08x
  • +
  • packet_length_tx : BNO08x
  • +
  • parse_command_report() : BNO08x
  • +
  • parse_input_report() : BNO08x
  • +
  • print_header() : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_q.html b/documentation/html/functions_q.html new file mode 100644 index 0000000..0845e0e --- /dev/null +++ b/documentation/html/functions_q.html @@ -0,0 +1,91 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- q -

    +
  • q_to_float() : BNO08x
  • +
  • quat_accuracy : BNO08x
  • +
  • queue_calibrate_command() : BNO08x
  • +
  • queue_command() : BNO08x
  • +
  • queue_feature_command() : BNO08x
  • +
  • queue_packet() : BNO08x
  • +
  • queue_request_product_id_command() : BNO08x
  • +
  • queue_tare_command() : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_r.html b/documentation/html/functions_r.html new file mode 100644 index 0000000..14640d4 --- /dev/null +++ b/documentation/html/functions_r.html @@ -0,0 +1,90 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- r -

    +
  • raw_velocity_gyro_Z : BNO08x
  • +
  • receive_packet() : BNO08x
  • +
  • request_calibration_status() : BNO08x
  • +
  • ROTATION_VECTOR_ACCURACY_Q1 : BNO08x
  • +
  • ROTATION_VECTOR_Q1 : BNO08x
  • +
  • run_full_calibration_routine() : BNO08x
  • +
  • rx_buffer : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_s.html b/documentation/html/functions_s.html new file mode 100644 index 0000000..55e5c0e --- /dev/null +++ b/documentation/html/functions_s.html @@ -0,0 +1,124 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- s -

    +
  • save_calibration() : BNO08x
  • +
  • save_tare() : BNO08x
  • +
  • sclk_speed : bno08x_config_t
  • +
  • send_packet() : BNO08x
  • +
  • SENSOR_REPORTID_ACCELEROMETER : BNO08x
  • +
  • SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR : BNO08x
  • +
  • SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR : BNO08x
  • +
  • SENSOR_REPORTID_GAME_ROTATION_VECTOR : BNO08x
  • +
  • SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR : BNO08x
  • +
  • SENSOR_REPORTID_GRAVITY : BNO08x
  • +
  • SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR : BNO08x
  • +
  • SENSOR_REPORTID_GYROSCOPE : BNO08x
  • +
  • SENSOR_REPORTID_LINEAR_ACCELERATION : BNO08x
  • +
  • SENSOR_REPORTID_MAGNETIC_FIELD : BNO08x
  • +
  • SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER : BNO08x
  • +
  • SENSOR_REPORTID_RAW_ACCELEROMETER : BNO08x
  • +
  • SENSOR_REPORTID_RAW_GYROSCOPE : BNO08x
  • +
  • SENSOR_REPORTID_RAW_MAGNETOMETER : BNO08x
  • +
  • SENSOR_REPORTID_ROTATION_VECTOR : BNO08x
  • +
  • SENSOR_REPORTID_STABILITY_CLASSIFIER : BNO08x
  • +
  • SENSOR_REPORTID_STEP_COUNTER : BNO08x
  • +
  • SENSOR_REPORTID_TAP_DETECTOR : BNO08x
  • +
  • SENSOR_REPORTID_UNCALIBRATED_GYRO : BNO08x
  • +
  • sequence_number : BNO08x
  • +
  • SHTP_REPORT_BASE_TIMESTAMP : BNO08x
  • +
  • SHTP_REPORT_COMMAND_REQUEST : BNO08x
  • +
  • SHTP_REPORT_COMMAND_RESPONSE : BNO08x
  • +
  • SHTP_REPORT_FRS_READ_REQUEST : BNO08x
  • +
  • SHTP_REPORT_FRS_READ_RESPONSE : BNO08x
  • +
  • SHTP_REPORT_PRODUCT_ID_REQUEST : BNO08x
  • +
  • SHTP_REPORT_PRODUCT_ID_RESPONSE : BNO08x
  • +
  • SHTP_REPORT_SET_FEATURE_COMMAND : BNO08x
  • +
  • soft_reset() : BNO08x
  • +
  • spi_hdl : BNO08x
  • +
  • spi_peripheral : bno08x_config_t
  • +
  • spi_task() : BNO08x
  • +
  • spi_task_hdl : BNO08x
  • +
  • spi_task_trampoline() : BNO08x
  • +
  • spi_transaction : BNO08x
  • +
  • stability_classifier : BNO08x
  • +
  • step_count : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_t.html b/documentation/html/functions_t.html new file mode 100644 index 0000000..71e113e --- /dev/null +++ b/documentation/html/functions_t.html @@ -0,0 +1,101 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- t -

    +
  • TAG : BNO08x
  • +
  • tap_detector : BNO08x
  • +
  • TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR : BNO08x
  • +
  • TARE_AR_VR_STABILIZED_ROTATION_VECTOR : BNO08x
  • +
  • TARE_AXIS_ALL : BNO08x
  • +
  • TARE_AXIS_Z : BNO08x
  • +
  • TARE_GAME_ROTATION_VECTOR : BNO08x
  • +
  • TARE_GEOMAGNETIC_ROTATION_VECTOR : BNO08x
  • +
  • TARE_GYRO_INTEGRATED_ROTATION_VECTOR : BNO08x
  • +
  • tare_now() : BNO08x
  • +
  • TARE_NOW : BNO08x
  • +
  • TARE_PERSIST : BNO08x
  • +
  • TARE_ROTATION_VECTOR : BNO08x
  • +
  • TARE_SET_REORIENTATION : BNO08x
  • +
  • time_stamp : BNO08x
  • +
  • tx_buffer : BNO08x
  • +
  • tx_packet_queued : BNO08x
  • +
  • tx_semaphore : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_u.html b/documentation/html/functions_u.html new file mode 100644 index 0000000..1658bcc --- /dev/null +++ b/documentation/html/functions_u.html @@ -0,0 +1,84 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- u -

    +
  • uncalib_gyro_accuracy : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_vars.html b/documentation/html/functions_vars.html new file mode 100644 index 0000000..76d201e --- /dev/null +++ b/documentation/html/functions_vars.html @@ -0,0 +1,247 @@ + + + + + + + +esp32_BNO08x: Class Members - Variables + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented variables with links to the class documentation for each member:
+ +

- a -

    +
  • accel_accuracy : BNO08x
  • +
  • accel_lin_accuracy : BNO08x
  • +
  • ACCELEROMETER_Q1 : BNO08x
  • +
  • activity_classifier : BNO08x
  • +
  • activity_confidences : BNO08x
  • +
  • ANGULAR_VELOCITY_Q1 : BNO08x
  • +
+ + +

- b -

+ + +

- c -

    +
  • CALIBRATE_ACCEL : BNO08x
  • +
  • CALIBRATE_ACCEL_GYRO_MAG : BNO08x
  • +
  • CALIBRATE_GYRO : BNO08x
  • +
  • CALIBRATE_MAG : BNO08x
  • +
  • CALIBRATE_PLANAR_ACCEL : BNO08x
  • +
  • CALIBRATE_STOP : BNO08x
  • +
  • calibration_status : BNO08x
  • +
  • COMMAND_CLEAR_DCD : BNO08x
  • +
  • COMMAND_DCD : BNO08x
  • +
  • COMMAND_DCD_PERIOD_SAVE : BNO08x
  • +
  • COMMAND_INITIALIZE : BNO08x
  • +
  • COMMAND_ME_CALIBRATE : BNO08x
  • +
  • COMMAND_OSCILLATOR : BNO08x
  • +
  • command_sequence_number : BNO08x
  • +
  • COMMAND_TARE : BNO08x
  • +
  • commands : BNO08x
  • +
+ + +

- d -

+ + +

- g -

+ + +

- h -

    +
  • HOST_INT_TIMEOUT_US : BNO08x
  • +
+ + +

- i -

+ + +

- l -

    +
  • LINEAR_ACCELEROMETER_Q1 : BNO08x
  • +
+ + +

- m -

+ + +

- p -

+ + +

- q -

+ + +

- r -

    +
  • raw_velocity_gyro_Z : BNO08x
  • +
  • ROTATION_VECTOR_ACCURACY_Q1 : BNO08x
  • +
  • ROTATION_VECTOR_Q1 : BNO08x
  • +
  • rx_buffer : BNO08x
  • +
+ + +

- s -

    +
  • sclk_speed : bno08x_config_t
  • +
  • SENSOR_REPORTID_ACCELEROMETER : BNO08x
  • +
  • SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR : BNO08x
  • +
  • SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR : BNO08x
  • +
  • SENSOR_REPORTID_GAME_ROTATION_VECTOR : BNO08x
  • +
  • SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR : BNO08x
  • +
  • SENSOR_REPORTID_GRAVITY : BNO08x
  • +
  • SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR : BNO08x
  • +
  • SENSOR_REPORTID_GYROSCOPE : BNO08x
  • +
  • SENSOR_REPORTID_LINEAR_ACCELERATION : BNO08x
  • +
  • SENSOR_REPORTID_MAGNETIC_FIELD : BNO08x
  • +
  • SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER : BNO08x
  • +
  • SENSOR_REPORTID_RAW_ACCELEROMETER : BNO08x
  • +
  • SENSOR_REPORTID_RAW_GYROSCOPE : BNO08x
  • +
  • SENSOR_REPORTID_RAW_MAGNETOMETER : BNO08x
  • +
  • SENSOR_REPORTID_ROTATION_VECTOR : BNO08x
  • +
  • SENSOR_REPORTID_STABILITY_CLASSIFIER : BNO08x
  • +
  • SENSOR_REPORTID_STEP_COUNTER : BNO08x
  • +
  • SENSOR_REPORTID_TAP_DETECTOR : BNO08x
  • +
  • SENSOR_REPORTID_UNCALIBRATED_GYRO : BNO08x
  • +
  • sequence_number : BNO08x
  • +
  • SHTP_REPORT_BASE_TIMESTAMP : BNO08x
  • +
  • SHTP_REPORT_COMMAND_REQUEST : BNO08x
  • +
  • SHTP_REPORT_COMMAND_RESPONSE : BNO08x
  • +
  • SHTP_REPORT_FRS_READ_REQUEST : BNO08x
  • +
  • SHTP_REPORT_FRS_READ_RESPONSE : BNO08x
  • +
  • SHTP_REPORT_PRODUCT_ID_REQUEST : BNO08x
  • +
  • SHTP_REPORT_PRODUCT_ID_RESPONSE : BNO08x
  • +
  • SHTP_REPORT_SET_FEATURE_COMMAND : BNO08x
  • +
  • spi_hdl : BNO08x
  • +
  • spi_peripheral : bno08x_config_t
  • +
  • spi_task_hdl : BNO08x
  • +
  • spi_transaction : BNO08x
  • +
  • stability_classifier : BNO08x
  • +
  • step_count : BNO08x
  • +
+ + +

- t -

    +
  • TAG : BNO08x
  • +
  • tap_detector : BNO08x
  • +
  • TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR : BNO08x
  • +
  • TARE_AR_VR_STABILIZED_ROTATION_VECTOR : BNO08x
  • +
  • TARE_AXIS_ALL : BNO08x
  • +
  • TARE_AXIS_Z : BNO08x
  • +
  • TARE_GAME_ROTATION_VECTOR : BNO08x
  • +
  • TARE_GEOMAGNETIC_ROTATION_VECTOR : BNO08x
  • +
  • TARE_GYRO_INTEGRATED_ROTATION_VECTOR : BNO08x
  • +
  • TARE_NOW : BNO08x
  • +
  • TARE_PERSIST : BNO08x
  • +
  • TARE_ROTATION_VECTOR : BNO08x
  • +
  • TARE_SET_REORIENTATION : BNO08x
  • +
  • time_stamp : BNO08x
  • +
  • tx_buffer : BNO08x
  • +
  • tx_packet_queued : BNO08x
  • +
  • tx_semaphore : BNO08x
  • +
+ + +

- u -

    +
  • uncalib_gyro_accuracy : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/functions_w.html b/documentation/html/functions_w.html new file mode 100644 index 0000000..da6dffa --- /dev/null +++ b/documentation/html/functions_w.html @@ -0,0 +1,84 @@ + + + + + + + +esp32_BNO08x: Class Members + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
Here is a list of all documented class members with links to the class documentation for each member:
+ +

- w -

    +
  • wait_for_device_int() : BNO08x
  • +
+
+ + + + diff --git a/documentation/html/index.html b/documentation/html/index.html new file mode 100644 index 0000000..02a91e2 --- /dev/null +++ b/documentation/html/index.html @@ -0,0 +1,82 @@ + + + + + + + +esp32_BNO08x: Main Page + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + +
+ +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
esp32_BNO08x Documentation
+
+
+
+ + + + diff --git a/documentation/html/jquery.js b/documentation/html/jquery.js new file mode 100644 index 0000000..1dffb65 --- /dev/null +++ b/documentation/html/jquery.js @@ -0,0 +1,34 @@ +/*! jQuery v3.6.0 | (c) OpenJS Foundation and other contributors | jquery.org/license */ +!function(e,t){"use strict";"object"==typeof module&&"object"==typeof module.exports?module.exports=e.document?t(e,!0):function(e){if(!e.document)throw new Error("jQuery requires a window with a document");return t(e)}:t(e)}("undefined"!=typeof window?window:this,function(C,e){"use strict";var t=[],r=Object.getPrototypeOf,s=t.slice,g=t.flat?function(e){return t.flat.call(e)}:function(e){return t.concat.apply([],e)},u=t.push,i=t.indexOf,n={},o=n.toString,v=n.hasOwnProperty,a=v.toString,l=a.call(Object),y={},m=function(e){return"function"==typeof e&&"number"!=typeof e.nodeType&&"function"!=typeof e.item},x=function(e){return null!=e&&e===e.window},E=C.document,c={type:!0,src:!0,nonce:!0,noModule:!0};function b(e,t,n){var r,i,o=(n=n||E).createElement("script");if(o.text=e,t)for(r in c)(i=t[r]||t.getAttribute&&t.getAttribute(r))&&o.setAttribute(r,i);n.head.appendChild(o).parentNode.removeChild(o)}function w(e){return null==e?e+"":"object"==typeof e||"function"==typeof e?n[o.call(e)]||"object":typeof e}var f="3.6.0",S=function(e,t){return new S.fn.init(e,t)};function p(e){var t=!!e&&"length"in e&&e.length,n=w(e);return!m(e)&&!x(e)&&("array"===n||0===t||"number"==typeof t&&0+~]|"+M+")"+M+"*"),U=new RegExp(M+"|>"),X=new RegExp(F),V=new RegExp("^"+I+"$"),G={ID:new RegExp("^#("+I+")"),CLASS:new RegExp("^\\.("+I+")"),TAG:new RegExp("^("+I+"|[*])"),ATTR:new RegExp("^"+W),PSEUDO:new RegExp("^"+F),CHILD:new RegExp("^:(only|first|last|nth|nth-last)-(child|of-type)(?:\\("+M+"*(even|odd|(([+-]|)(\\d*)n|)"+M+"*(?:([+-]|)"+M+"*(\\d+)|))"+M+"*\\)|)","i"),bool:new RegExp("^(?:"+R+")$","i"),needsContext:new RegExp("^"+M+"*[>+~]|:(even|odd|eq|gt|lt|nth|first|last)(?:\\("+M+"*((?:-\\d)?\\d*)"+M+"*\\)|)(?=[^-]|$)","i")},Y=/HTML$/i,Q=/^(?:input|select|textarea|button)$/i,J=/^h\d$/i,K=/^[^{]+\{\s*\[native \w/,Z=/^(?:#([\w-]+)|(\w+)|\.([\w-]+))$/,ee=/[+~]/,te=new RegExp("\\\\[\\da-fA-F]{1,6}"+M+"?|\\\\([^\\r\\n\\f])","g"),ne=function(e,t){var n="0x"+e.slice(1)-65536;return t||(n<0?String.fromCharCode(n+65536):String.fromCharCode(n>>10|55296,1023&n|56320))},re=/([\0-\x1f\x7f]|^-?\d)|^-$|[^\0-\x1f\x7f-\uFFFF\w-]/g,ie=function(e,t){return t?"\0"===e?"\ufffd":e.slice(0,-1)+"\\"+e.charCodeAt(e.length-1).toString(16)+" ":"\\"+e},oe=function(){T()},ae=be(function(e){return!0===e.disabled&&"fieldset"===e.nodeName.toLowerCase()},{dir:"parentNode",next:"legend"});try{H.apply(t=O.call(p.childNodes),p.childNodes),t[p.childNodes.length].nodeType}catch(e){H={apply:t.length?function(e,t){L.apply(e,O.call(t))}:function(e,t){var n=e.length,r=0;while(e[n++]=t[r++]);e.length=n-1}}}function se(t,e,n,r){var i,o,a,s,u,l,c,f=e&&e.ownerDocument,p=e?e.nodeType:9;if(n=n||[],"string"!=typeof t||!t||1!==p&&9!==p&&11!==p)return n;if(!r&&(T(e),e=e||C,E)){if(11!==p&&(u=Z.exec(t)))if(i=u[1]){if(9===p){if(!(a=e.getElementById(i)))return n;if(a.id===i)return n.push(a),n}else if(f&&(a=f.getElementById(i))&&y(e,a)&&a.id===i)return n.push(a),n}else{if(u[2])return H.apply(n,e.getElementsByTagName(t)),n;if((i=u[3])&&d.getElementsByClassName&&e.getElementsByClassName)return H.apply(n,e.getElementsByClassName(i)),n}if(d.qsa&&!N[t+" "]&&(!v||!v.test(t))&&(1!==p||"object"!==e.nodeName.toLowerCase())){if(c=t,f=e,1===p&&(U.test(t)||z.test(t))){(f=ee.test(t)&&ye(e.parentNode)||e)===e&&d.scope||((s=e.getAttribute("id"))?s=s.replace(re,ie):e.setAttribute("id",s=S)),o=(l=h(t)).length;while(o--)l[o]=(s?"#"+s:":scope")+" "+xe(l[o]);c=l.join(",")}try{return H.apply(n,f.querySelectorAll(c)),n}catch(e){N(t,!0)}finally{s===S&&e.removeAttribute("id")}}}return g(t.replace($,"$1"),e,n,r)}function ue(){var r=[];return function e(t,n){return r.push(t+" ")>b.cacheLength&&delete e[r.shift()],e[t+" "]=n}}function le(e){return e[S]=!0,e}function ce(e){var t=C.createElement("fieldset");try{return!!e(t)}catch(e){return!1}finally{t.parentNode&&t.parentNode.removeChild(t),t=null}}function fe(e,t){var n=e.split("|"),r=n.length;while(r--)b.attrHandle[n[r]]=t}function pe(e,t){var n=t&&e,r=n&&1===e.nodeType&&1===t.nodeType&&e.sourceIndex-t.sourceIndex;if(r)return r;if(n)while(n=n.nextSibling)if(n===t)return-1;return e?1:-1}function de(t){return function(e){return"input"===e.nodeName.toLowerCase()&&e.type===t}}function he(n){return function(e){var t=e.nodeName.toLowerCase();return("input"===t||"button"===t)&&e.type===n}}function ge(t){return function(e){return"form"in e?e.parentNode&&!1===e.disabled?"label"in e?"label"in e.parentNode?e.parentNode.disabled===t:e.disabled===t:e.isDisabled===t||e.isDisabled!==!t&&ae(e)===t:e.disabled===t:"label"in e&&e.disabled===t}}function ve(a){return le(function(o){return o=+o,le(function(e,t){var n,r=a([],e.length,o),i=r.length;while(i--)e[n=r[i]]&&(e[n]=!(t[n]=e[n]))})})}function ye(e){return e&&"undefined"!=typeof e.getElementsByTagName&&e}for(e in d=se.support={},i=se.isXML=function(e){var t=e&&e.namespaceURI,n=e&&(e.ownerDocument||e).documentElement;return!Y.test(t||n&&n.nodeName||"HTML")},T=se.setDocument=function(e){var t,n,r=e?e.ownerDocument||e:p;return r!=C&&9===r.nodeType&&r.documentElement&&(a=(C=r).documentElement,E=!i(C),p!=C&&(n=C.defaultView)&&n.top!==n&&(n.addEventListener?n.addEventListener("unload",oe,!1):n.attachEvent&&n.attachEvent("onunload",oe)),d.scope=ce(function(e){return a.appendChild(e).appendChild(C.createElement("div")),"undefined"!=typeof e.querySelectorAll&&!e.querySelectorAll(":scope fieldset div").length}),d.attributes=ce(function(e){return e.className="i",!e.getAttribute("className")}),d.getElementsByTagName=ce(function(e){return e.appendChild(C.createComment("")),!e.getElementsByTagName("*").length}),d.getElementsByClassName=K.test(C.getElementsByClassName),d.getById=ce(function(e){return a.appendChild(e).id=S,!C.getElementsByName||!C.getElementsByName(S).length}),d.getById?(b.filter.ID=function(e){var t=e.replace(te,ne);return function(e){return e.getAttribute("id")===t}},b.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&E){var n=t.getElementById(e);return n?[n]:[]}}):(b.filter.ID=function(e){var n=e.replace(te,ne);return function(e){var t="undefined"!=typeof e.getAttributeNode&&e.getAttributeNode("id");return t&&t.value===n}},b.find.ID=function(e,t){if("undefined"!=typeof t.getElementById&&E){var n,r,i,o=t.getElementById(e);if(o){if((n=o.getAttributeNode("id"))&&n.value===e)return[o];i=t.getElementsByName(e),r=0;while(o=i[r++])if((n=o.getAttributeNode("id"))&&n.value===e)return[o]}return[]}}),b.find.TAG=d.getElementsByTagName?function(e,t){return"undefined"!=typeof t.getElementsByTagName?t.getElementsByTagName(e):d.qsa?t.querySelectorAll(e):void 0}:function(e,t){var n,r=[],i=0,o=t.getElementsByTagName(e);if("*"===e){while(n=o[i++])1===n.nodeType&&r.push(n);return r}return o},b.find.CLASS=d.getElementsByClassName&&function(e,t){if("undefined"!=typeof t.getElementsByClassName&&E)return t.getElementsByClassName(e)},s=[],v=[],(d.qsa=K.test(C.querySelectorAll))&&(ce(function(e){var t;a.appendChild(e).innerHTML="",e.querySelectorAll("[msallowcapture^='']").length&&v.push("[*^$]="+M+"*(?:''|\"\")"),e.querySelectorAll("[selected]").length||v.push("\\["+M+"*(?:value|"+R+")"),e.querySelectorAll("[id~="+S+"-]").length||v.push("~="),(t=C.createElement("input")).setAttribute("name",""),e.appendChild(t),e.querySelectorAll("[name='']").length||v.push("\\["+M+"*name"+M+"*="+M+"*(?:''|\"\")"),e.querySelectorAll(":checked").length||v.push(":checked"),e.querySelectorAll("a#"+S+"+*").length||v.push(".#.+[+~]"),e.querySelectorAll("\\\f"),v.push("[\\r\\n\\f]")}),ce(function(e){e.innerHTML="";var t=C.createElement("input");t.setAttribute("type","hidden"),e.appendChild(t).setAttribute("name","D"),e.querySelectorAll("[name=d]").length&&v.push("name"+M+"*[*^$|!~]?="),2!==e.querySelectorAll(":enabled").length&&v.push(":enabled",":disabled"),a.appendChild(e).disabled=!0,2!==e.querySelectorAll(":disabled").length&&v.push(":enabled",":disabled"),e.querySelectorAll("*,:x"),v.push(",.*:")})),(d.matchesSelector=K.test(c=a.matches||a.webkitMatchesSelector||a.mozMatchesSelector||a.oMatchesSelector||a.msMatchesSelector))&&ce(function(e){d.disconnectedMatch=c.call(e,"*"),c.call(e,"[s!='']:x"),s.push("!=",F)}),v=v.length&&new RegExp(v.join("|")),s=s.length&&new RegExp(s.join("|")),t=K.test(a.compareDocumentPosition),y=t||K.test(a.contains)?function(e,t){var n=9===e.nodeType?e.documentElement:e,r=t&&t.parentNode;return e===r||!(!r||1!==r.nodeType||!(n.contains?n.contains(r):e.compareDocumentPosition&&16&e.compareDocumentPosition(r)))}:function(e,t){if(t)while(t=t.parentNode)if(t===e)return!0;return!1},j=t?function(e,t){if(e===t)return l=!0,0;var n=!e.compareDocumentPosition-!t.compareDocumentPosition;return n||(1&(n=(e.ownerDocument||e)==(t.ownerDocument||t)?e.compareDocumentPosition(t):1)||!d.sortDetached&&t.compareDocumentPosition(e)===n?e==C||e.ownerDocument==p&&y(p,e)?-1:t==C||t.ownerDocument==p&&y(p,t)?1:u?P(u,e)-P(u,t):0:4&n?-1:1)}:function(e,t){if(e===t)return l=!0,0;var n,r=0,i=e.parentNode,o=t.parentNode,a=[e],s=[t];if(!i||!o)return e==C?-1:t==C?1:i?-1:o?1:u?P(u,e)-P(u,t):0;if(i===o)return pe(e,t);n=e;while(n=n.parentNode)a.unshift(n);n=t;while(n=n.parentNode)s.unshift(n);while(a[r]===s[r])r++;return r?pe(a[r],s[r]):a[r]==p?-1:s[r]==p?1:0}),C},se.matches=function(e,t){return se(e,null,null,t)},se.matchesSelector=function(e,t){if(T(e),d.matchesSelector&&E&&!N[t+" "]&&(!s||!s.test(t))&&(!v||!v.test(t)))try{var n=c.call(e,t);if(n||d.disconnectedMatch||e.document&&11!==e.document.nodeType)return n}catch(e){N(t,!0)}return 0":{dir:"parentNode",first:!0}," ":{dir:"parentNode"},"+":{dir:"previousSibling",first:!0},"~":{dir:"previousSibling"}},preFilter:{ATTR:function(e){return e[1]=e[1].replace(te,ne),e[3]=(e[3]||e[4]||e[5]||"").replace(te,ne),"~="===e[2]&&(e[3]=" "+e[3]+" "),e.slice(0,4)},CHILD:function(e){return e[1]=e[1].toLowerCase(),"nth"===e[1].slice(0,3)?(e[3]||se.error(e[0]),e[4]=+(e[4]?e[5]+(e[6]||1):2*("even"===e[3]||"odd"===e[3])),e[5]=+(e[7]+e[8]||"odd"===e[3])):e[3]&&se.error(e[0]),e},PSEUDO:function(e){var t,n=!e[6]&&e[2];return G.CHILD.test(e[0])?null:(e[3]?e[2]=e[4]||e[5]||"":n&&X.test(n)&&(t=h(n,!0))&&(t=n.indexOf(")",n.length-t)-n.length)&&(e[0]=e[0].slice(0,t),e[2]=n.slice(0,t)),e.slice(0,3))}},filter:{TAG:function(e){var t=e.replace(te,ne).toLowerCase();return"*"===e?function(){return!0}:function(e){return e.nodeName&&e.nodeName.toLowerCase()===t}},CLASS:function(e){var t=m[e+" "];return t||(t=new RegExp("(^|"+M+")"+e+"("+M+"|$)"))&&m(e,function(e){return t.test("string"==typeof e.className&&e.className||"undefined"!=typeof e.getAttribute&&e.getAttribute("class")||"")})},ATTR:function(n,r,i){return function(e){var t=se.attr(e,n);return null==t?"!="===r:!r||(t+="","="===r?t===i:"!="===r?t!==i:"^="===r?i&&0===t.indexOf(i):"*="===r?i&&-1:\x20\t\r\n\f]*)[\x20\t\r\n\f]*\/?>(?:<\/\1>|)$/i;function j(e,n,r){return m(n)?S.grep(e,function(e,t){return!!n.call(e,t,e)!==r}):n.nodeType?S.grep(e,function(e){return e===n!==r}):"string"!=typeof n?S.grep(e,function(e){return-1)[^>]*|#([\w-]+))$/;(S.fn.init=function(e,t,n){var r,i;if(!e)return this;if(n=n||D,"string"==typeof e){if(!(r="<"===e[0]&&">"===e[e.length-1]&&3<=e.length?[null,e,null]:q.exec(e))||!r[1]&&t)return!t||t.jquery?(t||n).find(e):this.constructor(t).find(e);if(r[1]){if(t=t instanceof S?t[0]:t,S.merge(this,S.parseHTML(r[1],t&&t.nodeType?t.ownerDocument||t:E,!0)),N.test(r[1])&&S.isPlainObject(t))for(r in t)m(this[r])?this[r](t[r]):this.attr(r,t[r]);return this}return(i=E.getElementById(r[2]))&&(this[0]=i,this.length=1),this}return e.nodeType?(this[0]=e,this.length=1,this):m(e)?void 0!==n.ready?n.ready(e):e(S):S.makeArray(e,this)}).prototype=S.fn,D=S(E);var L=/^(?:parents|prev(?:Until|All))/,H={children:!0,contents:!0,next:!0,prev:!0};function O(e,t){while((e=e[t])&&1!==e.nodeType);return e}S.fn.extend({has:function(e){var t=S(e,this),n=t.length;return this.filter(function(){for(var e=0;e\x20\t\r\n\f]*)/i,he=/^$|^module$|\/(?:java|ecma)script/i;ce=E.createDocumentFragment().appendChild(E.createElement("div")),(fe=E.createElement("input")).setAttribute("type","radio"),fe.setAttribute("checked","checked"),fe.setAttribute("name","t"),ce.appendChild(fe),y.checkClone=ce.cloneNode(!0).cloneNode(!0).lastChild.checked,ce.innerHTML="",y.noCloneChecked=!!ce.cloneNode(!0).lastChild.defaultValue,ce.innerHTML="",y.option=!!ce.lastChild;var ge={thead:[1,"","
"],col:[2,"","
"],tr:[2,"","
"],td:[3,"","
"],_default:[0,"",""]};function ve(e,t){var n;return n="undefined"!=typeof e.getElementsByTagName?e.getElementsByTagName(t||"*"):"undefined"!=typeof e.querySelectorAll?e.querySelectorAll(t||"*"):[],void 0===t||t&&A(e,t)?S.merge([e],n):n}function ye(e,t){for(var n=0,r=e.length;n",""]);var me=/<|&#?\w+;/;function xe(e,t,n,r,i){for(var o,a,s,u,l,c,f=t.createDocumentFragment(),p=[],d=0,h=e.length;d\s*$/g;function je(e,t){return A(e,"table")&&A(11!==t.nodeType?t:t.firstChild,"tr")&&S(e).children("tbody")[0]||e}function De(e){return e.type=(null!==e.getAttribute("type"))+"/"+e.type,e}function qe(e){return"true/"===(e.type||"").slice(0,5)?e.type=e.type.slice(5):e.removeAttribute("type"),e}function Le(e,t){var n,r,i,o,a,s;if(1===t.nodeType){if(Y.hasData(e)&&(s=Y.get(e).events))for(i in Y.remove(t,"handle events"),s)for(n=0,r=s[i].length;n").attr(n.scriptAttrs||{}).prop({charset:n.scriptCharset,src:n.url}).on("load error",i=function(e){r.remove(),i=null,e&&t("error"===e.type?404:200,e.type)}),E.head.appendChild(r[0])},abort:function(){i&&i()}}});var _t,zt=[],Ut=/(=)\?(?=&|$)|\?\?/;S.ajaxSetup({jsonp:"callback",jsonpCallback:function(){var e=zt.pop()||S.expando+"_"+wt.guid++;return this[e]=!0,e}}),S.ajaxPrefilter("json jsonp",function(e,t,n){var r,i,o,a=!1!==e.jsonp&&(Ut.test(e.url)?"url":"string"==typeof e.data&&0===(e.contentType||"").indexOf("application/x-www-form-urlencoded")&&Ut.test(e.data)&&"data");if(a||"jsonp"===e.dataTypes[0])return r=e.jsonpCallback=m(e.jsonpCallback)?e.jsonpCallback():e.jsonpCallback,a?e[a]=e[a].replace(Ut,"$1"+r):!1!==e.jsonp&&(e.url+=(Tt.test(e.url)?"&":"?")+e.jsonp+"="+r),e.converters["script json"]=function(){return o||S.error(r+" was not called"),o[0]},e.dataTypes[0]="json",i=C[r],C[r]=function(){o=arguments},n.always(function(){void 0===i?S(C).removeProp(r):C[r]=i,e[r]&&(e.jsonpCallback=t.jsonpCallback,zt.push(r)),o&&m(i)&&i(o[0]),o=i=void 0}),"script"}),y.createHTMLDocument=((_t=E.implementation.createHTMLDocument("").body).innerHTML="
",2===_t.childNodes.length),S.parseHTML=function(e,t,n){return"string"!=typeof e?[]:("boolean"==typeof t&&(n=t,t=!1),t||(y.createHTMLDocument?((r=(t=E.implementation.createHTMLDocument("")).createElement("base")).href=E.location.href,t.head.appendChild(r)):t=E),o=!n&&[],(i=N.exec(e))?[t.createElement(i[1])]:(i=xe([e],t,o),o&&o.length&&S(o).remove(),S.merge([],i.childNodes)));var r,i,o},S.fn.load=function(e,t,n){var r,i,o,a=this,s=e.indexOf(" ");return-1").append(S.parseHTML(e)).find(r):e)}).always(n&&function(e,t){a.each(function(){n.apply(this,o||[e.responseText,t,e])})}),this},S.expr.pseudos.animated=function(t){return S.grep(S.timers,function(e){return t===e.elem}).length},S.offset={setOffset:function(e,t,n){var r,i,o,a,s,u,l=S.css(e,"position"),c=S(e),f={};"static"===l&&(e.style.position="relative"),s=c.offset(),o=S.css(e,"top"),u=S.css(e,"left"),("absolute"===l||"fixed"===l)&&-1<(o+u).indexOf("auto")?(a=(r=c.position()).top,i=r.left):(a=parseFloat(o)||0,i=parseFloat(u)||0),m(t)&&(t=t.call(e,n,S.extend({},s))),null!=t.top&&(f.top=t.top-s.top+a),null!=t.left&&(f.left=t.left-s.left+i),"using"in t?t.using.call(e,f):c.css(f)}},S.fn.extend({offset:function(t){if(arguments.length)return void 0===t?this:this.each(function(e){S.offset.setOffset(this,t,e)});var e,n,r=this[0];return r?r.getClientRects().length?(e=r.getBoundingClientRect(),n=r.ownerDocument.defaultView,{top:e.top+n.pageYOffset,left:e.left+n.pageXOffset}):{top:0,left:0}:void 0},position:function(){if(this[0]){var e,t,n,r=this[0],i={top:0,left:0};if("fixed"===S.css(r,"position"))t=r.getBoundingClientRect();else{t=this.offset(),n=r.ownerDocument,e=r.offsetParent||n.documentElement;while(e&&(e===n.body||e===n.documentElement)&&"static"===S.css(e,"position"))e=e.parentNode;e&&e!==r&&1===e.nodeType&&((i=S(e).offset()).top+=S.css(e,"borderTopWidth",!0),i.left+=S.css(e,"borderLeftWidth",!0))}return{top:t.top-i.top-S.css(r,"marginTop",!0),left:t.left-i.left-S.css(r,"marginLeft",!0)}}},offsetParent:function(){return this.map(function(){var e=this.offsetParent;while(e&&"static"===S.css(e,"position"))e=e.offsetParent;return e||re})}}),S.each({scrollLeft:"pageXOffset",scrollTop:"pageYOffset"},function(t,i){var o="pageYOffset"===i;S.fn[t]=function(e){return $(this,function(e,t,n){var r;if(x(e)?r=e:9===e.nodeType&&(r=e.defaultView),void 0===n)return r?r[i]:e[t];r?r.scrollTo(o?r.pageXOffset:n,o?n:r.pageYOffset):e[t]=n},t,e,arguments.length)}}),S.each(["top","left"],function(e,n){S.cssHooks[n]=Fe(y.pixelPosition,function(e,t){if(t)return t=We(e,n),Pe.test(t)?S(e).position()[n]+"px":t})}),S.each({Height:"height",Width:"width"},function(a,s){S.each({padding:"inner"+a,content:s,"":"outer"+a},function(r,o){S.fn[o]=function(e,t){var n=arguments.length&&(r||"boolean"!=typeof e),i=r||(!0===e||!0===t?"margin":"border");return $(this,function(e,t,n){var r;return x(e)?0===o.indexOf("outer")?e["inner"+a]:e.document.documentElement["client"+a]:9===e.nodeType?(r=e.documentElement,Math.max(e.body["scroll"+a],r["scroll"+a],e.body["offset"+a],r["offset"+a],r["client"+a])):void 0===n?S.css(e,t,i):S.style(e,t,n,i)},s,n?e:void 0,n)}})}),S.each(["ajaxStart","ajaxStop","ajaxComplete","ajaxError","ajaxSuccess","ajaxSend"],function(e,t){S.fn[t]=function(e){return this.on(t,e)}}),S.fn.extend({bind:function(e,t,n){return this.on(e,null,t,n)},unbind:function(e,t){return this.off(e,null,t)},delegate:function(e,t,n,r){return this.on(t,e,n,r)},undelegate:function(e,t,n){return 1===arguments.length?this.off(e,"**"):this.off(t,e||"**",n)},hover:function(e,t){return this.mouseenter(e).mouseleave(t||e)}}),S.each("blur focus focusin focusout resize scroll click dblclick mousedown mouseup mousemove mouseover mouseout mouseenter mouseleave change select submit keydown keypress keyup contextmenu".split(" "),function(e,n){S.fn[n]=function(e,t){return 0",options:{classes:{},disabled:!1,create:null},_createWidget:function(t,e){e=y(e||this.defaultElement||this)[0],this.element=y(e),this.uuid=i++,this.eventNamespace="."+this.widgetName+this.uuid,this.bindings=y(),this.hoverable=y(),this.focusable=y(),this.classesElementLookup={},e!==this&&(y.data(e,this.widgetFullName,this),this._on(!0,this.element,{remove:function(t){t.target===e&&this.destroy()}}),this.document=y(e.style?e.ownerDocument:e.document||e),this.window=y(this.document[0].defaultView||this.document[0].parentWindow)),this.options=y.widget.extend({},this.options,this._getCreateOptions(),t),this._create(),this.options.disabled&&this._setOptionDisabled(this.options.disabled),this._trigger("create",null,this._getCreateEventData()),this._init()},_getCreateOptions:function(){return{}},_getCreateEventData:y.noop,_create:y.noop,_init:y.noop,destroy:function(){var i=this;this._destroy(),y.each(this.classesElementLookup,function(t,e){i._removeClass(e,t)}),this.element.off(this.eventNamespace).removeData(this.widgetFullName),this.widget().off(this.eventNamespace).removeAttr("aria-disabled"),this.bindings.off(this.eventNamespace)},_destroy:y.noop,widget:function(){return this.element},option:function(t,e){var i,s,n,o=t;if(0===arguments.length)return y.widget.extend({},this.options);if("string"==typeof t)if(o={},t=(i=t.split(".")).shift(),i.length){for(s=o[t]=y.widget.extend({},this.options[t]),n=0;n
"),i=e.children()[0];return y("body").append(e),t=i.offsetWidth,e.css("overflow","scroll"),t===(i=i.offsetWidth)&&(i=e[0].clientWidth),e.remove(),s=t-i},getScrollInfo:function(t){var e=t.isWindow||t.isDocument?"":t.element.css("overflow-x"),i=t.isWindow||t.isDocument?"":t.element.css("overflow-y"),e="scroll"===e||"auto"===e&&t.widthx(D(s),D(n))?o.important="horizontal":o.important="vertical",p.using.call(this,t,o)}),h.offset(y.extend(l,{using:t}))})},y.ui.position={fit:{left:function(t,e){var i=e.within,s=i.isWindow?i.scrollLeft:i.offset.left,n=i.width,o=t.left-e.collisionPosition.marginLeft,h=s-o,a=o+e.collisionWidth-n-s;e.collisionWidth>n?0n?0=this.options.distance},_mouseDelayMet:function(){return this.mouseDelayMet},_mouseStart:function(){},_mouseDrag:function(){},_mouseStop:function(){},_mouseCapture:function(){return!0}}),y.ui.plugin={add:function(t,e,i){var s,n=y.ui[t].prototype;for(s in i)n.plugins[s]=n.plugins[s]||[],n.plugins[s].push([e,i[s]])},call:function(t,e,i,s){var n,o=t.plugins[e];if(o&&(s||t.element[0].parentNode&&11!==t.element[0].parentNode.nodeType))for(n=0;n").css({overflow:"hidden",position:this.element.css("position"),width:this.element.outerWidth(),height:this.element.outerHeight(),top:this.element.css("top"),left:this.element.css("left")})),this.element=this.element.parent().data("ui-resizable",this.element.resizable("instance")),this.elementIsWrapper=!0,t={marginTop:this.originalElement.css("marginTop"),marginRight:this.originalElement.css("marginRight"),marginBottom:this.originalElement.css("marginBottom"),marginLeft:this.originalElement.css("marginLeft")},this.element.css(t),this.originalElement.css("margin",0),this.originalResizeStyle=this.originalElement.css("resize"),this.originalElement.css("resize","none"),this._proportionallyResizeElements.push(this.originalElement.css({position:"static",zoom:1,display:"block"})),this.originalElement.css(t),this._proportionallyResize()),this._setupHandles(),e.autoHide&&y(this.element).on("mouseenter",function(){e.disabled||(i._removeClass("ui-resizable-autohide"),i._handles.show())}).on("mouseleave",function(){e.disabled||i.resizing||(i._addClass("ui-resizable-autohide"),i._handles.hide())}),this._mouseInit()},_destroy:function(){this._mouseDestroy(),this._addedHandles.remove();function t(t){y(t).removeData("resizable").removeData("ui-resizable").off(".resizable")}var e;return this.elementIsWrapper&&(t(this.element),e=this.element,this.originalElement.css({position:e.css("position"),width:e.outerWidth(),height:e.outerHeight(),top:e.css("top"),left:e.css("left")}).insertAfter(e),e.remove()),this.originalElement.css("resize",this.originalResizeStyle),t(this.originalElement),this},_setOption:function(t,e){switch(this._super(t,e),t){case"handles":this._removeHandles(),this._setupHandles();break;case"aspectRatio":this._aspectRatio=!!e}},_setupHandles:function(){var t,e,i,s,n,o=this.options,h=this;if(this.handles=o.handles||(y(".ui-resizable-handle",this.element).length?{n:".ui-resizable-n",e:".ui-resizable-e",s:".ui-resizable-s",w:".ui-resizable-w",se:".ui-resizable-se",sw:".ui-resizable-sw",ne:".ui-resizable-ne",nw:".ui-resizable-nw"}:"e,s,se"),this._handles=y(),this._addedHandles=y(),this.handles.constructor===String)for("all"===this.handles&&(this.handles="n,e,s,w,se,sw,ne,nw"),i=this.handles.split(","),this.handles={},e=0;e"),this._addClass(n,"ui-resizable-handle "+s),n.css({zIndex:o.zIndex}),this.handles[t]=".ui-resizable-"+t,this.element.children(this.handles[t]).length||(this.element.append(n),this._addedHandles=this._addedHandles.add(n));this._renderAxis=function(t){var e,i,s;for(e in t=t||this.element,this.handles)this.handles[e].constructor===String?this.handles[e]=this.element.children(this.handles[e]).first().show():(this.handles[e].jquery||this.handles[e].nodeType)&&(this.handles[e]=y(this.handles[e]),this._on(this.handles[e],{mousedown:h._mouseDown})),this.elementIsWrapper&&this.originalElement[0].nodeName.match(/^(textarea|input|select|button)$/i)&&(i=y(this.handles[e],this.element),s=/sw|ne|nw|se|n|s/.test(e)?i.outerHeight():i.outerWidth(),i=["padding",/ne|nw|n/.test(e)?"Top":/se|sw|s/.test(e)?"Bottom":/^e$/.test(e)?"Right":"Left"].join(""),t.css(i,s),this._proportionallyResize()),this._handles=this._handles.add(this.handles[e])},this._renderAxis(this.element),this._handles=this._handles.add(this.element.find(".ui-resizable-handle")),this._handles.disableSelection(),this._handles.on("mouseover",function(){h.resizing||(this.className&&(n=this.className.match(/ui-resizable-(se|sw|ne|nw|n|e|s|w)/i)),h.axis=n&&n[1]?n[1]:"se")}),o.autoHide&&(this._handles.hide(),this._addClass("ui-resizable-autohide"))},_removeHandles:function(){this._addedHandles.remove()},_mouseCapture:function(t){var e,i,s=!1;for(e in this.handles)(i=y(this.handles[e])[0])!==t.target&&!y.contains(i,t.target)||(s=!0);return!this.options.disabled&&s},_mouseStart:function(t){var e,i,s=this.options,n=this.element;return this.resizing=!0,this._renderProxy(),e=this._num(this.helper.css("left")),i=this._num(this.helper.css("top")),s.containment&&(e+=y(s.containment).scrollLeft()||0,i+=y(s.containment).scrollTop()||0),this.offset=this.helper.offset(),this.position={left:e,top:i},this.size=this._helper?{width:this.helper.width(),height:this.helper.height()}:{width:n.width(),height:n.height()},this.originalSize=this._helper?{width:n.outerWidth(),height:n.outerHeight()}:{width:n.width(),height:n.height()},this.sizeDiff={width:n.outerWidth()-n.width(),height:n.outerHeight()-n.height()},this.originalPosition={left:e,top:i},this.originalMousePosition={left:t.pageX,top:t.pageY},this.aspectRatio="number"==typeof s.aspectRatio?s.aspectRatio:this.originalSize.width/this.originalSize.height||1,s=y(".ui-resizable-"+this.axis).css("cursor"),y("body").css("cursor","auto"===s?this.axis+"-resize":s),this._addClass("ui-resizable-resizing"),this._propagate("start",t),!0},_mouseDrag:function(t){var e=this.originalMousePosition,i=this.axis,s=t.pageX-e.left||0,e=t.pageY-e.top||0,i=this._change[i];return this._updatePrevProperties(),i&&(e=i.apply(this,[t,s,e]),this._updateVirtualBoundaries(t.shiftKey),(this._aspectRatio||t.shiftKey)&&(e=this._updateRatio(e,t)),e=this._respectSize(e,t),this._updateCache(e),this._propagate("resize",t),e=this._applyChanges(),!this._helper&&this._proportionallyResizeElements.length&&this._proportionallyResize(),y.isEmptyObject(e)||(this._updatePrevProperties(),this._trigger("resize",t,this.ui()),this._applyChanges())),!1},_mouseStop:function(t){this.resizing=!1;var e,i,s,n=this.options,o=this;return this._helper&&(s=(e=(i=this._proportionallyResizeElements).length&&/textarea/i.test(i[0].nodeName))&&this._hasScroll(i[0],"left")?0:o.sizeDiff.height,i=e?0:o.sizeDiff.width,e={width:o.helper.width()-i,height:o.helper.height()-s},i=parseFloat(o.element.css("left"))+(o.position.left-o.originalPosition.left)||null,s=parseFloat(o.element.css("top"))+(o.position.top-o.originalPosition.top)||null,n.animate||this.element.css(y.extend(e,{top:s,left:i})),o.helper.height(o.size.height),o.helper.width(o.size.width),this._helper&&!n.animate&&this._proportionallyResize()),y("body").css("cursor","auto"),this._removeClass("ui-resizable-resizing"),this._propagate("stop",t),this._helper&&this.helper.remove(),!1},_updatePrevProperties:function(){this.prevPosition={top:this.position.top,left:this.position.left},this.prevSize={width:this.size.width,height:this.size.height}},_applyChanges:function(){var t={};return this.position.top!==this.prevPosition.top&&(t.top=this.position.top+"px"),this.position.left!==this.prevPosition.left&&(t.left=this.position.left+"px"),this.size.width!==this.prevSize.width&&(t.width=this.size.width+"px"),this.size.height!==this.prevSize.height&&(t.height=this.size.height+"px"),this.helper.css(t),t},_updateVirtualBoundaries:function(t){var e,i,s=this.options,n={minWidth:this._isNumber(s.minWidth)?s.minWidth:0,maxWidth:this._isNumber(s.maxWidth)?s.maxWidth:1/0,minHeight:this._isNumber(s.minHeight)?s.minHeight:0,maxHeight:this._isNumber(s.maxHeight)?s.maxHeight:1/0};(this._aspectRatio||t)&&(e=n.minHeight*this.aspectRatio,i=n.minWidth/this.aspectRatio,s=n.maxHeight*this.aspectRatio,t=n.maxWidth/this.aspectRatio,e>n.minWidth&&(n.minWidth=e),i>n.minHeight&&(n.minHeight=i),st.width,h=this._isNumber(t.height)&&e.minHeight&&e.minHeight>t.height,a=this.originalPosition.left+this.originalSize.width,r=this.originalPosition.top+this.originalSize.height,l=/sw|nw|w/.test(i),i=/nw|ne|n/.test(i);return o&&(t.width=e.minWidth),h&&(t.height=e.minHeight),s&&(t.width=e.maxWidth),n&&(t.height=e.maxHeight),o&&l&&(t.left=a-e.minWidth),s&&l&&(t.left=a-e.maxWidth),h&&i&&(t.top=r-e.minHeight),n&&i&&(t.top=r-e.maxHeight),t.width||t.height||t.left||!t.top?t.width||t.height||t.top||!t.left||(t.left=null):t.top=null,t},_getPaddingPlusBorderDimensions:function(t){for(var e=0,i=[],s=[t.css("borderTopWidth"),t.css("borderRightWidth"),t.css("borderBottomWidth"),t.css("borderLeftWidth")],n=[t.css("paddingTop"),t.css("paddingRight"),t.css("paddingBottom"),t.css("paddingLeft")];e<4;e++)i[e]=parseFloat(s[e])||0,i[e]+=parseFloat(n[e])||0;return{height:i[0]+i[2],width:i[1]+i[3]}},_proportionallyResize:function(){if(this._proportionallyResizeElements.length)for(var t,e=0,i=this.helper||this.element;e").css({overflow:"hidden"}),this._addClass(this.helper,this._helper),this.helper.css({width:this.element.outerWidth(),height:this.element.outerHeight(),position:"absolute",left:this.elementOffset.left+"px",top:this.elementOffset.top+"px",zIndex:++e.zIndex}),this.helper.appendTo("body").disableSelection()):this.helper=this.element},_change:{e:function(t,e){return{width:this.originalSize.width+e}},w:function(t,e){var i=this.originalSize;return{left:this.originalPosition.left+e,width:i.width-e}},n:function(t,e,i){var s=this.originalSize;return{top:this.originalPosition.top+i,height:s.height-i}},s:function(t,e,i){return{height:this.originalSize.height+i}},se:function(t,e,i){return y.extend(this._change.s.apply(this,arguments),this._change.e.apply(this,[t,e,i]))},sw:function(t,e,i){return y.extend(this._change.s.apply(this,arguments),this._change.w.apply(this,[t,e,i]))},ne:function(t,e,i){return y.extend(this._change.n.apply(this,arguments),this._change.e.apply(this,[t,e,i]))},nw:function(t,e,i){return y.extend(this._change.n.apply(this,arguments),this._change.w.apply(this,[t,e,i]))}},_propagate:function(t,e){y.ui.plugin.call(this,t,[e,this.ui()]),"resize"!==t&&this._trigger(t,e,this.ui())},plugins:{},ui:function(){return{originalElement:this.originalElement,element:this.element,helper:this.helper,position:this.position,size:this.size,originalSize:this.originalSize,originalPosition:this.originalPosition}}}),y.ui.plugin.add("resizable","animate",{stop:function(e){var i=y(this).resizable("instance"),t=i.options,s=i._proportionallyResizeElements,n=s.length&&/textarea/i.test(s[0].nodeName),o=n&&i._hasScroll(s[0],"left")?0:i.sizeDiff.height,h=n?0:i.sizeDiff.width,n={width:i.size.width-h,height:i.size.height-o},h=parseFloat(i.element.css("left"))+(i.position.left-i.originalPosition.left)||null,o=parseFloat(i.element.css("top"))+(i.position.top-i.originalPosition.top)||null;i.element.animate(y.extend(n,o&&h?{top:o,left:h}:{}),{duration:t.animateDuration,easing:t.animateEasing,step:function(){var t={width:parseFloat(i.element.css("width")),height:parseFloat(i.element.css("height")),top:parseFloat(i.element.css("top")),left:parseFloat(i.element.css("left"))};s&&s.length&&y(s[0]).css({width:t.width,height:t.height}),i._updateCache(t),i._propagate("resize",e)}})}}),y.ui.plugin.add("resizable","containment",{start:function(){var i,s,n=y(this).resizable("instance"),t=n.options,e=n.element,o=t.containment,h=o instanceof y?o.get(0):/parent/.test(o)?e.parent().get(0):o;h&&(n.containerElement=y(h),/document/.test(o)||o===document?(n.containerOffset={left:0,top:0},n.containerPosition={left:0,top:0},n.parentData={element:y(document),left:0,top:0,width:y(document).width(),height:y(document).height()||document.body.parentNode.scrollHeight}):(i=y(h),s=[],y(["Top","Right","Left","Bottom"]).each(function(t,e){s[t]=n._num(i.css("padding"+e))}),n.containerOffset=i.offset(),n.containerPosition=i.position(),n.containerSize={height:i.innerHeight()-s[3],width:i.innerWidth()-s[1]},t=n.containerOffset,e=n.containerSize.height,o=n.containerSize.width,o=n._hasScroll(h,"left")?h.scrollWidth:o,e=n._hasScroll(h)?h.scrollHeight:e,n.parentData={element:h,left:t.left,top:t.top,width:o,height:e}))},resize:function(t){var e=y(this).resizable("instance"),i=e.options,s=e.containerOffset,n=e.position,o=e._aspectRatio||t.shiftKey,h={top:0,left:0},a=e.containerElement,t=!0;a[0]!==document&&/static/.test(a.css("position"))&&(h=s),n.left<(e._helper?s.left:0)&&(e.size.width=e.size.width+(e._helper?e.position.left-s.left:e.position.left-h.left),o&&(e.size.height=e.size.width/e.aspectRatio,t=!1),e.position.left=i.helper?s.left:0),n.top<(e._helper?s.top:0)&&(e.size.height=e.size.height+(e._helper?e.position.top-s.top:e.position.top),o&&(e.size.width=e.size.height*e.aspectRatio,t=!1),e.position.top=e._helper?s.top:0),i=e.containerElement.get(0)===e.element.parent().get(0),n=/relative|absolute/.test(e.containerElement.css("position")),i&&n?(e.offset.left=e.parentData.left+e.position.left,e.offset.top=e.parentData.top+e.position.top):(e.offset.left=e.element.offset().left,e.offset.top=e.element.offset().top),n=Math.abs(e.sizeDiff.width+(e._helper?e.offset.left-h.left:e.offset.left-s.left)),s=Math.abs(e.sizeDiff.height+(e._helper?e.offset.top-h.top:e.offset.top-s.top)),n+e.size.width>=e.parentData.width&&(e.size.width=e.parentData.width-n,o&&(e.size.height=e.size.width/e.aspectRatio,t=!1)),s+e.size.height>=e.parentData.height&&(e.size.height=e.parentData.height-s,o&&(e.size.width=e.size.height*e.aspectRatio,t=!1)),t||(e.position.left=e.prevPosition.left,e.position.top=e.prevPosition.top,e.size.width=e.prevSize.width,e.size.height=e.prevSize.height)},stop:function(){var t=y(this).resizable("instance"),e=t.options,i=t.containerOffset,s=t.containerPosition,n=t.containerElement,o=y(t.helper),h=o.offset(),a=o.outerWidth()-t.sizeDiff.width,o=o.outerHeight()-t.sizeDiff.height;t._helper&&!e.animate&&/relative/.test(n.css("position"))&&y(this).css({left:h.left-s.left-i.left,width:a,height:o}),t._helper&&!e.animate&&/static/.test(n.css("position"))&&y(this).css({left:h.left-s.left-i.left,width:a,height:o})}}),y.ui.plugin.add("resizable","alsoResize",{start:function(){var t=y(this).resizable("instance").options;y(t.alsoResize).each(function(){var t=y(this);t.data("ui-resizable-alsoresize",{width:parseFloat(t.width()),height:parseFloat(t.height()),left:parseFloat(t.css("left")),top:parseFloat(t.css("top"))})})},resize:function(t,i){var e=y(this).resizable("instance"),s=e.options,n=e.originalSize,o=e.originalPosition,h={height:e.size.height-n.height||0,width:e.size.width-n.width||0,top:e.position.top-o.top||0,left:e.position.left-o.left||0};y(s.alsoResize).each(function(){var t=y(this),s=y(this).data("ui-resizable-alsoresize"),n={},e=t.parents(i.originalElement[0]).length?["width","height"]:["width","height","top","left"];y.each(e,function(t,e){var i=(s[e]||0)+(h[e]||0);i&&0<=i&&(n[e]=i||null)}),t.css(n)})},stop:function(){y(this).removeData("ui-resizable-alsoresize")}}),y.ui.plugin.add("resizable","ghost",{start:function(){var t=y(this).resizable("instance"),e=t.size;t.ghost=t.originalElement.clone(),t.ghost.css({opacity:.25,display:"block",position:"relative",height:e.height,width:e.width,margin:0,left:0,top:0}),t._addClass(t.ghost,"ui-resizable-ghost"),!1!==y.uiBackCompat&&"string"==typeof t.options.ghost&&t.ghost.addClass(this.options.ghost),t.ghost.appendTo(t.helper)},resize:function(){var t=y(this).resizable("instance");t.ghost&&t.ghost.css({position:"relative",height:t.size.height,width:t.size.width})},stop:function(){var t=y(this).resizable("instance");t.ghost&&t.helper&&t.helper.get(0).removeChild(t.ghost.get(0))}}),y.ui.plugin.add("resizable","grid",{resize:function(){var t,e=y(this).resizable("instance"),i=e.options,s=e.size,n=e.originalSize,o=e.originalPosition,h=e.axis,a="number"==typeof i.grid?[i.grid,i.grid]:i.grid,r=a[0]||1,l=a[1]||1,u=Math.round((s.width-n.width)/r)*r,p=Math.round((s.height-n.height)/l)*l,d=n.width+u,c=n.height+p,f=i.maxWidth&&i.maxWidthd,s=i.minHeight&&i.minHeight>c;i.grid=a,m&&(d+=r),s&&(c+=l),f&&(d-=r),g&&(c-=l),/^(se|s|e)$/.test(h)?(e.size.width=d,e.size.height=c):/^(ne)$/.test(h)?(e.size.width=d,e.size.height=c,e.position.top=o.top-p):/^(sw)$/.test(h)?(e.size.width=d,e.size.height=c,e.position.left=o.left-u):((c-l<=0||d-r<=0)&&(t=e._getPaddingPlusBorderDimensions(this)),0=f[g]?0:Math.min(f[g],n));!a&&1-1){targetElements.on(evt+EVENT_NAMESPACE,function elementToggle(event){$.powerTip.toggle(this,event)})}else{targetElements.on(evt+EVENT_NAMESPACE,function elementOpen(event){$.powerTip.show(this,event)})}});$.each(options.closeEvents,function(idx,evt){if($.inArray(evt,options.openEvents)<0){targetElements.on(evt+EVENT_NAMESPACE,function elementClose(event){$.powerTip.hide(this,!isMouseEvent(event))})}});targetElements.on("keydown"+EVENT_NAMESPACE,function elementKeyDown(event){if(event.keyCode===27){$.powerTip.hide(this,true)}})}return targetElements};$.fn.powerTip.defaults={fadeInTime:200,fadeOutTime:100,followMouse:false,popupId:"powerTip",popupClass:null,intentSensitivity:7,intentPollInterval:100,closeDelay:100,placement:"n",smartPlacement:false,offset:10,mouseOnToPopup:false,manual:false,openEvents:["mouseenter","focus"],closeEvents:["mouseleave","blur"]};$.fn.powerTip.smartPlacementLists={n:["n","ne","nw","s"],e:["e","ne","se","w","nw","sw","n","s","e"],s:["s","se","sw","n"],w:["w","nw","sw","e","ne","se","n","s","w"],nw:["nw","w","sw","n","s","se","nw"],ne:["ne","e","se","n","s","sw","ne"],sw:["sw","w","nw","s","n","ne","sw"],se:["se","e","ne","s","n","nw","se"],"nw-alt":["nw-alt","n","ne-alt","sw-alt","s","se-alt","w","e"],"ne-alt":["ne-alt","n","nw-alt","se-alt","s","sw-alt","e","w"],"sw-alt":["sw-alt","s","se-alt","nw-alt","n","ne-alt","w","e"],"se-alt":["se-alt","s","sw-alt","ne-alt","n","nw-alt","e","w"]};$.powerTip={show:function apiShowTip(element,event){if(isMouseEvent(event)){trackMouse(event);session.previousX=event.pageX;session.previousY=event.pageY;$(element).data(DATA_DISPLAYCONTROLLER).show()}else{$(element).first().data(DATA_DISPLAYCONTROLLER).show(true,true)}return element},reposition:function apiResetPosition(element){$(element).first().data(DATA_DISPLAYCONTROLLER).resetPosition();return element},hide:function apiCloseTip(element,immediate){var displayController;immediate=element?immediate:true;if(element){displayController=$(element).first().data(DATA_DISPLAYCONTROLLER)}else if(session.activeHover){displayController=session.activeHover.data(DATA_DISPLAYCONTROLLER)}if(displayController){displayController.hide(immediate)}return element},toggle:function apiToggle(element,event){if(session.activeHover&&session.activeHover.is(element)){$.powerTip.hide(element,!isMouseEvent(event))}else{$.powerTip.show(element,event)}return element}};$.powerTip.showTip=$.powerTip.show;$.powerTip.closeTip=$.powerTip.hide;function CSSCoordinates(){var me=this;me.top="auto";me.left="auto";me.right="auto";me.bottom="auto";me.set=function(property,value){if($.isNumeric(value)){me[property]=Math.round(value)}}}function DisplayController(element,options,tipController){var hoverTimer=null,myCloseDelay=null;function openTooltip(immediate,forceOpen){cancelTimer();if(!element.data(DATA_HASACTIVEHOVER)){if(!immediate){session.tipOpenImminent=true;hoverTimer=setTimeout(function intentDelay(){hoverTimer=null;checkForIntent()},options.intentPollInterval)}else{if(forceOpen){element.data(DATA_FORCEDOPEN,true)}closeAnyDelayed();tipController.showTip(element)}}else{cancelClose()}}function closeTooltip(disableDelay){if(myCloseDelay){myCloseDelay=session.closeDelayTimeout=clearTimeout(myCloseDelay);session.delayInProgress=false}cancelTimer();session.tipOpenImminent=false;if(element.data(DATA_HASACTIVEHOVER)){element.data(DATA_FORCEDOPEN,false);if(!disableDelay){session.delayInProgress=true;session.closeDelayTimeout=setTimeout(function closeDelay(){session.closeDelayTimeout=null;tipController.hideTip(element);session.delayInProgress=false;myCloseDelay=null},options.closeDelay);myCloseDelay=session.closeDelayTimeout}else{tipController.hideTip(element)}}}function checkForIntent(){var xDifference=Math.abs(session.previousX-session.currentX),yDifference=Math.abs(session.previousY-session.currentY),totalDifference=xDifference+yDifference;if(totalDifference",{id:options.popupId});if($body.length===0){$body=$("body")}$body.append(tipElement);session.tooltips=session.tooltips?session.tooltips.add(tipElement):tipElement}if(options.followMouse){if(!tipElement.data(DATA_HASMOUSEMOVE)){$document.on("mousemove"+EVENT_NAMESPACE,positionTipOnCursor);$window.on("scroll"+EVENT_NAMESPACE,positionTipOnCursor);tipElement.data(DATA_HASMOUSEMOVE,true)}}function beginShowTip(element){element.data(DATA_HASACTIVEHOVER,true);tipElement.queue(function queueTipInit(next){showTip(element);next()})}function showTip(element){var tipContent;if(!element.data(DATA_HASACTIVEHOVER)){return}if(session.isTipOpen){if(!session.isClosing){hideTip(session.activeHover)}tipElement.delay(100).queue(function queueTipAgain(next){showTip(element);next()});return}element.trigger("powerTipPreRender");tipContent=getTooltipContent(element);if(tipContent){tipElement.empty().append(tipContent)}else{return}element.trigger("powerTipRender");session.activeHover=element;session.isTipOpen=true;tipElement.data(DATA_MOUSEONTOTIP,options.mouseOnToPopup);tipElement.addClass(options.popupClass);if(!options.followMouse||element.data(DATA_FORCEDOPEN)){positionTipOnElement(element);session.isFixedTipOpen=true}else{positionTipOnCursor()}if(!element.data(DATA_FORCEDOPEN)&&!options.followMouse){$document.on("click"+EVENT_NAMESPACE,function documentClick(event){var target=event.target;if(target!==element[0]){if(options.mouseOnToPopup){if(target!==tipElement[0]&&!$.contains(tipElement[0],target)){$.powerTip.hide()}}else{$.powerTip.hide()}}})}if(options.mouseOnToPopup&&!options.manual){tipElement.on("mouseenter"+EVENT_NAMESPACE,function tipMouseEnter(){if(session.activeHover){session.activeHover.data(DATA_DISPLAYCONTROLLER).cancel()}});tipElement.on("mouseleave"+EVENT_NAMESPACE,function tipMouseLeave(){if(session.activeHover){session.activeHover.data(DATA_DISPLAYCONTROLLER).hide()}})}tipElement.fadeIn(options.fadeInTime,function fadeInCallback(){if(!session.desyncTimeout){session.desyncTimeout=setInterval(closeDesyncedTip,500)}element.trigger("powerTipOpen")})}function hideTip(element){session.isClosing=true;session.isTipOpen=false;session.desyncTimeout=clearInterval(session.desyncTimeout);element.data(DATA_HASACTIVEHOVER,false);element.data(DATA_FORCEDOPEN,false);$document.off("click"+EVENT_NAMESPACE);tipElement.off(EVENT_NAMESPACE);tipElement.fadeOut(options.fadeOutTime,function fadeOutCallback(){var coords=new CSSCoordinates;session.activeHover=null;session.isClosing=false;session.isFixedTipOpen=false;tipElement.removeClass();coords.set("top",session.currentY+options.offset);coords.set("left",session.currentX+options.offset);tipElement.css(coords);element.trigger("powerTipClose")})}function positionTipOnCursor(){var tipWidth,tipHeight,coords,collisions,collisionCount;if(!session.isFixedTipOpen&&(session.isTipOpen||session.tipOpenImminent&&tipElement.data(DATA_HASMOUSEMOVE))){tipWidth=tipElement.outerWidth();tipHeight=tipElement.outerHeight();coords=new CSSCoordinates;coords.set("top",session.currentY+options.offset);coords.set("left",session.currentX+options.offset);collisions=getViewportCollisions(coords,tipWidth,tipHeight);if(collisions!==Collision.none){collisionCount=countFlags(collisions);if(collisionCount===1){if(collisions===Collision.right){coords.set("left",session.scrollLeft+session.windowWidth-tipWidth)}else if(collisions===Collision.bottom){coords.set("top",session.scrollTop+session.windowHeight-tipHeight)}}else{coords.set("left",session.currentX-tipWidth-options.offset);coords.set("top",session.currentY-tipHeight-options.offset)}}tipElement.css(coords)}}function positionTipOnElement(element){var priorityList,finalPlacement;if(options.smartPlacement||options.followMouse&&element.data(DATA_FORCEDOPEN)){priorityList=$.fn.powerTip.smartPlacementLists[options.placement];$.each(priorityList,function(idx,pos){var collisions=getViewportCollisions(placeTooltip(element,pos),tipElement.outerWidth(),tipElement.outerHeight());finalPlacement=pos;return collisions!==Collision.none})}else{placeTooltip(element,options.placement);finalPlacement=options.placement}tipElement.removeClass("w nw sw e ne se n s w se-alt sw-alt ne-alt nw-alt");tipElement.addClass(finalPlacement)}function placeTooltip(element,placement){var iterationCount=0,tipWidth,tipHeight,coords=new CSSCoordinates;coords.set("top",0);coords.set("left",0);tipElement.css(coords);do{tipWidth=tipElement.outerWidth();tipHeight=tipElement.outerHeight();coords=placementCalculator.compute(element,placement,tipWidth,tipHeight,options.offset);tipElement.css(coords)}while(++iterationCount<=5&&(tipWidth!==tipElement.outerWidth()||tipHeight!==tipElement.outerHeight()));return coords}function closeDesyncedTip(){var isDesynced=false,hasDesyncableCloseEvent=$.grep(["mouseleave","mouseout","blur","focusout"],function(eventType){return $.inArray(eventType,options.closeEvents)!==-1}).length>0;if(session.isTipOpen&&!session.isClosing&&!session.delayInProgress&&hasDesyncableCloseEvent){if(session.activeHover.data(DATA_HASACTIVEHOVER)===false||session.activeHover.is(":disabled")){isDesynced=true}else if(!isMouseOver(session.activeHover)&&!session.activeHover.is(":focus")&&!session.activeHover.data(DATA_FORCEDOPEN)){if(tipElement.data(DATA_MOUSEONTOTIP)){if(!isMouseOver(tipElement)){isDesynced=true}}else{isDesynced=true}}if(isDesynced){hideTip(session.activeHover)}}}this.showTip=beginShowTip;this.hideTip=hideTip;this.resetPosition=positionTipOnElement}function isSvgElement(element){return Boolean(window.SVGElement&&element[0]instanceof SVGElement)}function isMouseEvent(event){return Boolean(event&&$.inArray(event.type,MOUSE_EVENTS)>-1&&typeof event.pageX==="number")}function initTracking(){if(!session.mouseTrackingActive){session.mouseTrackingActive=true;getViewportDimensions();$(getViewportDimensions);$document.on("mousemove"+EVENT_NAMESPACE,trackMouse);$window.on("resize"+EVENT_NAMESPACE,trackResize);$window.on("scroll"+EVENT_NAMESPACE,trackScroll)}}function getViewportDimensions(){session.scrollLeft=$window.scrollLeft();session.scrollTop=$window.scrollTop();session.windowWidth=$window.width();session.windowHeight=$window.height()}function trackResize(){session.windowWidth=$window.width();session.windowHeight=$window.height()}function trackScroll(){var x=$window.scrollLeft(),y=$window.scrollTop();if(x!==session.scrollLeft){session.currentX+=x-session.scrollLeft;session.scrollLeft=x}if(y!==session.scrollTop){session.currentY+=y-session.scrollTop;session.scrollTop=y}}function trackMouse(event){session.currentX=event.pageX;session.currentY=event.pageY}function isMouseOver(element){var elementPosition=element.offset(),elementBox=element[0].getBoundingClientRect(),elementWidth=elementBox.right-elementBox.left,elementHeight=elementBox.bottom-elementBox.top;return session.currentX>=elementPosition.left&&session.currentX<=elementPosition.left+elementWidth&&session.currentY>=elementPosition.top&&session.currentY<=elementPosition.top+elementHeight}function getTooltipContent(element){var tipText=element.data(DATA_POWERTIP),tipObject=element.data(DATA_POWERTIPJQ),tipTarget=element.data(DATA_POWERTIPTARGET),targetElement,content;if(tipText){if($.isFunction(tipText)){tipText=tipText.call(element[0])}content=tipText}else if(tipObject){if($.isFunction(tipObject)){tipObject=tipObject.call(element[0])}if(tipObject.length>0){content=tipObject.clone(true,true)}}else if(tipTarget){targetElement=$("#"+tipTarget);if(targetElement.length>0){content=targetElement.html()}}return content}function getViewportCollisions(coords,elementWidth,elementHeight){var viewportTop=session.scrollTop,viewportLeft=session.scrollLeft,viewportBottom=viewportTop+session.windowHeight,viewportRight=viewportLeft+session.windowWidth,collisions=Collision.none;if(coords.topviewportBottom||Math.abs(coords.bottom-session.windowHeight)>viewportBottom){collisions|=Collision.bottom}if(coords.leftviewportRight){collisions|=Collision.left}if(coords.left+elementWidth>viewportRight||coords.right1)){a.preventDefault();var c=a.originalEvent.changedTouches[0],d=document.createEvent("MouseEvents");d.initMouseEvent(b,!0,!0,window,1,c.screenX,c.screenY,c.clientX,c.clientY,!1,!1,!1,!1,0,null),a.target.dispatchEvent(d)}}if(a.support.touch="ontouchend"in document,a.support.touch){var e,b=a.ui.mouse.prototype,c=b._mouseInit,d=b._mouseDestroy;b._touchStart=function(a){var b=this;!e&&b._mouseCapture(a.originalEvent.changedTouches[0])&&(e=!0,b._touchMoved=!1,f(a,"mouseover"),f(a,"mousemove"),f(a,"mousedown"))},b._touchMove=function(a){e&&(this._touchMoved=!0,f(a,"mousemove"))},b._touchEnd=function(a){e&&(f(a,"mouseup"),f(a,"mouseout"),this._touchMoved||f(a,"click"),e=!1)},b._mouseInit=function(){var b=this;b.element.bind({touchstart:a.proxy(b,"_touchStart"),touchmove:a.proxy(b,"_touchMove"),touchend:a.proxy(b,"_touchEnd")}),c.call(b)},b._mouseDestroy=function(){var b=this;b.element.unbind({touchstart:a.proxy(b,"_touchStart"),touchmove:a.proxy(b,"_touchMove"),touchend:a.proxy(b,"_touchEnd")}),d.call(b)}}}(jQuery);/*! SmartMenus jQuery Plugin - v1.1.0 - September 17, 2017 + * http://www.smartmenus.org/ + * Copyright Vasil Dinkov, Vadikom Web Ltd. http://vadikom.com; Licensed MIT */(function(t){"function"==typeof define&&define.amd?define(["jquery"],t):"object"==typeof module&&"object"==typeof module.exports?module.exports=t(require("jquery")):t(jQuery)})(function($){function initMouseDetection(t){var e=".smartmenus_mouse";if(mouseDetectionEnabled||t)mouseDetectionEnabled&&t&&($(document).off(e),mouseDetectionEnabled=!1);else{var i=!0,s=null,o={mousemove:function(t){var e={x:t.pageX,y:t.pageY,timeStamp:(new Date).getTime()};if(s){var o=Math.abs(s.x-e.x),a=Math.abs(s.y-e.y);if((o>0||a>0)&&2>=o&&2>=a&&300>=e.timeStamp-s.timeStamp&&(mouse=!0,i)){var n=$(t.target).closest("a");n.is("a")&&$.each(menuTrees,function(){return $.contains(this.$root[0],n[0])?(this.itemEnter({currentTarget:n[0]}),!1):void 0}),i=!1}}s=e}};o[touchEvents?"touchstart":"pointerover pointermove pointerout MSPointerOver MSPointerMove MSPointerOut"]=function(t){isTouchEvent(t.originalEvent)&&(mouse=!1)},$(document).on(getEventsNS(o,e)),mouseDetectionEnabled=!0}}function isTouchEvent(t){return!/^(4|mouse)$/.test(t.pointerType)}function getEventsNS(t,e){e||(e="");var i={};for(var s in t)i[s.split(" ").join(e+" ")+e]=t[s];return i}var menuTrees=[],mouse=!1,touchEvents="ontouchstart"in window,mouseDetectionEnabled=!1,requestAnimationFrame=window.requestAnimationFrame||function(t){return setTimeout(t,1e3/60)},cancelAnimationFrame=window.cancelAnimationFrame||function(t){clearTimeout(t)},canAnimate=!!$.fn.animate;return $.SmartMenus=function(t,e){this.$root=$(t),this.opts=e,this.rootId="",this.accessIdPrefix="",this.$subArrow=null,this.activatedItems=[],this.visibleSubMenus=[],this.showTimeout=0,this.hideTimeout=0,this.scrollTimeout=0,this.clickActivated=!1,this.focusActivated=!1,this.zIndexInc=0,this.idInc=0,this.$firstLink=null,this.$firstSub=null,this.disabled=!1,this.$disableOverlay=null,this.$touchScrollingSub=null,this.cssTransforms3d="perspective"in t.style||"webkitPerspective"in t.style,this.wasCollapsible=!1,this.init()},$.extend($.SmartMenus,{hideAll:function(){$.each(menuTrees,function(){this.menuHideAll()})},destroy:function(){for(;menuTrees.length;)menuTrees[0].destroy();initMouseDetection(!0)},prototype:{init:function(t){var e=this;if(!t){menuTrees.push(this),this.rootId=((new Date).getTime()+Math.random()+"").replace(/\D/g,""),this.accessIdPrefix="sm-"+this.rootId+"-",this.$root.hasClass("sm-rtl")&&(this.opts.rightToLeftSubMenus=!0);var i=".smartmenus";this.$root.data("smartmenus",this).attr("data-smartmenus-id",this.rootId).dataSM("level",1).on(getEventsNS({"mouseover focusin":$.proxy(this.rootOver,this),"mouseout focusout":$.proxy(this.rootOut,this),keydown:$.proxy(this.rootKeyDown,this)},i)).on(getEventsNS({mouseenter:$.proxy(this.itemEnter,this),mouseleave:$.proxy(this.itemLeave,this),mousedown:$.proxy(this.itemDown,this),focus:$.proxy(this.itemFocus,this),blur:$.proxy(this.itemBlur,this),click:$.proxy(this.itemClick,this)},i),"a"),i+=this.rootId,this.opts.hideOnClick&&$(document).on(getEventsNS({touchstart:$.proxy(this.docTouchStart,this),touchmove:$.proxy(this.docTouchMove,this),touchend:$.proxy(this.docTouchEnd,this),click:$.proxy(this.docClick,this)},i)),$(window).on(getEventsNS({"resize orientationchange":$.proxy(this.winResize,this)},i)),this.opts.subIndicators&&(this.$subArrow=$("").addClass("sub-arrow"),this.opts.subIndicatorsText&&this.$subArrow.html(this.opts.subIndicatorsText)),initMouseDetection()}if(this.$firstSub=this.$root.find("ul").each(function(){e.menuInit($(this))}).eq(0),this.$firstLink=this.$root.find("a").eq(0),this.opts.markCurrentItem){var s=/(index|default)\.[^#\?\/]*/i,o=/#.*/,a=window.location.href.replace(s,""),n=a.replace(o,"");this.$root.find("a").each(function(){var t=this.href.replace(s,""),i=$(this);(t==a||t==n)&&(i.addClass("current"),e.opts.markCurrentTree&&i.parentsUntil("[data-smartmenus-id]","ul").each(function(){$(this).dataSM("parent-a").addClass("current")}))})}this.wasCollapsible=this.isCollapsible()},destroy:function(t){if(!t){var e=".smartmenus";this.$root.removeData("smartmenus").removeAttr("data-smartmenus-id").removeDataSM("level").off(e),e+=this.rootId,$(document).off(e),$(window).off(e),this.opts.subIndicators&&(this.$subArrow=null)}this.menuHideAll();var i=this;this.$root.find("ul").each(function(){var t=$(this);t.dataSM("scroll-arrows")&&t.dataSM("scroll-arrows").remove(),t.dataSM("shown-before")&&((i.opts.subMenusMinWidth||i.opts.subMenusMaxWidth)&&t.css({width:"",minWidth:"",maxWidth:""}).removeClass("sm-nowrap"),t.dataSM("scroll-arrows")&&t.dataSM("scroll-arrows").remove(),t.css({zIndex:"",top:"",left:"",marginLeft:"",marginTop:"",display:""})),0==(t.attr("id")||"").indexOf(i.accessIdPrefix)&&t.removeAttr("id")}).removeDataSM("in-mega").removeDataSM("shown-before").removeDataSM("scroll-arrows").removeDataSM("parent-a").removeDataSM("level").removeDataSM("beforefirstshowfired").removeAttr("role").removeAttr("aria-hidden").removeAttr("aria-labelledby").removeAttr("aria-expanded"),this.$root.find("a.has-submenu").each(function(){var t=$(this);0==t.attr("id").indexOf(i.accessIdPrefix)&&t.removeAttr("id")}).removeClass("has-submenu").removeDataSM("sub").removeAttr("aria-haspopup").removeAttr("aria-controls").removeAttr("aria-expanded").closest("li").removeDataSM("sub"),this.opts.subIndicators&&this.$root.find("span.sub-arrow").remove(),this.opts.markCurrentItem&&this.$root.find("a.current").removeClass("current"),t||(this.$root=null,this.$firstLink=null,this.$firstSub=null,this.$disableOverlay&&(this.$disableOverlay.remove(),this.$disableOverlay=null),menuTrees.splice($.inArray(this,menuTrees),1))},disable:function(t){if(!this.disabled){if(this.menuHideAll(),!t&&!this.opts.isPopup&&this.$root.is(":visible")){var e=this.$root.offset();this.$disableOverlay=$('
').css({position:"absolute",top:e.top,left:e.left,width:this.$root.outerWidth(),height:this.$root.outerHeight(),zIndex:this.getStartZIndex(!0),opacity:0}).appendTo(document.body)}this.disabled=!0}},docClick:function(t){return this.$touchScrollingSub?(this.$touchScrollingSub=null,void 0):((this.visibleSubMenus.length&&!$.contains(this.$root[0],t.target)||$(t.target).closest("a").length)&&this.menuHideAll(),void 0)},docTouchEnd:function(){if(this.lastTouch){if(!(!this.visibleSubMenus.length||void 0!==this.lastTouch.x2&&this.lastTouch.x1!=this.lastTouch.x2||void 0!==this.lastTouch.y2&&this.lastTouch.y1!=this.lastTouch.y2||this.lastTouch.target&&$.contains(this.$root[0],this.lastTouch.target))){this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0);var t=this;this.hideTimeout=setTimeout(function(){t.menuHideAll()},350)}this.lastTouch=null}},docTouchMove:function(t){if(this.lastTouch){var e=t.originalEvent.touches[0];this.lastTouch.x2=e.pageX,this.lastTouch.y2=e.pageY}},docTouchStart:function(t){var e=t.originalEvent.touches[0];this.lastTouch={x1:e.pageX,y1:e.pageY,target:e.target}},enable:function(){this.disabled&&(this.$disableOverlay&&(this.$disableOverlay.remove(),this.$disableOverlay=null),this.disabled=!1)},getClosestMenu:function(t){for(var e=$(t).closest("ul");e.dataSM("in-mega");)e=e.parent().closest("ul");return e[0]||null},getHeight:function(t){return this.getOffset(t,!0)},getOffset:function(t,e){var i;"none"==t.css("display")&&(i={position:t[0].style.position,visibility:t[0].style.visibility},t.css({position:"absolute",visibility:"hidden"}).show());var s=t[0].getBoundingClientRect&&t[0].getBoundingClientRect(),o=s&&(e?s.height||s.bottom-s.top:s.width||s.right-s.left);return o||0===o||(o=e?t[0].offsetHeight:t[0].offsetWidth),i&&t.hide().css(i),o},getStartZIndex:function(t){var e=parseInt(this[t?"$root":"$firstSub"].css("z-index"));return!t&&isNaN(e)&&(e=parseInt(this.$root.css("z-index"))),isNaN(e)?1:e},getTouchPoint:function(t){return t.touches&&t.touches[0]||t.changedTouches&&t.changedTouches[0]||t},getViewport:function(t){var e=t?"Height":"Width",i=document.documentElement["client"+e],s=window["inner"+e];return s&&(i=Math.min(i,s)),i},getViewportHeight:function(){return this.getViewport(!0)},getViewportWidth:function(){return this.getViewport()},getWidth:function(t){return this.getOffset(t)},handleEvents:function(){return!this.disabled&&this.isCSSOn()},handleItemEvents:function(t){return this.handleEvents()&&!this.isLinkInMegaMenu(t)},isCollapsible:function(){return"static"==this.$firstSub.css("position")},isCSSOn:function(){return"inline"!=this.$firstLink.css("display")},isFixed:function(){var t="fixed"==this.$root.css("position");return t||this.$root.parentsUntil("body").each(function(){return"fixed"==$(this).css("position")?(t=!0,!1):void 0}),t},isLinkInMegaMenu:function(t){return $(this.getClosestMenu(t[0])).hasClass("mega-menu")},isTouchMode:function(){return!mouse||this.opts.noMouseOver||this.isCollapsible()},itemActivate:function(t,e){var i=t.closest("ul"),s=i.dataSM("level");if(s>1&&(!this.activatedItems[s-2]||this.activatedItems[s-2][0]!=i.dataSM("parent-a")[0])){var o=this;$(i.parentsUntil("[data-smartmenus-id]","ul").get().reverse()).add(i).each(function(){o.itemActivate($(this).dataSM("parent-a"))})}if((!this.isCollapsible()||e)&&this.menuHideSubMenus(this.activatedItems[s-1]&&this.activatedItems[s-1][0]==t[0]?s:s-1),this.activatedItems[s-1]=t,this.$root.triggerHandler("activate.smapi",t[0])!==!1){var a=t.dataSM("sub");a&&(this.isTouchMode()||!this.opts.showOnClick||this.clickActivated)&&this.menuShow(a)}},itemBlur:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&this.$root.triggerHandler("blur.smapi",e[0])},itemClick:function(t){var e=$(t.currentTarget);if(this.handleItemEvents(e)){if(this.$touchScrollingSub&&this.$touchScrollingSub[0]==e.closest("ul")[0])return this.$touchScrollingSub=null,t.stopPropagation(),!1;if(this.$root.triggerHandler("click.smapi",e[0])===!1)return!1;var i=$(t.target).is(".sub-arrow"),s=e.dataSM("sub"),o=s?2==s.dataSM("level"):!1,a=this.isCollapsible(),n=/toggle$/.test(this.opts.collapsibleBehavior),r=/link$/.test(this.opts.collapsibleBehavior),h=/^accordion/.test(this.opts.collapsibleBehavior);if(s&&!s.is(":visible")){if((!r||!a||i)&&(this.opts.showOnClick&&o&&(this.clickActivated=!0),this.itemActivate(e,h),s.is(":visible")))return this.focusActivated=!0,!1}else if(a&&(n||i))return this.itemActivate(e,h),this.menuHide(s),n&&(this.focusActivated=!1),!1;return this.opts.showOnClick&&o||e.hasClass("disabled")||this.$root.triggerHandler("select.smapi",e[0])===!1?!1:void 0}},itemDown:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&e.dataSM("mousedown",!0)},itemEnter:function(t){var e=$(t.currentTarget);if(this.handleItemEvents(e)){if(!this.isTouchMode()){this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0);var i=this;this.showTimeout=setTimeout(function(){i.itemActivate(e)},this.opts.showOnClick&&1==e.closest("ul").dataSM("level")?1:this.opts.showTimeout)}this.$root.triggerHandler("mouseenter.smapi",e[0])}},itemFocus:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&(!this.focusActivated||this.isTouchMode()&&e.dataSM("mousedown")||this.activatedItems.length&&this.activatedItems[this.activatedItems.length-1][0]==e[0]||this.itemActivate(e,!0),this.$root.triggerHandler("focus.smapi",e[0]))},itemLeave:function(t){var e=$(t.currentTarget);this.handleItemEvents(e)&&(this.isTouchMode()||(e[0].blur(),this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0)),e.removeDataSM("mousedown"),this.$root.triggerHandler("mouseleave.smapi",e[0]))},menuHide:function(t){if(this.$root.triggerHandler("beforehide.smapi",t[0])!==!1&&(canAnimate&&t.stop(!0,!0),"none"!=t.css("display"))){var e=function(){t.css("z-index","")};this.isCollapsible()?canAnimate&&this.opts.collapsibleHideFunction?this.opts.collapsibleHideFunction.call(this,t,e):t.hide(this.opts.collapsibleHideDuration,e):canAnimate&&this.opts.hideFunction?this.opts.hideFunction.call(this,t,e):t.hide(this.opts.hideDuration,e),t.dataSM("scroll")&&(this.menuScrollStop(t),t.css({"touch-action":"","-ms-touch-action":"","-webkit-transform":"",transform:""}).off(".smartmenus_scroll").removeDataSM("scroll").dataSM("scroll-arrows").hide()),t.dataSM("parent-a").removeClass("highlighted").attr("aria-expanded","false"),t.attr({"aria-expanded":"false","aria-hidden":"true"});var i=t.dataSM("level");this.activatedItems.splice(i-1,1),this.visibleSubMenus.splice($.inArray(t,this.visibleSubMenus),1),this.$root.triggerHandler("hide.smapi",t[0])}},menuHideAll:function(){this.showTimeout&&(clearTimeout(this.showTimeout),this.showTimeout=0);for(var t=this.opts.isPopup?1:0,e=this.visibleSubMenus.length-1;e>=t;e--)this.menuHide(this.visibleSubMenus[e]);this.opts.isPopup&&(canAnimate&&this.$root.stop(!0,!0),this.$root.is(":visible")&&(canAnimate&&this.opts.hideFunction?this.opts.hideFunction.call(this,this.$root):this.$root.hide(this.opts.hideDuration))),this.activatedItems=[],this.visibleSubMenus=[],this.clickActivated=!1,this.focusActivated=!1,this.zIndexInc=0,this.$root.triggerHandler("hideAll.smapi")},menuHideSubMenus:function(t){for(var e=this.activatedItems.length-1;e>=t;e--){var i=this.activatedItems[e].dataSM("sub");i&&this.menuHide(i)}},menuInit:function(t){if(!t.dataSM("in-mega")){t.hasClass("mega-menu")&&t.find("ul").dataSM("in-mega",!0);for(var e=2,i=t[0];(i=i.parentNode.parentNode)!=this.$root[0];)e++;var s=t.prevAll("a").eq(-1);s.length||(s=t.prevAll().find("a").eq(-1)),s.addClass("has-submenu").dataSM("sub",t),t.dataSM("parent-a",s).dataSM("level",e).parent().dataSM("sub",t);var o=s.attr("id")||this.accessIdPrefix+ ++this.idInc,a=t.attr("id")||this.accessIdPrefix+ ++this.idInc;s.attr({id:o,"aria-haspopup":"true","aria-controls":a,"aria-expanded":"false"}),t.attr({id:a,role:"group","aria-hidden":"true","aria-labelledby":o,"aria-expanded":"false"}),this.opts.subIndicators&&s[this.opts.subIndicatorsPos](this.$subArrow.clone())}},menuPosition:function(t){var e,i,s=t.dataSM("parent-a"),o=s.closest("li"),a=o.parent(),n=t.dataSM("level"),r=this.getWidth(t),h=this.getHeight(t),u=s.offset(),l=u.left,c=u.top,d=this.getWidth(s),m=this.getHeight(s),p=$(window),f=p.scrollLeft(),v=p.scrollTop(),b=this.getViewportWidth(),S=this.getViewportHeight(),g=a.parent().is("[data-sm-horizontal-sub]")||2==n&&!a.hasClass("sm-vertical"),M=this.opts.rightToLeftSubMenus&&!o.is("[data-sm-reverse]")||!this.opts.rightToLeftSubMenus&&o.is("[data-sm-reverse]"),w=2==n?this.opts.mainMenuSubOffsetX:this.opts.subMenusSubOffsetX,T=2==n?this.opts.mainMenuSubOffsetY:this.opts.subMenusSubOffsetY;if(g?(e=M?d-r-w:w,i=this.opts.bottomToTopSubMenus?-h-T:m+T):(e=M?w-r:d-w,i=this.opts.bottomToTopSubMenus?m-T-h:T),this.opts.keepInViewport){var y=l+e,I=c+i;if(M&&f>y?e=g?f-y+e:d-w:!M&&y+r>f+b&&(e=g?f+b-r-y+e:w-r),g||(S>h&&I+h>v+S?i+=v+S-h-I:(h>=S||v>I)&&(i+=v-I)),g&&(I+h>v+S+.49||v>I)||!g&&h>S+.49){var x=this;t.dataSM("scroll-arrows")||t.dataSM("scroll-arrows",$([$('')[0],$('')[0]]).on({mouseenter:function(){t.dataSM("scroll").up=$(this).hasClass("scroll-up"),x.menuScroll(t)},mouseleave:function(e){x.menuScrollStop(t),x.menuScrollOut(t,e)},"mousewheel DOMMouseScroll":function(t){t.preventDefault()}}).insertAfter(t));var A=".smartmenus_scroll";if(t.dataSM("scroll",{y:this.cssTransforms3d?0:i-m,step:1,itemH:m,subH:h,arrowDownH:this.getHeight(t.dataSM("scroll-arrows").eq(1))}).on(getEventsNS({mouseover:function(e){x.menuScrollOver(t,e)},mouseout:function(e){x.menuScrollOut(t,e)},"mousewheel DOMMouseScroll":function(e){x.menuScrollMousewheel(t,e)}},A)).dataSM("scroll-arrows").css({top:"auto",left:"0",marginLeft:e+(parseInt(t.css("border-left-width"))||0),width:r-(parseInt(t.css("border-left-width"))||0)-(parseInt(t.css("border-right-width"))||0),zIndex:t.css("z-index")}).eq(g&&this.opts.bottomToTopSubMenus?0:1).show(),this.isFixed()){var C={};C[touchEvents?"touchstart touchmove touchend":"pointerdown pointermove pointerup MSPointerDown MSPointerMove MSPointerUp"]=function(e){x.menuScrollTouch(t,e)},t.css({"touch-action":"none","-ms-touch-action":"none"}).on(getEventsNS(C,A))}}}t.css({top:"auto",left:"0",marginLeft:e,marginTop:i-m})},menuScroll:function(t,e,i){var s,o=t.dataSM("scroll"),a=t.dataSM("scroll-arrows"),n=o.up?o.upEnd:o.downEnd;if(!e&&o.momentum){if(o.momentum*=.92,s=o.momentum,.5>s)return this.menuScrollStop(t),void 0}else s=i||(e||!this.opts.scrollAccelerate?this.opts.scrollStep:Math.floor(o.step));var r=t.dataSM("level");if(this.activatedItems[r-1]&&this.activatedItems[r-1].dataSM("sub")&&this.activatedItems[r-1].dataSM("sub").is(":visible")&&this.menuHideSubMenus(r-1),o.y=o.up&&o.y>=n||!o.up&&n>=o.y?o.y:Math.abs(n-o.y)>s?o.y+(o.up?s:-s):n,t.css(this.cssTransforms3d?{"-webkit-transform":"translate3d(0, "+o.y+"px, 0)",transform:"translate3d(0, "+o.y+"px, 0)"}:{marginTop:o.y}),mouse&&(o.up&&o.y>o.downEnd||!o.up&&o.y0;t.dataSM("scroll-arrows").eq(i?0:1).is(":visible")&&(t.dataSM("scroll").up=i,this.menuScroll(t,!0))}e.preventDefault()},menuScrollOut:function(t,e){mouse&&(/^scroll-(up|down)/.test((e.relatedTarget||"").className)||(t[0]==e.relatedTarget||$.contains(t[0],e.relatedTarget))&&this.getClosestMenu(e.relatedTarget)==t[0]||t.dataSM("scroll-arrows").css("visibility","hidden"))},menuScrollOver:function(t,e){if(mouse&&!/^scroll-(up|down)/.test(e.target.className)&&this.getClosestMenu(e.target)==t[0]){this.menuScrollRefreshData(t);var i=t.dataSM("scroll"),s=$(window).scrollTop()-t.dataSM("parent-a").offset().top-i.itemH;t.dataSM("scroll-arrows").eq(0).css("margin-top",s).end().eq(1).css("margin-top",s+this.getViewportHeight()-i.arrowDownH).end().css("visibility","visible")}},menuScrollRefreshData:function(t){var e=t.dataSM("scroll"),i=$(window).scrollTop()-t.dataSM("parent-a").offset().top-e.itemH;this.cssTransforms3d&&(i=-(parseFloat(t.css("margin-top"))-i)),$.extend(e,{upEnd:i,downEnd:i+this.getViewportHeight()-e.subH})},menuScrollStop:function(t){return this.scrollTimeout?(cancelAnimationFrame(this.scrollTimeout),this.scrollTimeout=0,t.dataSM("scroll").step=1,!0):void 0},menuScrollTouch:function(t,e){if(e=e.originalEvent,isTouchEvent(e)){var i=this.getTouchPoint(e);if(this.getClosestMenu(i.target)==t[0]){var s=t.dataSM("scroll");if(/(start|down)$/i.test(e.type))this.menuScrollStop(t)?(e.preventDefault(),this.$touchScrollingSub=t):this.$touchScrollingSub=null,this.menuScrollRefreshData(t),$.extend(s,{touchStartY:i.pageY,touchStartTime:e.timeStamp});else if(/move$/i.test(e.type)){var o=void 0!==s.touchY?s.touchY:s.touchStartY;if(void 0!==o&&o!=i.pageY){this.$touchScrollingSub=t;var a=i.pageY>o;void 0!==s.up&&s.up!=a&&$.extend(s,{touchStartY:i.pageY,touchStartTime:e.timeStamp}),$.extend(s,{up:a,touchY:i.pageY}),this.menuScroll(t,!0,Math.abs(i.pageY-o))}e.preventDefault()}else void 0!==s.touchY&&((s.momentum=15*Math.pow(Math.abs(i.pageY-s.touchStartY)/(e.timeStamp-s.touchStartTime),2))&&(this.menuScrollStop(t),this.menuScroll(t),e.preventDefault()),delete s.touchY)}}},menuShow:function(t){if((t.dataSM("beforefirstshowfired")||(t.dataSM("beforefirstshowfired",!0),this.$root.triggerHandler("beforefirstshow.smapi",t[0])!==!1))&&this.$root.triggerHandler("beforeshow.smapi",t[0])!==!1&&(t.dataSM("shown-before",!0),canAnimate&&t.stop(!0,!0),!t.is(":visible"))){var e=t.dataSM("parent-a"),i=this.isCollapsible();if((this.opts.keepHighlighted||i)&&e.addClass("highlighted"),i)t.removeClass("sm-nowrap").css({zIndex:"",width:"auto",minWidth:"",maxWidth:"",top:"",left:"",marginLeft:"",marginTop:""});else{if(t.css("z-index",this.zIndexInc=(this.zIndexInc||this.getStartZIndex())+1),(this.opts.subMenusMinWidth||this.opts.subMenusMaxWidth)&&(t.css({width:"auto",minWidth:"",maxWidth:""}).addClass("sm-nowrap"),this.opts.subMenusMinWidth&&t.css("min-width",this.opts.subMenusMinWidth),this.opts.subMenusMaxWidth)){var s=this.getWidth(t);t.css("max-width",this.opts.subMenusMaxWidth),s>this.getWidth(t)&&t.removeClass("sm-nowrap").css("width",this.opts.subMenusMaxWidth)}this.menuPosition(t)}var o=function(){t.css("overflow","")};i?canAnimate&&this.opts.collapsibleShowFunction?this.opts.collapsibleShowFunction.call(this,t,o):t.show(this.opts.collapsibleShowDuration,o):canAnimate&&this.opts.showFunction?this.opts.showFunction.call(this,t,o):t.show(this.opts.showDuration,o),e.attr("aria-expanded","true"),t.attr({"aria-expanded":"true","aria-hidden":"false"}),this.visibleSubMenus.push(t),this.$root.triggerHandler("show.smapi",t[0])}},popupHide:function(t){this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0);var e=this;this.hideTimeout=setTimeout(function(){e.menuHideAll()},t?1:this.opts.hideTimeout)},popupShow:function(t,e){if(!this.opts.isPopup)return alert('SmartMenus jQuery Error:\n\nIf you want to show this menu via the "popupShow" method, set the isPopup:true option.'),void 0;if(this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0),this.$root.dataSM("shown-before",!0),canAnimate&&this.$root.stop(!0,!0),!this.$root.is(":visible")){this.$root.css({left:t,top:e});var i=this,s=function(){i.$root.css("overflow","")};canAnimate&&this.opts.showFunction?this.opts.showFunction.call(this,this.$root,s):this.$root.show(this.opts.showDuration,s),this.visibleSubMenus[0]=this.$root}},refresh:function(){this.destroy(!0),this.init(!0)},rootKeyDown:function(t){if(this.handleEvents())switch(t.keyCode){case 27:var e=this.activatedItems[0];if(e){this.menuHideAll(),e[0].focus();var i=e.dataSM("sub");i&&this.menuHide(i)}break;case 32:var s=$(t.target);if(s.is("a")&&this.handleItemEvents(s)){var i=s.dataSM("sub");i&&!i.is(":visible")&&(this.itemClick({currentTarget:t.target}),t.preventDefault())}}},rootOut:function(t){if(this.handleEvents()&&!this.isTouchMode()&&t.target!=this.$root[0]&&(this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0),!this.opts.showOnClick||!this.opts.hideOnClick)){var e=this;this.hideTimeout=setTimeout(function(){e.menuHideAll()},this.opts.hideTimeout)}},rootOver:function(t){this.handleEvents()&&!this.isTouchMode()&&t.target!=this.$root[0]&&this.hideTimeout&&(clearTimeout(this.hideTimeout),this.hideTimeout=0)},winResize:function(t){if(this.handleEvents()){if(!("onorientationchange"in window)||"orientationchange"==t.type){var e=this.isCollapsible();this.wasCollapsible&&e||(this.activatedItems.length&&this.activatedItems[this.activatedItems.length-1][0].blur(),this.menuHideAll()),this.wasCollapsible=e}}else if(this.$disableOverlay){var i=this.$root.offset();this.$disableOverlay.css({top:i.top,left:i.left,width:this.$root.outerWidth(),height:this.$root.outerHeight()})}}}}),$.fn.dataSM=function(t,e){return e?this.data(t+"_smartmenus",e):this.data(t+"_smartmenus")},$.fn.removeDataSM=function(t){return this.removeData(t+"_smartmenus")},$.fn.smartmenus=function(options){if("string"==typeof options){var args=arguments,method=options;return Array.prototype.shift.call(args),this.each(function(){var t=$(this).data("smartmenus");t&&t[method]&&t[method].apply(t,args)})}return this.each(function(){var dataOpts=$(this).data("sm-options")||null;if(dataOpts)try{dataOpts=eval("("+dataOpts+")")}catch(e){dataOpts=null,alert('ERROR\n\nSmartMenus jQuery init:\nInvalid "data-sm-options" attribute value syntax.')}new $.SmartMenus(this,$.extend({},$.fn.smartmenus.defaults,options,dataOpts))})},$.fn.smartmenus.defaults={isPopup:!1,mainMenuSubOffsetX:0,mainMenuSubOffsetY:0,subMenusSubOffsetX:0,subMenusSubOffsetY:0,subMenusMinWidth:"10em",subMenusMaxWidth:"20em",subIndicators:!0,subIndicatorsPos:"append",subIndicatorsText:"",scrollStep:30,scrollAccelerate:!0,showTimeout:250,hideTimeout:500,showDuration:0,showFunction:null,hideDuration:0,hideFunction:function(t,e){t.fadeOut(200,e)},collapsibleShowDuration:0,collapsibleShowFunction:function(t,e){t.slideDown(200,e)},collapsibleHideDuration:0,collapsibleHideFunction:function(t,e){t.slideUp(200,e)},showOnClick:!1,hideOnClick:!0,noMouseOver:!1,keepInViewport:!0,keepHighlighted:!0,markCurrentItem:!1,markCurrentTree:!0,rightToLeftSubMenus:!1,bottomToTopSubMenus:!1,collapsibleBehavior:"default"},$}); \ No newline at end of file diff --git a/documentation/html/md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e.html b/documentation/html/md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e.html new file mode 100644 index 0000000..7d8223f --- /dev/null +++ b/documentation/html/md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e.html @@ -0,0 +1,206 @@ + + + + + + + +esp32_BNO08x: README + + + + + + + + + +
+
+ + + + + + +
+
esp32_BNO08x 1.00 +
+
C++ BNO08x IMU driver component for esp-idf.
+
+
+ + + + + + + + +
+
+ + +
+
+
+
+
+
Loading...
+
Searching...
+
No Matches
+
+
+
+
+ +
+
+
README
+
+
+

Table of Contents.

+

image

+
    +
  1. +About
  2. +
  3. +Getting Started +
  4. +
  5. +Example
  6. +
  7. +Documentation
  8. +
  9. +Acknowledgements
  10. +
  11. +License
  12. +
  13. +Contact
  14. +
+

+About

+

esp32_BNO08x is a C++ component written for esp-idf version 5.1 to serve as a driver for the BNO085 or BNO080 IMU.
+ This library is heavy influenced by the SparkFun BNO080 Arduino Library, it is more or less a port. It supports access to all the same data that the BNO08x provides.
+ Currently, only SPI is supported, there is no plans to support I2C (esp32 has I2C driver silicone bug, leading to unpredictable behavior).
+ I may implement UART at some point in the future.

+

+Getting Started

+

(back to top)

+

+Wiring

+

The default wiring is depicted below, it can be changed at driver initialization (see example section). image

+

(back to top)

+

+Adding to Project

+
    +
  1. Create a "components" directory in the root workspace directory of your esp-idf project if it does not exist already.
    +

    +

    In workspace directory:
    +

    mkdir components
    +
  2. +
  3. Cd into the components directory and clone the esp32_BNO08x repo.

    +
    cd components
    +
    git clone https://github.com/myles-parfeniuk/esp32_BNO08x.git
    +

    (back to top)

    +
  4. +
+

+Example

+
#include <stdio.h>
+
#include "BNO08x.hpp"
+
+
extern "C" void app_main(void)
+
{
+
BNO08x imu; //create IMU object with default wiring scheme
+
+
/*
+
//if a custom wiring scheme is desired:
+
//create config struct
+
bno08x_config_t imu_config;
+
imu_config.io_mos = GPIO_NUM_X;
+
imu_config.io_miso = GPIO_NUM_X;
+
//etc...
+
+
BNO08x imu(imu_config);
+
*/
+
+
imu.initialize(); //initialize IMU
+
+
//enable gyro & game rotation vector
+ +
imu.enable_gyro(150);
+
+
while(1)
+
{
+
//print absolute heading in degrees and angular velocity in Rad/s
+
if(imu.data_available())
+
{
+
ESP_LOGW("Main", "Velocity: x: %.3f y: %.3f z: %.3f", imu.get_gyro_calibrated_velocity_X(), imu.get_gyro_calibrated_velocity_Y(), imu.get_gyro_calibrated_velocity_Z());
+
ESP_LOGI("Main", "Euler Angle: pitch: %.3f roll: %.3f yaw: %.3f", imu.get_pitch_deg(), imu.get_roll_deg(), imu.get_yaw_deg());
+
}
+
}
+
+
}
+
Definition BNO08x.hpp:74
+
float get_gyro_calibrated_velocity_Z()
Get calibrated gyro z axis angular velocity measurement.
Definition BNO08x.cpp:1862
+
bool data_available()
Checks if BNO08x has asserted interrupt and sent data.
Definition BNO08x.cpp:725
+
void enable_game_rotation_vector(uint16_t time_between_reports)
Sends command to enable game rotation vector reports (See Ref. Manual 6.5.19)
Definition BNO08x.cpp:996
+
float get_roll_deg()
Get the reported rotation about x axis.
Definition BNO08x.cpp:1500
+
void enable_gyro(uint16_t time_between_reports)
Sends command to enable gyro reports (See Ref. Manual 6.5.13)
Definition BNO08x.cpp:1100
+
float get_gyro_calibrated_velocity_X()
Get calibrated gyro x axis angular velocity measurement.
Definition BNO08x.cpp:1842
+
float get_gyro_calibrated_velocity_Y()
Get calibrated gyro y axis angular velocity measurement.
Definition BNO08x.cpp:1852
+
bool initialize()
Initializes BNO08x sensor.
Definition BNO08x.cpp:114
+
float get_pitch_deg()
Get the reported rotation about y axis.
Definition BNO08x.cpp:1510
+
float get_yaw_deg()
Get the reported rotation about z axis.
Definition BNO08x.cpp:1520
+

(back to top)

+

+Documentation

+

API documentation generated with doxygen can be found in the documentation directory of the master branch.
+

+

(back to top)

+

+Acknowledgements

+

Special thanks to the original creators of the sparkfun BNO080 library. Developing this without a reference would have been much more time consuming.
+ https://github.com/sparkfun/SparkFun_BNO080_Arduino_Library
+

+

Special thanks to Anton Babiy, aka hwBirdy007 for helping with debugging SPI.
+ https://github.com/hwBirdy007
+

+

(back to top)

+

+License

+

Distributed under the MIT License. See LICENSE.md for more information.

+

(back to top)

+

+Contact

+

Myles Parfeniuk - myles.nosp@m..par.nosp@m.fenyu.nosp@m.k@gm.nosp@m.ail.c.nosp@m.om

+

Project Link: https://github.com/myles-parfeniuk/esp32_BNO08x.git

+

(back to top)

+
+
+ + + + diff --git a/documentation/html/menu.js b/documentation/html/menu.js new file mode 100644 index 0000000..b0b2693 --- /dev/null +++ b/documentation/html/menu.js @@ -0,0 +1,136 @@ +/* + @licstart The following is the entire license notice for the JavaScript code in this file. + + The MIT License (MIT) + + Copyright (C) 1997-2020 by Dimitri van Heesch + + Permission is hereby granted, free of charge, to any person obtaining a copy of this software + and associated documentation files (the "Software"), to deal in the Software without restriction, + including without limitation the rights to use, copy, modify, merge, publish, distribute, + sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all copies or + substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING + BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, + DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + @licend The above is the entire license notice for the JavaScript code in this file + */ +function initMenu(relPath,searchEnabled,serverSide,searchPage,search) { + function makeTree(data,relPath) { + var result=''; + if ('children' in data) { + result+='
    '; + for (var i in data.children) { + var url; + var link; + link = data.children[i].url; + if (link.substring(0,1)=='^') { + url = link.substring(1); + } else { + url = relPath+link; + } + result+='
  • '+ + data.children[i].text+''+ + makeTree(data.children[i],relPath)+'
  • '; + } + result+='
'; + } + return result; + } + var searchBoxHtml; + if (searchEnabled) { + if (serverSide) { + searchBoxHtml='
'+ + '
'+ + '
 '+ + ''+ + '
'+ + '
'+ + '
'+ + '
'; + } else { + searchBoxHtml='
'+ + ''+ + ' '+ + ''+ + ''+ + ''+ + ''+ + ''+ + '
'; + } + } + + $('#main-nav').before('
'+ + ''+ + ''+ + '
'); + $('#main-nav').append(makeTree(menudata,relPath)); + $('#main-nav').children(':first').addClass('sm sm-dox').attr('id','main-menu'); + if (searchBoxHtml) { + $('#main-menu').append('
  • '); + } + var $mainMenuState = $('#main-menu-state'); + var prevWidth = 0; + if ($mainMenuState.length) { + function initResizableIfExists() { + if (typeof initResizable==='function') initResizable(); + } + // animate mobile menu + $mainMenuState.change(function(e) { + var $menu = $('#main-menu'); + var options = { duration: 250, step: initResizableIfExists }; + if (this.checked) { + options['complete'] = function() { $menu.css('display', 'block') }; + $menu.hide().slideDown(options); + } else { + options['complete'] = function() { $menu.css('display', 'none') }; + $menu.show().slideUp(options); + } + }); + // set default menu visibility + function resetState() { + var $menu = $('#main-menu'); + var $mainMenuState = $('#main-menu-state'); + var newWidth = $(window).outerWidth(); + if (newWidth!=prevWidth) { + if ($(window).outerWidth()<768) { + $mainMenuState.prop('checked',false); $menu.hide(); + $('#searchBoxPos1').html(searchBoxHtml); + $('#searchBoxPos2').hide(); + } else { + $menu.show(); + $('#searchBoxPos1').empty(); + $('#searchBoxPos2').html(searchBoxHtml); + $('#searchBoxPos2').show(); + } + if (typeof searchBox!=='undefined') { + searchBox.CloseResultsWindow(); + } + prevWidth = newWidth; + } + } + $(window).ready(function() { resetState(); initResizableIfExists(); }); + $(window).resize(resetState); + } + $('#main-menu').smartmenus(); +} +/* @license-end */ diff --git a/documentation/html/menudata.js b/documentation/html/menudata.js new file mode 100644 index 0000000..56a01cb --- /dev/null +++ b/documentation/html/menudata.js @@ -0,0 +1,84 @@ +/* + @licstart The following is the entire license notice for the JavaScript code in this file. + + The MIT License (MIT) + + Copyright (C) 1997-2020 by Dimitri van Heesch + + Permission is hereby granted, free of charge, to any person obtaining a copy of this software + and associated documentation files (the "Software"), to deal in the Software without restriction, + including without limitation the rights to use, copy, modify, merge, publish, distribute, + sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all copies or + substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING + BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, + DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + @licend The above is the entire license notice for the JavaScript code in this file +*/ +var menudata={children:[ +{text:"Main Page",url:"index.html"}, +{text:"Related Pages",url:"pages.html"}, +{text:"Classes",url:"annotated.html",children:[ +{text:"Class List",url:"annotated.html"}, +{text:"Class Index",url:"classes.html"}, +{text:"Class Members",url:"functions.html",children:[ +{text:"All",url:"functions.html",children:[ +{text:"a",url:"functions.html#index_a"}, +{text:"b",url:"functions_b.html#index_b"}, +{text:"c",url:"functions_c.html#index_c"}, +{text:"d",url:"functions_d.html#index_d"}, +{text:"e",url:"functions_e.html#index_e"}, +{text:"f",url:"functions_f.html#index_f"}, +{text:"g",url:"functions_g.html#index_g"}, +{text:"h",url:"functions_h.html#index_h"}, +{text:"i",url:"functions_i.html#index_i"}, +{text:"l",url:"functions_l.html#index_l"}, +{text:"m",url:"functions_m.html#index_m"}, +{text:"p",url:"functions_p.html#index_p"}, +{text:"q",url:"functions_q.html#index_q"}, +{text:"r",url:"functions_r.html#index_r"}, +{text:"s",url:"functions_s.html#index_s"}, +{text:"t",url:"functions_t.html#index_t"}, +{text:"u",url:"functions_u.html#index_u"}, +{text:"w",url:"functions_w.html#index_w"}]}, +{text:"Functions",url:"functions_func.html",children:[ +{text:"b",url:"functions_func.html#index_b"}, +{text:"c",url:"functions_func.html#index_c"}, +{text:"d",url:"functions_func.html#index_d"}, +{text:"e",url:"functions_func.html#index_e"}, +{text:"f",url:"functions_func.html#index_f"}, +{text:"g",url:"functions_func.html#index_g"}, +{text:"h",url:"functions_func.html#index_h"}, +{text:"i",url:"functions_func.html#index_i"}, +{text:"m",url:"functions_func.html#index_m"}, +{text:"p",url:"functions_func.html#index_p"}, +{text:"q",url:"functions_func.html#index_q"}, +{text:"r",url:"functions_func.html#index_r"}, +{text:"s",url:"functions_func.html#index_s"}, +{text:"t",url:"functions_func.html#index_t"}, +{text:"w",url:"functions_func.html#index_w"}]}, +{text:"Variables",url:"functions_vars.html",children:[ +{text:"a",url:"functions_vars.html#index_a"}, +{text:"b",url:"functions_vars.html#index_b"}, +{text:"c",url:"functions_vars.html#index_c"}, +{text:"d",url:"functions_vars.html#index_d"}, +{text:"g",url:"functions_vars.html#index_g"}, +{text:"h",url:"functions_vars.html#index_h"}, +{text:"i",url:"functions_vars.html#index_i"}, +{text:"l",url:"functions_vars.html#index_l"}, +{text:"m",url:"functions_vars.html#index_m"}, +{text:"p",url:"functions_vars.html#index_p"}, +{text:"q",url:"functions_vars.html#index_q"}, +{text:"r",url:"functions_vars.html#index_r"}, +{text:"s",url:"functions_vars.html#index_s"}, +{text:"t",url:"functions_vars.html#index_t"}, +{text:"u",url:"functions_vars.html#index_u"}]}]}]}, +{text:"Files",url:"files.html",children:[ +{text:"File List",url:"files.html"}]}]} diff --git a/documentation/html/nav_f.png b/documentation/html/nav_f.png new file mode 100644 index 0000000..72a58a5 Binary files /dev/null and b/documentation/html/nav_f.png differ diff --git a/documentation/html/nav_fd.png b/documentation/html/nav_fd.png new file mode 100644 index 0000000..032fbdd Binary files /dev/null and b/documentation/html/nav_fd.png differ diff --git a/documentation/html/nav_g.png b/documentation/html/nav_g.png new file mode 100644 index 0000000..2093a23 Binary files /dev/null and b/documentation/html/nav_g.png differ diff --git a/documentation/html/nav_h.png b/documentation/html/nav_h.png new file mode 100644 index 0000000..33389b1 Binary files /dev/null and b/documentation/html/nav_h.png differ diff --git a/documentation/html/nav_hd.png b/documentation/html/nav_hd.png new file mode 100644 index 0000000..de80f18 Binary files /dev/null and b/documentation/html/nav_hd.png differ diff --git a/documentation/html/open.png b/documentation/html/open.png new file mode 100644 index 0000000..30f75c7 Binary files /dev/null and b/documentation/html/open.png differ diff --git a/documentation/html/pages.html b/documentation/html/pages.html new file mode 100644 index 0000000..d38ee3e --- /dev/null +++ b/documentation/html/pages.html @@ -0,0 +1,87 @@ + + + + + + + +esp32_BNO08x: Related Pages + + + + + + + + + +
    +
    + + + + + + +
    +
    esp32_BNO08x 1.00 +
    +
    C++ BNO08x IMU driver component for esp-idf.
    +
    +
    + + + + + + + +
    + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    Related Pages
    +
    +
    +
    Here is a list of all related documentation pages:
    + + +
     READMETable of Contents
    +
    +
    + + + + diff --git a/documentation/html/search/all_0.js b/documentation/html/search/all_0.js new file mode 100644 index 0000000..9755124 --- /dev/null +++ b/documentation/html/search/all_0.js @@ -0,0 +1,9 @@ +var searchData= +[ + ['accel_5faccuracy_0',['accel_accuracy',['../class_b_n_o08x.html#a3365b7ebde01e284274e655c60343df9',1,'BNO08x']]], + ['accel_5flin_5faccuracy_1',['accel_lin_accuracy',['../class_b_n_o08x.html#a35e1635ef5edde8fc8640f978c6f2e3c',1,'BNO08x']]], + ['accelerometer_5fq1_2',['ACCELEROMETER_Q1',['../class_b_n_o08x.html#a0564aaf5b20dc42b54db4fb3115ac1c7',1,'BNO08x']]], + ['activity_5fclassifier_3',['activity_classifier',['../class_b_n_o08x.html#a75cea49c1c08ca28d9fa7e5ed61c6e7b',1,'BNO08x']]], + ['activity_5fconfidences_4',['activity_confidences',['../class_b_n_o08x.html#af96e8cd070459f945ffbf01b98106e13',1,'BNO08x']]], + ['angular_5fvelocity_5fq1_5',['ANGULAR_VELOCITY_Q1',['../class_b_n_o08x.html#aafe117561fe9138800073a04a778b4ce',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_1.js b/documentation/html/search/all_1.js new file mode 100644 index 0000000..a96600a --- /dev/null +++ b/documentation/html/search/all_1.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['bno08x_0',['BNO08x',['../class_b_n_o08x.html',1,'BNO08x'],['../class_b_n_o08x.html#a40f7688e843d74b8bd526c6f5ff17845',1,'BNO08x::BNO08x()']]], + ['bno08x_5fconfig_5ft_1',['bno08x_config_t',['../structbno08x__config__t.html',1,'bno08x_config_t'],['../structbno08x__config__t.html#abf8805292192f4c30c5000423175a2e1',1,'bno08x_config_t::bno08x_config_t()']]], + ['bus_5fconfig_2',['bus_config',['../class_b_n_o08x.html#a982f065df42f00e53fd87c840efdb0f1',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_10.js b/documentation/html/search/all_10.js new file mode 100644 index 0000000..0e0280f --- /dev/null +++ b/documentation/html/search/all_10.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['uncalib_5fgyro_5faccuracy_0',['uncalib_gyro_accuracy',['../class_b_n_o08x.html#a081c666a3f24016d0ec5c5edc49f2903',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_11.js b/documentation/html/search/all_11.js new file mode 100644 index 0000000..1e57a56 --- /dev/null +++ b/documentation/html/search/all_11.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['wait_5ffor_5fdevice_5fint_0',['wait_for_device_int',['../class_b_n_o08x.html#a988c45b4afa4dcd6a24610ff308c1faa',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_2.js b/documentation/html/search/all_2.js new file mode 100644 index 0000000..3262191 --- /dev/null +++ b/documentation/html/search/all_2.js @@ -0,0 +1,26 @@ +var searchData= +[ + ['calibrate_5faccel_0',['CALIBRATE_ACCEL',['../class_b_n_o08x.html#acd5b44d705af1f9aaa271a59a9d2d595',1,'BNO08x']]], + ['calibrate_5faccel_5fgyro_5fmag_1',['CALIBRATE_ACCEL_GYRO_MAG',['../class_b_n_o08x.html#af53d9e99f163d97ef92fe989b1dd25cc',1,'BNO08x']]], + ['calibrate_5faccelerometer_2',['calibrate_accelerometer',['../class_b_n_o08x.html#aeffce374f558a167d5b5f19ad627e7cc',1,'BNO08x']]], + ['calibrate_5fall_3',['calibrate_all',['../class_b_n_o08x.html#afd0ca5f9b9741935543d143a5a43d128',1,'BNO08x']]], + ['calibrate_5fgyro_4',['calibrate_gyro',['../class_b_n_o08x.html#a9ada90f8ab6dd33fa2d7c168d9234af1',1,'BNO08x']]], + ['calibrate_5fgyro_5',['CALIBRATE_GYRO',['../class_b_n_o08x.html#aeac84719a1cc0f9c8d5a9a749391d4db',1,'BNO08x']]], + ['calibrate_5fmag_6',['CALIBRATE_MAG',['../class_b_n_o08x.html#ac00e8b59ae8d710cf79956eaafa97ddb',1,'BNO08x']]], + ['calibrate_5fmagnetometer_7',['calibrate_magnetometer',['../class_b_n_o08x.html#ac26350b55095a346d72598ab8aa74b4a',1,'BNO08x']]], + ['calibrate_5fplanar_5faccel_8',['CALIBRATE_PLANAR_ACCEL',['../class_b_n_o08x.html#a955dcb60da150490e17367a871b3a3d2',1,'BNO08x']]], + ['calibrate_5fplanar_5faccelerometer_9',['calibrate_planar_accelerometer',['../class_b_n_o08x.html#a1c6c49c97bc098db89db1aaa37e18f26',1,'BNO08x']]], + ['calibrate_5fstop_10',['CALIBRATE_STOP',['../class_b_n_o08x.html#a584bfa04a39feb93279ee673c340db54',1,'BNO08x']]], + ['calibration_5fcomplete_11',['calibration_complete',['../class_b_n_o08x.html#a71ca35f78b98d93d31eb0c187dc8543b',1,'BNO08x']]], + ['calibration_5fstatus_12',['calibration_status',['../class_b_n_o08x.html#ad212b5028a31e857e76d251ced2724e1',1,'BNO08x']]], + ['clear_5ftare_13',['clear_tare',['../class_b_n_o08x.html#afe39bfdede7b9a2b273983cb29a27d6e',1,'BNO08x']]], + ['command_5fclear_5fdcd_14',['COMMAND_CLEAR_DCD',['../class_b_n_o08x.html#a4f580b3cb232a762ea7019ee7b04d419',1,'BNO08x']]], + ['command_5fdcd_15',['COMMAND_DCD',['../class_b_n_o08x.html#af124a6c1d8b871f3181b6c85f1099cb2',1,'BNO08x']]], + ['command_5fdcd_5fperiod_5fsave_16',['COMMAND_DCD_PERIOD_SAVE',['../class_b_n_o08x.html#a7a246989c94cd87f68166b20b7ad4c8b',1,'BNO08x']]], + ['command_5finitialize_17',['COMMAND_INITIALIZE',['../class_b_n_o08x.html#a30eb6d305a187d4d36546841e12176b9',1,'BNO08x']]], + ['command_5fme_5fcalibrate_18',['COMMAND_ME_CALIBRATE',['../class_b_n_o08x.html#a8381dfe403ddff522f172cb16780731a',1,'BNO08x']]], + ['command_5foscillator_19',['COMMAND_OSCILLATOR',['../class_b_n_o08x.html#a308c8b5307d93a67b5b9066d44494aa5',1,'BNO08x']]], + ['command_5fsequence_5fnumber_20',['command_sequence_number',['../class_b_n_o08x.html#ac1daa730e75d17e6afd1edaa288260ae',1,'BNO08x']]], + ['command_5ftare_21',['COMMAND_TARE',['../class_b_n_o08x.html#a0a1756bc16ba3eac45f4229b1e350107',1,'BNO08x']]], + ['commands_22',['commands',['../class_b_n_o08x.html#acbca88b37c8c5a590ca971b241dac64f',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_3.js b/documentation/html/search/all_3.js new file mode 100644 index 0000000..40db403 --- /dev/null +++ b/documentation/html/search/all_3.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['data_5favailable_0',['data_available',['../class_b_n_o08x.html#a367d525d1c0ba119b3dca3067bb5bccc',1,'BNO08x']]], + ['debug_5fen_1',['debug_en',['../structbno08x__config__t.html#a720c215a75b3922ffa6f683e7ca70abe',1,'bno08x_config_t']]], + ['default_5fimu_5fconfig_2',['default_imu_config',['../class_b_n_o08x.html#a6232920a05c0aba34e5560951a20ae87',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_4.js b/documentation/html/search/all_4.js new file mode 100644 index 0000000..fdaa4ea --- /dev/null +++ b/documentation/html/search/all_4.js @@ -0,0 +1,22 @@ +var searchData= +[ + ['enable_5faccelerometer_0',['enable_accelerometer',['../class_b_n_o08x.html#a1d68494d911f7efbbb620d349fb9da0d',1,'BNO08x']]], + ['enable_5factivity_5fclassifier_1',['enable_activity_classifier',['../class_b_n_o08x.html#a0960ce957058af565dd4c43ad6c40225',1,'BNO08x']]], + ['enable_5farvr_5fstabilized_5fgame_5frotation_5fvector_2',['enable_ARVR_stabilized_game_rotation_vector',['../class_b_n_o08x.html#ad9e26658c53c728d7d10381db680765e',1,'BNO08x']]], + ['enable_5farvr_5fstabilized_5frotation_5fvector_3',['enable_ARVR_stabilized_rotation_vector',['../class_b_n_o08x.html#a04290cb6ba09b93d5a9ef337c13d1abb',1,'BNO08x']]], + ['enable_5fgame_5frotation_5fvector_4',['enable_game_rotation_vector',['../class_b_n_o08x.html#a639cb013ed17e0f33057742fac97f1a2',1,'BNO08x']]], + ['enable_5fgravity_5',['enable_gravity',['../class_b_n_o08x.html#a2dc0cd5bc04ca7eb3b4fffd2a3a6f27a',1,'BNO08x']]], + ['enable_5fgyro_6',['enable_gyro',['../class_b_n_o08x.html#a7619b598cc8e768c4df4805b2958a2c8',1,'BNO08x']]], + ['enable_5fgyro_5fintegrated_5frotation_5fvector_7',['enable_gyro_integrated_rotation_vector',['../class_b_n_o08x.html#a09a0306abec5895dd0450b2fe970347c',1,'BNO08x']]], + ['enable_5flinear_5faccelerometer_8',['enable_linear_accelerometer',['../class_b_n_o08x.html#ad3724e7e602feb2b695d2d88a61d5328',1,'BNO08x']]], + ['enable_5fmagnetometer_9',['enable_magnetometer',['../class_b_n_o08x.html#acf4a83a44a221f6495263f00f1b8d849',1,'BNO08x']]], + ['enable_5fraw_5faccelerometer_10',['enable_raw_accelerometer',['../class_b_n_o08x.html#ad6adf3b24a8a559d3bb57e6abcef4ce8',1,'BNO08x']]], + ['enable_5fraw_5fgyro_11',['enable_raw_gyro',['../class_b_n_o08x.html#af984deb77c92746fe4d193457312be63',1,'BNO08x']]], + ['enable_5fraw_5fmagnetometer_12',['enable_raw_magnetometer',['../class_b_n_o08x.html#ad1ca07ee06ef98d4e11a74dde18e9623',1,'BNO08x']]], + ['enable_5frotation_5fvector_13',['enable_rotation_vector',['../class_b_n_o08x.html#abe9acd2eb1ce2f2e72b7a48c8d025cc4',1,'BNO08x']]], + ['enable_5fstability_5fclassifier_14',['enable_stability_classifier',['../class_b_n_o08x.html#a5378a235e3114ccdc63b26bc3fae5dad',1,'BNO08x']]], + ['enable_5fstep_5fcounter_15',['enable_step_counter',['../class_b_n_o08x.html#ad550085fa1b51495ce3d8894538f33d5',1,'BNO08x']]], + ['enable_5ftap_5fdetector_16',['enable_tap_detector',['../class_b_n_o08x.html#a919c7d94226f4c6adbb8edf6fd1613a9',1,'BNO08x']]], + ['enable_5funcalibrated_5fgyro_17',['enable_uncalibrated_gyro',['../class_b_n_o08x.html#ac7b5815c5ad8b83a34ad0855423601e8',1,'BNO08x']]], + ['end_5fcalibration_18',['end_calibration',['../class_b_n_o08x.html#ac9d9b6636745e8180807284da67c92a2',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_5.js b/documentation/html/search/all_5.js new file mode 100644 index 0000000..983b345 --- /dev/null +++ b/documentation/html/search/all_5.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['frs_5fread_5fdata_0',['FRS_read_data',['../class_b_n_o08x.html#a40607e557eada666a5e1e416f42cd4a1',1,'BNO08x']]], + ['frs_5fread_5frequest_1',['FRS_read_request',['../class_b_n_o08x.html#adf789e709ac1667656db757c8d559af9',1,'BNO08x']]], + ['frs_5fread_5fword_2',['FRS_read_word',['../class_b_n_o08x.html#a27f5dce5c994be18a587fb622574ad41',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_6.js b/documentation/html/search/all_6.js new file mode 100644 index 0000000..788b9f1 --- /dev/null +++ b/documentation/html/search/all_6.js @@ -0,0 +1,78 @@ +var searchData= +[ + ['get_5faccel_0',['get_accel',['../class_b_n_o08x.html#a9329c6669282071622c3b3741b1b8142',1,'BNO08x']]], + ['get_5faccel_5faccuracy_1',['get_accel_accuracy',['../class_b_n_o08x.html#a3fce726d5de821f97ed207036dae2900',1,'BNO08x']]], + ['get_5faccel_5fx_2',['get_accel_X',['../class_b_n_o08x.html#abce574112a9079d2cbc58cfc352b8a69',1,'BNO08x']]], + ['get_5faccel_5fy_3',['get_accel_Y',['../class_b_n_o08x.html#afdf24bb3d54518b23972f21f007817c1',1,'BNO08x']]], + ['get_5faccel_5fz_4',['get_accel_Z',['../class_b_n_o08x.html#a0a72477cb7a330fedbcb3e2126b882b1',1,'BNO08x']]], + ['get_5factivity_5fclassifier_5',['get_activity_classifier',['../class_b_n_o08x.html#a4f7060b2d3c15b359b70b6346730446a',1,'BNO08x']]], + ['get_5fgravity_6',['get_gravity',['../class_b_n_o08x.html#a386c46ac8965220ab7b9423df838dd4d',1,'BNO08x']]], + ['get_5fgravity_5faccuracy_7',['get_gravity_accuracy',['../class_b_n_o08x.html#accd39f48e9f8ab8267df7184b5b7cd76',1,'BNO08x']]], + ['get_5fgravity_5fx_8',['get_gravity_X',['../class_b_n_o08x.html#a88679bccd9339b87ec35fc4fc4e745ae',1,'BNO08x']]], + ['get_5fgravity_5fy_9',['get_gravity_Y',['../class_b_n_o08x.html#a8a36db7f1c932f33e05e494632059801',1,'BNO08x']]], + ['get_5fgravity_5fz_10',['get_gravity_Z',['../class_b_n_o08x.html#a5622b4d1754648ea7eb400c1adf9e807',1,'BNO08x']]], + ['get_5fgyro_5faccuracy_11',['get_gyro_accuracy',['../class_b_n_o08x.html#a811999653110858311c97a779c388e5d',1,'BNO08x']]], + ['get_5fgyro_5fcalibrated_5fvelocity_12',['get_gyro_calibrated_velocity',['../class_b_n_o08x.html#a4d3746a376a22acb7a2641bb750c4c89',1,'BNO08x']]], + ['get_5fgyro_5fcalibrated_5fvelocity_5fx_13',['get_gyro_calibrated_velocity_X',['../class_b_n_o08x.html#ab7977391191067282e7f734b9ee45059',1,'BNO08x']]], + ['get_5fgyro_5fcalibrated_5fvelocity_5fy_14',['get_gyro_calibrated_velocity_Y',['../class_b_n_o08x.html#ad4fab6e636e239d4b9273f158983ed89',1,'BNO08x']]], + ['get_5fgyro_5fcalibrated_5fvelocity_5fz_15',['get_gyro_calibrated_velocity_Z',['../class_b_n_o08x.html#a15a29c3bb476048b7229abcfb2b1d52a',1,'BNO08x']]], + ['get_5fgyro_5fvelocity_16',['get_gyro_velocity',['../class_b_n_o08x.html#afe6392012669e7ebd1a9e817e2bd313f',1,'BNO08x']]], + ['get_5fgyro_5fvelocity_5fx_17',['get_gyro_velocity_X',['../class_b_n_o08x.html#acd376cd3e454a87198ec86accbf2ee00',1,'BNO08x']]], + ['get_5fgyro_5fvelocity_5fy_18',['get_gyro_velocity_Y',['../class_b_n_o08x.html#acd1819a81818f90dc105950b4a7d0b04',1,'BNO08x']]], + ['get_5fgyro_5fvelocity_5fz_19',['get_gyro_velocity_Z',['../class_b_n_o08x.html#ae2add976af256ec981248371a2f58207',1,'BNO08x']]], + ['get_5flinear_5faccel_20',['get_linear_accel',['../class_b_n_o08x.html#ad59b029d04341dbef72e059488951980',1,'BNO08x']]], + ['get_5flinear_5faccel_5faccuracy_21',['get_linear_accel_accuracy',['../class_b_n_o08x.html#a33fe3c2f47759cfae5f4b612ddd329ea',1,'BNO08x']]], + ['get_5flinear_5faccel_5fx_22',['get_linear_accel_X',['../class_b_n_o08x.html#a763c3a9699a1081d430fd9b9b7bc49a3',1,'BNO08x']]], + ['get_5flinear_5faccel_5fy_23',['get_linear_accel_Y',['../class_b_n_o08x.html#a1033bdd65b42b6706d1dfc67ece66191',1,'BNO08x']]], + ['get_5flinear_5faccel_5fz_24',['get_linear_accel_Z',['../class_b_n_o08x.html#afdfa7d50362702da689c5d18bf17fd84',1,'BNO08x']]], + ['get_5fmagf_25',['get_magf',['../class_b_n_o08x.html#a35a224d519a2a243d0d526a34ecde5a8',1,'BNO08x']]], + ['get_5fmagf_5faccuracy_26',['get_magf_accuracy',['../class_b_n_o08x.html#a487391e6b2dd7f05084804d1fb94976f',1,'BNO08x']]], + ['get_5fmagf_5fx_27',['get_magf_X',['../class_b_n_o08x.html#a111601243b913751eb51c1f37cba4e7d',1,'BNO08x']]], + ['get_5fmagf_5fy_28',['get_magf_Y',['../class_b_n_o08x.html#a82ed8d7b9a5c25374839df75a3d220ea',1,'BNO08x']]], + ['get_5fmagf_5fz_29',['get_magf_Z',['../class_b_n_o08x.html#ab4c48a91d2f8b29430abc17b7f015282',1,'BNO08x']]], + ['get_5fpitch_30',['get_pitch',['../class_b_n_o08x.html#a1b91f234d81c45f1f5ca2f27c9f0f6a3',1,'BNO08x']]], + ['get_5fpitch_5fdeg_31',['get_pitch_deg',['../class_b_n_o08x.html#af50010400cbd1445e9ddfa259384b412',1,'BNO08x']]], + ['get_5fq1_32',['get_Q1',['../class_b_n_o08x.html#a4421c43323945946ad605f8422958dcf',1,'BNO08x']]], + ['get_5fq2_33',['get_Q2',['../class_b_n_o08x.html#a954dccdcbe8a8c4f1787f13ebb8d932b',1,'BNO08x']]], + ['get_5fq3_34',['get_Q3',['../class_b_n_o08x.html#a1590ba793668f9cb1a32a1f4dd07cb9a',1,'BNO08x']]], + ['get_5fquat_35',['get_quat',['../class_b_n_o08x.html#a51a6d594824de2292e70f788454f8a2d',1,'BNO08x']]], + ['get_5fquat_5faccuracy_36',['get_quat_accuracy',['../class_b_n_o08x.html#a24ba760d064a1dc45f972c79b9c8d98d',1,'BNO08x']]], + ['get_5fquat_5fi_37',['get_quat_I',['../class_b_n_o08x.html#a12c12a8e078b28480fb8828d306656f5',1,'BNO08x']]], + ['get_5fquat_5fj_38',['get_quat_J',['../class_b_n_o08x.html#a9f6bb642fa0297a7b9bcc94dd7374015',1,'BNO08x']]], + ['get_5fquat_5fk_39',['get_quat_K',['../class_b_n_o08x.html#a9f42c70c2337a0d831064a40ecfe2dd8',1,'BNO08x']]], + ['get_5fquat_5fradian_5faccuracy_40',['get_quat_radian_accuracy',['../class_b_n_o08x.html#a61b7d10a98afc6903fea6b2cede27630',1,'BNO08x']]], + ['get_5fquat_5freal_41',['get_quat_real',['../class_b_n_o08x.html#a5a556c5ec1baaa7f1156779dbe47a7b7',1,'BNO08x']]], + ['get_5frange_42',['get_range',['../class_b_n_o08x.html#a0fff04c42c9502615ad73cd1457cb9b0',1,'BNO08x']]], + ['get_5fraw_5faccel_5fx_43',['get_raw_accel_X',['../class_b_n_o08x.html#a1de356dd604c1dffcd1a32faeb4fafe2',1,'BNO08x']]], + ['get_5fraw_5faccel_5fy_44',['get_raw_accel_Y',['../class_b_n_o08x.html#a96563de0eb597a52d595d19da827b1ac',1,'BNO08x']]], + ['get_5fraw_5faccel_5fz_45',['get_raw_accel_Z',['../class_b_n_o08x.html#a718cdd910e5e7e03fd0a1ad04ee6f0ce',1,'BNO08x']]], + ['get_5fraw_5fgyro_5fx_46',['get_raw_gyro_X',['../class_b_n_o08x.html#af1b2c3a383a84fc6dfaddae1052b44d4',1,'BNO08x']]], + ['get_5fraw_5fgyro_5fy_47',['get_raw_gyro_Y',['../class_b_n_o08x.html#aff7714441d242b3b9b0c03f94e0a9374',1,'BNO08x']]], + ['get_5fraw_5fgyro_5fz_48',['get_raw_gyro_Z',['../class_b_n_o08x.html#a2e28b5a79c442a6baa2fa5165b9ce37d',1,'BNO08x']]], + ['get_5fraw_5fmagf_5fx_49',['get_raw_magf_X',['../class_b_n_o08x.html#adf12600b39de41d258439a343fcc1ad8',1,'BNO08x']]], + ['get_5fraw_5fmagf_5fy_50',['get_raw_magf_Y',['../class_b_n_o08x.html#a2c842e43ceae19149f6525bcbc48f1cf',1,'BNO08x']]], + ['get_5fraw_5fmagf_5fz_51',['get_raw_magf_Z',['../class_b_n_o08x.html#a99c1bcc2ec3ca3d8feafd6dd61f9d269',1,'BNO08x']]], + ['get_5freadings_52',['get_readings',['../class_b_n_o08x.html#a9cc47f0e5b7d679c80992c993a910ccf',1,'BNO08x']]], + ['get_5freset_5freason_53',['get_reset_reason',['../class_b_n_o08x.html#a11bb1b3fa44ad8f28c1492b5c07af886',1,'BNO08x']]], + ['get_5fresolution_54',['get_resolution',['../class_b_n_o08x.html#a1d6ea02d0d4b23ff6a15e9d5c6c92372',1,'BNO08x']]], + ['get_5froll_55',['get_roll',['../class_b_n_o08x.html#a89618eba08186ee8e679e7313907ddef',1,'BNO08x']]], + ['get_5froll_5fdeg_56',['get_roll_deg',['../class_b_n_o08x.html#a7077b9a130f1dcf0192454e387968dd6',1,'BNO08x']]], + ['get_5fstability_5fclassifier_57',['get_stability_classifier',['../class_b_n_o08x.html#a0d148e00abcfeec48c689e3084a7e786',1,'BNO08x']]], + ['get_5fstep_5fcount_58',['get_step_count',['../class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef',1,'BNO08x']]], + ['get_5ftap_5fdetector_59',['get_tap_detector',['../class_b_n_o08x.html#a4797ec731de4c158716da1a7af9d1602',1,'BNO08x']]], + ['get_5ftime_5fstamp_60',['get_time_stamp',['../class_b_n_o08x.html#ad9137777271421a58159f3fe5e05ed20',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_61',['get_uncalibrated_gyro',['../class_b_n_o08x.html#a1bd3c33e70354bd35a78b83b6786b531',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5faccuracy_62',['get_uncalibrated_gyro_accuracy',['../class_b_n_o08x.html#a3285613f18b2f2f4c3f9e6d5c971af10',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5fbias_5fx_63',['get_uncalibrated_gyro_bias_X',['../class_b_n_o08x.html#ad228cdf352b7ea95e484da993045a47b',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5fbias_5fy_64',['get_uncalibrated_gyro_bias_Y',['../class_b_n_o08x.html#a74725517129dd548c7a3de705d5861bd',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5fbias_5fz_65',['get_uncalibrated_gyro_bias_Z',['../class_b_n_o08x.html#a5050359272abd146ab3c7a6101effbd7',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5fx_66',['get_uncalibrated_gyro_X',['../class_b_n_o08x.html#a289ff66f51c94be62c4a556f3a5997bf',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5fy_67',['get_uncalibrated_gyro_Y',['../class_b_n_o08x.html#a1874e4bd457bb5b6ecc2c64039b88ba4',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5fz_68',['get_uncalibrated_gyro_Z',['../class_b_n_o08x.html#a0a73633d8929ce4058b14cefc8cad717',1,'BNO08x']]], + ['get_5fyaw_69',['get_yaw',['../class_b_n_o08x.html#a64d3e41750c6de9413d6982511f78f17',1,'BNO08x']]], + ['get_5fyaw_5fdeg_70',['get_yaw_deg',['../class_b_n_o08x.html#af80f7795656e695e036d3b1557aed94c',1,'BNO08x']]], + ['gravity_5faccuracy_71',['gravity_accuracy',['../class_b_n_o08x.html#ae01698d287ea999179a11e2244902022',1,'BNO08x']]], + ['gravity_5fq1_72',['GRAVITY_Q1',['../class_b_n_o08x.html#ae10722334dfce9635e76519598e165a2',1,'BNO08x']]], + ['gyro_5faccuracy_73',['gyro_accuracy',['../class_b_n_o08x.html#a98ea35dd0fbd0c409d25fd8a6ed9f277',1,'BNO08x']]], + ['gyro_5fq1_74',['GYRO_Q1',['../class_b_n_o08x.html#aa3bec8effefa61cec6fa170e9d02c4dd',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_7.js b/documentation/html/search/all_7.js new file mode 100644 index 0000000..ecb1940 --- /dev/null +++ b/documentation/html/search/all_7.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['hard_5freset_0',['hard_reset',['../class_b_n_o08x.html#a28cd1c0b3477571d87133234e6358503',1,'BNO08x']]], + ['hint_5fhandler_1',['hint_handler',['../class_b_n_o08x.html#a804b95c58c30d36933fd251626b85bf7',1,'BNO08x']]], + ['host_5fint_5ftimeout_5fus_2',['HOST_INT_TIMEOUT_US',['../class_b_n_o08x.html#a53c4824accdff697948c10df30a15457',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_8.js b/documentation/html/search/all_8.js new file mode 100644 index 0000000..2182da5 --- /dev/null +++ b/documentation/html/search/all_8.js @@ -0,0 +1,14 @@ +var searchData= +[ + ['imu_5fconfig_0',['imu_config',['../class_b_n_o08x.html#aeda443e9f608fccfec0e6770edc90c82',1,'BNO08x']]], + ['imu_5fspi_5fconfig_1',['imu_spi_config',['../class_b_n_o08x.html#a425a1f5a9f3232aadc685caaf4c2f82e',1,'BNO08x']]], + ['initialize_2',['initialize',['../class_b_n_o08x.html#aea8e2c6dd7a2c9899479a7f39fe94798',1,'BNO08x']]], + ['int_5fasserted_3',['int_asserted',['../class_b_n_o08x.html#a496407fcd9c7c921bf5b3b062024b29d',1,'BNO08x']]], + ['io_5fint_4',['io_int',['../structbno08x__config__t.html#a3cfe965659cfbc6b0c5269bd0211975f',1,'bno08x_config_t']]], + ['io_5fmiso_5',['io_miso',['../structbno08x__config__t.html#a9468180a773892977db39cc5ed9368e3',1,'bno08x_config_t']]], + ['io_5fmosi_6',['io_mosi',['../structbno08x__config__t.html#a79023fd80039e41a22b7f73ccd5fc861',1,'bno08x_config_t']]], + ['io_5frst_7',['io_rst',['../structbno08x__config__t.html#a62745c761219139f66ecd173b51577fc',1,'bno08x_config_t']]], + ['io_5fsclk_8',['io_sclk',['../structbno08x__config__t.html#a639685b91ae3198909d722316495246a',1,'bno08x_config_t']]], + ['io_5fwake_9',['io_wake',['../structbno08x__config__t.html#a90ad7f316dc443874d19dc7e723a0ce0',1,'bno08x_config_t']]], + ['isr_5fservice_5finstalled_10',['isr_service_installed',['../class_b_n_o08x.html#a4882dbc698d7b730f57e2401037766a9',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_9.js b/documentation/html/search/all_9.js new file mode 100644 index 0000000..21ab395 --- /dev/null +++ b/documentation/html/search/all_9.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['linear_5faccelerometer_5fq1_0',['LINEAR_ACCELEROMETER_Q1',['../class_b_n_o08x.html#ad0d37fe07ced24f2c9afc21145a74e7b',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_a.js b/documentation/html/search/all_a.js new file mode 100644 index 0000000..f712371 --- /dev/null +++ b/documentation/html/search/all_a.js @@ -0,0 +1,11 @@ +var searchData= +[ + ['magf_5faccuracy_0',['magf_accuracy',['../class_b_n_o08x.html#ac5d4e151690774687efa951ca41c16ae',1,'BNO08x']]], + ['magnetometer_5fq1_1',['MAGNETOMETER_Q1',['../class_b_n_o08x.html#a9fac9b811b7c2117675a784cb4df204c',1,'BNO08x']]], + ['mems_5fraw_5faccel_5fz_2',['mems_raw_accel_Z',['../class_b_n_o08x.html#a59a4d75f1302ab693b1b26e9ccaa5341',1,'BNO08x']]], + ['mems_5fraw_5fgyro_5fz_3',['mems_raw_gyro_Z',['../class_b_n_o08x.html#ac35d5b12721ab876eaeb1f714a9b3b1d',1,'BNO08x']]], + ['mems_5fraw_5fmagf_5fz_4',['mems_raw_magf_Z',['../class_b_n_o08x.html#a90f0cdf11decc276006f76a494d42ce3',1,'BNO08x']]], + ['meta_5fdata_5',['meta_data',['../class_b_n_o08x.html#a7bd032712a975e73e66bd72a3502baba',1,'BNO08x']]], + ['mode_5fon_6',['mode_on',['../class_b_n_o08x.html#ac1b3de9b552c611ee9c455d7f19be698',1,'BNO08x']]], + ['mode_5fsleep_7',['mode_sleep',['../class_b_n_o08x.html#a176ae0112325c05105eacb4566bbfa0b',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_b.js b/documentation/html/search/all_b.js new file mode 100644 index 0000000..f8fbb99 --- /dev/null +++ b/documentation/html/search/all_b.js @@ -0,0 +1,9 @@ +var searchData= +[ + ['packet_5fheader_5frx_0',['packet_header_rx',['../class_b_n_o08x.html#a908264b797fff9dc6679abde5e7584a5',1,'BNO08x']]], + ['packet_5flength_5frx_1',['packet_length_rx',['../class_b_n_o08x.html#af65e3fd0bfdb5b82dcf775e2c061c65a',1,'BNO08x']]], + ['packet_5flength_5ftx_2',['packet_length_tx',['../class_b_n_o08x.html#a6fbc6d086654b022a3ea53dfacd4fdf5',1,'BNO08x']]], + ['parse_5fcommand_5freport_3',['parse_command_report',['../class_b_n_o08x.html#a3762125be0025a335f0d918415f4ce18',1,'BNO08x']]], + ['parse_5finput_5freport_4',['parse_input_report',['../class_b_n_o08x.html#a7ba1d779ed68edf30090dd0f938a5709',1,'BNO08x']]], + ['print_5fheader_5',['print_header',['../class_b_n_o08x.html#a08f037df7b3c7e2fc3f0e968f4a5f68c',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_c.js b/documentation/html/search/all_c.js new file mode 100644 index 0000000..91bb37d --- /dev/null +++ b/documentation/html/search/all_c.js @@ -0,0 +1,11 @@ +var searchData= +[ + ['q_5fto_5ffloat_0',['q_to_float',['../class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9',1,'BNO08x']]], + ['quat_5faccuracy_1',['quat_accuracy',['../class_b_n_o08x.html#a36223f7124751fa71e860b2ef55dd2ac',1,'BNO08x']]], + ['queue_5fcalibrate_5fcommand_2',['queue_calibrate_command',['../class_b_n_o08x.html#ad097849616c5caab1fd3eb3632ee2b91',1,'BNO08x']]], + ['queue_5fcommand_3',['queue_command',['../class_b_n_o08x.html#a1742d6445ffb6e9297b8bf84dec24f22',1,'BNO08x']]], + ['queue_5ffeature_5fcommand_4',['queue_feature_command',['../class_b_n_o08x.html#a6c004a16b146527aa9eeeb6ff37db281',1,'BNO08x::queue_feature_command(uint8_t report_ID, uint16_t time_between_reports)'],['../class_b_n_o08x.html#af0a0686a78c929aad43af2eaeba12878',1,'BNO08x::queue_feature_command(uint8_t report_ID, uint16_t time_between_reports, uint32_t specific_config)']]], + ['queue_5fpacket_5',['queue_packet',['../class_b_n_o08x.html#a67d0b5302a60083cef1b31936e2b65d8',1,'BNO08x']]], + ['queue_5frequest_5fproduct_5fid_5fcommand_6',['queue_request_product_id_command',['../class_b_n_o08x.html#ab5f200069a2f8cb74cb79c6f162da5a1',1,'BNO08x']]], + ['queue_5ftare_5fcommand_7',['queue_tare_command',['../class_b_n_o08x.html#a4c6353e795f734ed28613f9a3d161ea2',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_d.js b/documentation/html/search/all_d.js new file mode 100644 index 0000000..c044a57 --- /dev/null +++ b/documentation/html/search/all_d.js @@ -0,0 +1,11 @@ +var searchData= +[ + ['raw_5fvelocity_5fgyro_5fz_0',['raw_velocity_gyro_Z',['../class_b_n_o08x.html#ab49f9a6586d709bbd26280ef44a4bbf7',1,'BNO08x']]], + ['readme_1',['README',['../md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e.html',1,'']]], + ['receive_5fpacket_2',['receive_packet',['../class_b_n_o08x.html#ae540799865934fcff54caed0772df071',1,'BNO08x']]], + ['request_5fcalibration_5fstatus_3',['request_calibration_status',['../class_b_n_o08x.html#affaaa35abbb872da5299ebab6e2c9b11',1,'BNO08x']]], + ['rotation_5fvector_5faccuracy_5fq1_4',['ROTATION_VECTOR_ACCURACY_Q1',['../class_b_n_o08x.html#a923d65d8568cc31873ad56a3908e1939',1,'BNO08x']]], + ['rotation_5fvector_5fq1_5',['ROTATION_VECTOR_Q1',['../class_b_n_o08x.html#a0b19c8f2de2b2bfe033da7f93cdd2608',1,'BNO08x']]], + ['run_5ffull_5fcalibration_5froutine_6',['run_full_calibration_routine',['../class_b_n_o08x.html#ae6e875a27ae74ebed806ee1a4576845a',1,'BNO08x']]], + ['rx_5fbuffer_7',['rx_buffer',['../class_b_n_o08x.html#a7a85ccea09eadf865e8bbbf00d800e64',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_e.js b/documentation/html/search/all_e.js new file mode 100644 index 0000000..139abd6 --- /dev/null +++ b/documentation/html/search/all_e.js @@ -0,0 +1,44 @@ +var searchData= +[ + ['save_5fcalibration_0',['save_calibration',['../class_b_n_o08x.html#aa16609de88bfb7b389348859aa0cee54',1,'BNO08x']]], + ['save_5ftare_1',['save_tare',['../class_b_n_o08x.html#afb2ffc4e7ff0498917bc14a83af306e2',1,'BNO08x']]], + ['sclk_5fspeed_2',['sclk_speed',['../structbno08x__config__t.html#a652ad01310ba21afcae1bb765de51cfe',1,'bno08x_config_t']]], + ['send_5fpacket_3',['send_packet',['../class_b_n_o08x.html#a0ee58cedbc06d4a7db8821f40c0ee207',1,'BNO08x']]], + ['sensor_5freportid_5faccelerometer_4',['SENSOR_REPORTID_ACCELEROMETER',['../class_b_n_o08x.html#a476b35f11a2f096cdb70f7ee73cf2e90',1,'BNO08x']]], + ['sensor_5freportid_5far_5fvr_5fstabilized_5fgame_5frotation_5fvector_5',['SENSOR_REPORTID_AR_VR_STABILIZED_GAME_ROTATION_VECTOR',['../class_b_n_o08x.html#a09dd6846e22801427b92b325385653e0',1,'BNO08x']]], + ['sensor_5freportid_5far_5fvr_5fstabilized_5frotation_5fvector_6',['SENSOR_REPORTID_AR_VR_STABILIZED_ROTATION_VECTOR',['../class_b_n_o08x.html#a263b8c25089c38f9ffa85493aef79606',1,'BNO08x']]], + ['sensor_5freportid_5fgame_5frotation_5fvector_7',['SENSOR_REPORTID_GAME_ROTATION_VECTOR',['../class_b_n_o08x.html#ab3dc8b362050d438d8a05b26e86af638',1,'BNO08x']]], + ['sensor_5freportid_5fgeomagnetic_5frotation_5fvector_8',['SENSOR_REPORTID_GEOMAGNETIC_ROTATION_VECTOR',['../class_b_n_o08x.html#aec618850b70a4e32a5148b05281aa8f0',1,'BNO08x']]], + ['sensor_5freportid_5fgravity_9',['SENSOR_REPORTID_GRAVITY',['../class_b_n_o08x.html#aeeb54b0b516917f3ff58cb655ae707a8',1,'BNO08x']]], + ['sensor_5freportid_5fgyro_5fintegrated_5frotation_5fvector_10',['SENSOR_REPORTID_GYRO_INTEGRATED_ROTATION_VECTOR',['../class_b_n_o08x.html#a8b55a8131c251bb234d5391b0cd6aa48',1,'BNO08x']]], + ['sensor_5freportid_5fgyroscope_11',['SENSOR_REPORTID_GYROSCOPE',['../class_b_n_o08x.html#a29ab9f86763cce89e833392553f7abb4',1,'BNO08x']]], + ['sensor_5freportid_5flinear_5facceleration_12',['SENSOR_REPORTID_LINEAR_ACCELERATION',['../class_b_n_o08x.html#a53898b82dbac7ef27e1adb519dfcd686',1,'BNO08x']]], + ['sensor_5freportid_5fmagnetic_5ffield_13',['SENSOR_REPORTID_MAGNETIC_FIELD',['../class_b_n_o08x.html#a6f3bf6774ceb583c5c56f2ad80573834',1,'BNO08x']]], + ['sensor_5freportid_5fpersonal_5factivity_5fclassifier_14',['SENSOR_REPORTID_PERSONAL_ACTIVITY_CLASSIFIER',['../class_b_n_o08x.html#a001b45f56e347fb8e8149bcecbe2b40c',1,'BNO08x']]], + ['sensor_5freportid_5fraw_5faccelerometer_15',['SENSOR_REPORTID_RAW_ACCELEROMETER',['../class_b_n_o08x.html#aa8d2d5c66b72af3966dca751e7343a97',1,'BNO08x']]], + ['sensor_5freportid_5fraw_5fgyroscope_16',['SENSOR_REPORTID_RAW_GYROSCOPE',['../class_b_n_o08x.html#aaed7faffc8f2bba8a2ae56933236f9f7',1,'BNO08x']]], + ['sensor_5freportid_5fraw_5fmagnetometer_17',['SENSOR_REPORTID_RAW_MAGNETOMETER',['../class_b_n_o08x.html#ac719a06278c239cc36f666b99a41b1c0',1,'BNO08x']]], + ['sensor_5freportid_5frotation_5fvector_18',['SENSOR_REPORTID_ROTATION_VECTOR',['../class_b_n_o08x.html#ab0279e8622ed188ee48411e074fb7e9d',1,'BNO08x']]], + ['sensor_5freportid_5fstability_5fclassifier_19',['SENSOR_REPORTID_STABILITY_CLASSIFIER',['../class_b_n_o08x.html#afad93ba52698512205df714109cadcfc',1,'BNO08x']]], + ['sensor_5freportid_5fstep_5fcounter_20',['SENSOR_REPORTID_STEP_COUNTER',['../class_b_n_o08x.html#aaff9af63d5f35c05f0a1e485f3d97bc5',1,'BNO08x']]], + ['sensor_5freportid_5ftap_5fdetector_21',['SENSOR_REPORTID_TAP_DETECTOR',['../class_b_n_o08x.html#a437fed4cb82edd32f839d88679ff8ed9',1,'BNO08x']]], + ['sensor_5freportid_5funcalibrated_5fgyro_22',['SENSOR_REPORTID_UNCALIBRATED_GYRO',['../class_b_n_o08x.html#ab94bfdbbffc0a7a255e752244b22322a',1,'BNO08x']]], + ['sequence_5fnumber_23',['sequence_number',['../class_b_n_o08x.html#aa722dbc6f6f07c63e9ea2a9271614af3',1,'BNO08x']]], + ['shtp_5freport_5fbase_5ftimestamp_24',['SHTP_REPORT_BASE_TIMESTAMP',['../class_b_n_o08x.html#ae37d6f8431c8c465bfb0c662772b5cb9',1,'BNO08x']]], + ['shtp_5freport_5fcommand_5frequest_25',['SHTP_REPORT_COMMAND_REQUEST',['../class_b_n_o08x.html#ab04695dd189412092254e52bd6e5a75a',1,'BNO08x']]], + ['shtp_5freport_5fcommand_5fresponse_26',['SHTP_REPORT_COMMAND_RESPONSE',['../class_b_n_o08x.html#a1e5b64caa514b7e4fe64ab214758b875',1,'BNO08x']]], + ['shtp_5freport_5ffrs_5fread_5frequest_27',['SHTP_REPORT_FRS_READ_REQUEST',['../class_b_n_o08x.html#a74af7eacc35cc825940b647c2de0d368',1,'BNO08x']]], + ['shtp_5freport_5ffrs_5fread_5fresponse_28',['SHTP_REPORT_FRS_READ_RESPONSE',['../class_b_n_o08x.html#aeb760b095dcf808a413ef696f2608e43',1,'BNO08x']]], + ['shtp_5freport_5fproduct_5fid_5frequest_29',['SHTP_REPORT_PRODUCT_ID_REQUEST',['../class_b_n_o08x.html#a542405639c28bd56bc4361b922763c95',1,'BNO08x']]], + ['shtp_5freport_5fproduct_5fid_5fresponse_30',['SHTP_REPORT_PRODUCT_ID_RESPONSE',['../class_b_n_o08x.html#a0177134162e116501bc9483c6e4b76c3',1,'BNO08x']]], + ['shtp_5freport_5fset_5ffeature_5fcommand_31',['SHTP_REPORT_SET_FEATURE_COMMAND',['../class_b_n_o08x.html#a1d3bff4e20c2c3d47db322c9e34ef338',1,'BNO08x']]], + ['soft_5freset_32',['soft_reset',['../class_b_n_o08x.html#a973a1b1785f3302ee1b2702c6a27646e',1,'BNO08x']]], + ['spi_5fhdl_33',['spi_hdl',['../class_b_n_o08x.html#acc0ea091465fc9a5736f5e0c6a0ce8ef',1,'BNO08x']]], + ['spi_5fperipheral_34',['spi_peripheral',['../structbno08x__config__t.html#a020d2343750bb7debc2a108ae038c9ec',1,'bno08x_config_t']]], + ['spi_5ftask_35',['spi_task',['../class_b_n_o08x.html#a2ecd4ed60f82730ae230c61687ec92bf',1,'BNO08x']]], + ['spi_5ftask_5fhdl_36',['spi_task_hdl',['../class_b_n_o08x.html#a615090aae15f1b0410a7e5ecb94957b5',1,'BNO08x']]], + ['spi_5ftask_5ftrampoline_37',['spi_task_trampoline',['../class_b_n_o08x.html#a0ce6d9db873555f1ebe7e095251eab74',1,'BNO08x']]], + ['spi_5ftransaction_38',['spi_transaction',['../class_b_n_o08x.html#ac16adc5f00b0039c98a4921f13895026',1,'BNO08x']]], + ['stability_5fclassifier_39',['stability_classifier',['../class_b_n_o08x.html#a1b12471e92536a79d0c425d77676f2e1',1,'BNO08x']]], + ['step_5fcount_40',['step_count',['../class_b_n_o08x.html#ad80a77973371b12d722ea39063c648be',1,'BNO08x']]] +]; diff --git a/documentation/html/search/all_f.js b/documentation/html/search/all_f.js new file mode 100644 index 0000000..72d3153 --- /dev/null +++ b/documentation/html/search/all_f.js @@ -0,0 +1,21 @@ +var searchData= +[ + ['tag_0',['TAG',['../class_b_n_o08x.html#a2c98d5f2c406a3efd0b48c5666fa8c46',1,'BNO08x']]], + ['tap_5fdetector_1',['tap_detector',['../class_b_n_o08x.html#a1171a5738a4e6831ec7fa32a29f15554',1,'BNO08x']]], + ['tare_5far_5fvr_5fstabilized_5fgame_5frotation_5fvector_2',['TARE_AR_VR_STABILIZED_GAME_ROTATION_VECTOR',['../class_b_n_o08x.html#aed8135fd5e7996ef06bf5968692ccd84',1,'BNO08x']]], + ['tare_5far_5fvr_5fstabilized_5frotation_5fvector_3',['TARE_AR_VR_STABILIZED_ROTATION_VECTOR',['../class_b_n_o08x.html#a32204963cefc4ae64a80f43e71c8667a',1,'BNO08x']]], + ['tare_5faxis_5fall_4',['TARE_AXIS_ALL',['../class_b_n_o08x.html#a1ef13f6f330810934416ad5fe0ee55b2',1,'BNO08x']]], + ['tare_5faxis_5fz_5',['TARE_AXIS_Z',['../class_b_n_o08x.html#aecb3e11c1ca5769fd60f42c17a105731',1,'BNO08x']]], + ['tare_5fgame_5frotation_5fvector_6',['TARE_GAME_ROTATION_VECTOR',['../class_b_n_o08x.html#abaf1ec8bb197db1998a9ed3cec6180d5',1,'BNO08x']]], + ['tare_5fgeomagnetic_5frotation_5fvector_7',['TARE_GEOMAGNETIC_ROTATION_VECTOR',['../class_b_n_o08x.html#a225397a04d849e5647992ca80d68febb',1,'BNO08x']]], + ['tare_5fgyro_5fintegrated_5frotation_5fvector_8',['TARE_GYRO_INTEGRATED_ROTATION_VECTOR',['../class_b_n_o08x.html#a9ec354d75249f06f13599abf7bedfde0',1,'BNO08x']]], + ['tare_5fnow_9',['tare_now',['../class_b_n_o08x.html#a4549bbef48208bd9c745fc755b93012f',1,'BNO08x']]], + ['tare_5fnow_10',['TARE_NOW',['../class_b_n_o08x.html#a27df630f3e52b35552d2c1f2cf3496b0',1,'BNO08x']]], + ['tare_5fpersist_11',['TARE_PERSIST',['../class_b_n_o08x.html#a115aef7b38ec0dec2085f6917d832912',1,'BNO08x']]], + ['tare_5frotation_5fvector_12',['TARE_ROTATION_VECTOR',['../class_b_n_o08x.html#a8e2cfc25d0e34ae53a762b88cc3ac3c8',1,'BNO08x']]], + ['tare_5fset_5freorientation_13',['TARE_SET_REORIENTATION',['../class_b_n_o08x.html#a59cde7dd301c94a20b84735c5d49008e',1,'BNO08x']]], + ['time_5fstamp_14',['time_stamp',['../class_b_n_o08x.html#abc972db20affbd0040b4e6c4892dd57b',1,'BNO08x']]], + ['tx_5fbuffer_15',['tx_buffer',['../class_b_n_o08x.html#a74d936708ba924b6ba21004ff9a0b30b',1,'BNO08x']]], + ['tx_5fpacket_5fqueued_16',['tx_packet_queued',['../class_b_n_o08x.html#a5b1f13a3170f1c8fdcc886353efa0c08',1,'BNO08x']]], + ['tx_5fsemaphore_17',['tx_semaphore',['../class_b_n_o08x.html#aee2d0bcb8e9d7bacacccacbb04ded661',1,'BNO08x']]] +]; diff --git a/documentation/html/search/classes_0.js b/documentation/html/search/classes_0.js new file mode 100644 index 0000000..bea014d --- /dev/null +++ b/documentation/html/search/classes_0.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['bno08x_0',['BNO08x',['../class_b_n_o08x.html',1,'']]], + ['bno08x_5fconfig_5ft_1',['bno08x_config_t',['../structbno08x__config__t.html',1,'']]] +]; diff --git a/documentation/html/search/close.svg b/documentation/html/search/close.svg new file mode 100644 index 0000000..337d6cc --- /dev/null +++ b/documentation/html/search/close.svg @@ -0,0 +1,18 @@ + + + + + + diff --git a/documentation/html/search/functions_0.js b/documentation/html/search/functions_0.js new file mode 100644 index 0000000..ceb9113 --- /dev/null +++ b/documentation/html/search/functions_0.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['bno08x_0',['BNO08x',['../class_b_n_o08x.html#a40f7688e843d74b8bd526c6f5ff17845',1,'BNO08x']]], + ['bno08x_5fconfig_5ft_1',['bno08x_config_t',['../structbno08x__config__t.html#abf8805292192f4c30c5000423175a2e1',1,'bno08x_config_t']]] +]; diff --git a/documentation/html/search/functions_1.js b/documentation/html/search/functions_1.js new file mode 100644 index 0000000..33a0414 --- /dev/null +++ b/documentation/html/search/functions_1.js @@ -0,0 +1,10 @@ +var searchData= +[ + ['calibrate_5faccelerometer_0',['calibrate_accelerometer',['../class_b_n_o08x.html#aeffce374f558a167d5b5f19ad627e7cc',1,'BNO08x']]], + ['calibrate_5fall_1',['calibrate_all',['../class_b_n_o08x.html#afd0ca5f9b9741935543d143a5a43d128',1,'BNO08x']]], + ['calibrate_5fgyro_2',['calibrate_gyro',['../class_b_n_o08x.html#a9ada90f8ab6dd33fa2d7c168d9234af1',1,'BNO08x']]], + ['calibrate_5fmagnetometer_3',['calibrate_magnetometer',['../class_b_n_o08x.html#ac26350b55095a346d72598ab8aa74b4a',1,'BNO08x']]], + ['calibrate_5fplanar_5faccelerometer_4',['calibrate_planar_accelerometer',['../class_b_n_o08x.html#a1c6c49c97bc098db89db1aaa37e18f26',1,'BNO08x']]], + ['calibration_5fcomplete_5',['calibration_complete',['../class_b_n_o08x.html#a71ca35f78b98d93d31eb0c187dc8543b',1,'BNO08x']]], + ['clear_5ftare_6',['clear_tare',['../class_b_n_o08x.html#afe39bfdede7b9a2b273983cb29a27d6e',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_2.js b/documentation/html/search/functions_2.js new file mode 100644 index 0000000..525877a --- /dev/null +++ b/documentation/html/search/functions_2.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['data_5favailable_0',['data_available',['../class_b_n_o08x.html#a367d525d1c0ba119b3dca3067bb5bccc',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_3.js b/documentation/html/search/functions_3.js new file mode 100644 index 0000000..fdaa4ea --- /dev/null +++ b/documentation/html/search/functions_3.js @@ -0,0 +1,22 @@ +var searchData= +[ + ['enable_5faccelerometer_0',['enable_accelerometer',['../class_b_n_o08x.html#a1d68494d911f7efbbb620d349fb9da0d',1,'BNO08x']]], + ['enable_5factivity_5fclassifier_1',['enable_activity_classifier',['../class_b_n_o08x.html#a0960ce957058af565dd4c43ad6c40225',1,'BNO08x']]], + ['enable_5farvr_5fstabilized_5fgame_5frotation_5fvector_2',['enable_ARVR_stabilized_game_rotation_vector',['../class_b_n_o08x.html#ad9e26658c53c728d7d10381db680765e',1,'BNO08x']]], + ['enable_5farvr_5fstabilized_5frotation_5fvector_3',['enable_ARVR_stabilized_rotation_vector',['../class_b_n_o08x.html#a04290cb6ba09b93d5a9ef337c13d1abb',1,'BNO08x']]], + ['enable_5fgame_5frotation_5fvector_4',['enable_game_rotation_vector',['../class_b_n_o08x.html#a639cb013ed17e0f33057742fac97f1a2',1,'BNO08x']]], + ['enable_5fgravity_5',['enable_gravity',['../class_b_n_o08x.html#a2dc0cd5bc04ca7eb3b4fffd2a3a6f27a',1,'BNO08x']]], + ['enable_5fgyro_6',['enable_gyro',['../class_b_n_o08x.html#a7619b598cc8e768c4df4805b2958a2c8',1,'BNO08x']]], + ['enable_5fgyro_5fintegrated_5frotation_5fvector_7',['enable_gyro_integrated_rotation_vector',['../class_b_n_o08x.html#a09a0306abec5895dd0450b2fe970347c',1,'BNO08x']]], + ['enable_5flinear_5faccelerometer_8',['enable_linear_accelerometer',['../class_b_n_o08x.html#ad3724e7e602feb2b695d2d88a61d5328',1,'BNO08x']]], + ['enable_5fmagnetometer_9',['enable_magnetometer',['../class_b_n_o08x.html#acf4a83a44a221f6495263f00f1b8d849',1,'BNO08x']]], + ['enable_5fraw_5faccelerometer_10',['enable_raw_accelerometer',['../class_b_n_o08x.html#ad6adf3b24a8a559d3bb57e6abcef4ce8',1,'BNO08x']]], + ['enable_5fraw_5fgyro_11',['enable_raw_gyro',['../class_b_n_o08x.html#af984deb77c92746fe4d193457312be63',1,'BNO08x']]], + ['enable_5fraw_5fmagnetometer_12',['enable_raw_magnetometer',['../class_b_n_o08x.html#ad1ca07ee06ef98d4e11a74dde18e9623',1,'BNO08x']]], + ['enable_5frotation_5fvector_13',['enable_rotation_vector',['../class_b_n_o08x.html#abe9acd2eb1ce2f2e72b7a48c8d025cc4',1,'BNO08x']]], + ['enable_5fstability_5fclassifier_14',['enable_stability_classifier',['../class_b_n_o08x.html#a5378a235e3114ccdc63b26bc3fae5dad',1,'BNO08x']]], + ['enable_5fstep_5fcounter_15',['enable_step_counter',['../class_b_n_o08x.html#ad550085fa1b51495ce3d8894538f33d5',1,'BNO08x']]], + ['enable_5ftap_5fdetector_16',['enable_tap_detector',['../class_b_n_o08x.html#a919c7d94226f4c6adbb8edf6fd1613a9',1,'BNO08x']]], + ['enable_5funcalibrated_5fgyro_17',['enable_uncalibrated_gyro',['../class_b_n_o08x.html#ac7b5815c5ad8b83a34ad0855423601e8',1,'BNO08x']]], + ['end_5fcalibration_18',['end_calibration',['../class_b_n_o08x.html#ac9d9b6636745e8180807284da67c92a2',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_4.js b/documentation/html/search/functions_4.js new file mode 100644 index 0000000..983b345 --- /dev/null +++ b/documentation/html/search/functions_4.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['frs_5fread_5fdata_0',['FRS_read_data',['../class_b_n_o08x.html#a40607e557eada666a5e1e416f42cd4a1',1,'BNO08x']]], + ['frs_5fread_5frequest_1',['FRS_read_request',['../class_b_n_o08x.html#adf789e709ac1667656db757c8d559af9',1,'BNO08x']]], + ['frs_5fread_5fword_2',['FRS_read_word',['../class_b_n_o08x.html#a27f5dce5c994be18a587fb622574ad41',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_5.js b/documentation/html/search/functions_5.js new file mode 100644 index 0000000..2719170 --- /dev/null +++ b/documentation/html/search/functions_5.js @@ -0,0 +1,74 @@ +var searchData= +[ + ['get_5faccel_0',['get_accel',['../class_b_n_o08x.html#a9329c6669282071622c3b3741b1b8142',1,'BNO08x']]], + ['get_5faccel_5faccuracy_1',['get_accel_accuracy',['../class_b_n_o08x.html#a3fce726d5de821f97ed207036dae2900',1,'BNO08x']]], + ['get_5faccel_5fx_2',['get_accel_X',['../class_b_n_o08x.html#abce574112a9079d2cbc58cfc352b8a69',1,'BNO08x']]], + ['get_5faccel_5fy_3',['get_accel_Y',['../class_b_n_o08x.html#afdf24bb3d54518b23972f21f007817c1',1,'BNO08x']]], + ['get_5faccel_5fz_4',['get_accel_Z',['../class_b_n_o08x.html#a0a72477cb7a330fedbcb3e2126b882b1',1,'BNO08x']]], + ['get_5factivity_5fclassifier_5',['get_activity_classifier',['../class_b_n_o08x.html#a4f7060b2d3c15b359b70b6346730446a',1,'BNO08x']]], + ['get_5fgravity_6',['get_gravity',['../class_b_n_o08x.html#a386c46ac8965220ab7b9423df838dd4d',1,'BNO08x']]], + ['get_5fgravity_5faccuracy_7',['get_gravity_accuracy',['../class_b_n_o08x.html#accd39f48e9f8ab8267df7184b5b7cd76',1,'BNO08x']]], + ['get_5fgravity_5fx_8',['get_gravity_X',['../class_b_n_o08x.html#a88679bccd9339b87ec35fc4fc4e745ae',1,'BNO08x']]], + ['get_5fgravity_5fy_9',['get_gravity_Y',['../class_b_n_o08x.html#a8a36db7f1c932f33e05e494632059801',1,'BNO08x']]], + ['get_5fgravity_5fz_10',['get_gravity_Z',['../class_b_n_o08x.html#a5622b4d1754648ea7eb400c1adf9e807',1,'BNO08x']]], + ['get_5fgyro_5faccuracy_11',['get_gyro_accuracy',['../class_b_n_o08x.html#a811999653110858311c97a779c388e5d',1,'BNO08x']]], + ['get_5fgyro_5fcalibrated_5fvelocity_12',['get_gyro_calibrated_velocity',['../class_b_n_o08x.html#a4d3746a376a22acb7a2641bb750c4c89',1,'BNO08x']]], + ['get_5fgyro_5fcalibrated_5fvelocity_5fx_13',['get_gyro_calibrated_velocity_X',['../class_b_n_o08x.html#ab7977391191067282e7f734b9ee45059',1,'BNO08x']]], + ['get_5fgyro_5fcalibrated_5fvelocity_5fy_14',['get_gyro_calibrated_velocity_Y',['../class_b_n_o08x.html#ad4fab6e636e239d4b9273f158983ed89',1,'BNO08x']]], + ['get_5fgyro_5fcalibrated_5fvelocity_5fz_15',['get_gyro_calibrated_velocity_Z',['../class_b_n_o08x.html#a15a29c3bb476048b7229abcfb2b1d52a',1,'BNO08x']]], + ['get_5fgyro_5fvelocity_16',['get_gyro_velocity',['../class_b_n_o08x.html#afe6392012669e7ebd1a9e817e2bd313f',1,'BNO08x']]], + ['get_5fgyro_5fvelocity_5fx_17',['get_gyro_velocity_X',['../class_b_n_o08x.html#acd376cd3e454a87198ec86accbf2ee00',1,'BNO08x']]], + ['get_5fgyro_5fvelocity_5fy_18',['get_gyro_velocity_Y',['../class_b_n_o08x.html#acd1819a81818f90dc105950b4a7d0b04',1,'BNO08x']]], + ['get_5fgyro_5fvelocity_5fz_19',['get_gyro_velocity_Z',['../class_b_n_o08x.html#ae2add976af256ec981248371a2f58207',1,'BNO08x']]], + ['get_5flinear_5faccel_20',['get_linear_accel',['../class_b_n_o08x.html#ad59b029d04341dbef72e059488951980',1,'BNO08x']]], + ['get_5flinear_5faccel_5faccuracy_21',['get_linear_accel_accuracy',['../class_b_n_o08x.html#a33fe3c2f47759cfae5f4b612ddd329ea',1,'BNO08x']]], + ['get_5flinear_5faccel_5fx_22',['get_linear_accel_X',['../class_b_n_o08x.html#a763c3a9699a1081d430fd9b9b7bc49a3',1,'BNO08x']]], + ['get_5flinear_5faccel_5fy_23',['get_linear_accel_Y',['../class_b_n_o08x.html#a1033bdd65b42b6706d1dfc67ece66191',1,'BNO08x']]], + ['get_5flinear_5faccel_5fz_24',['get_linear_accel_Z',['../class_b_n_o08x.html#afdfa7d50362702da689c5d18bf17fd84',1,'BNO08x']]], + ['get_5fmagf_25',['get_magf',['../class_b_n_o08x.html#a35a224d519a2a243d0d526a34ecde5a8',1,'BNO08x']]], + ['get_5fmagf_5faccuracy_26',['get_magf_accuracy',['../class_b_n_o08x.html#a487391e6b2dd7f05084804d1fb94976f',1,'BNO08x']]], + ['get_5fmagf_5fx_27',['get_magf_X',['../class_b_n_o08x.html#a111601243b913751eb51c1f37cba4e7d',1,'BNO08x']]], + ['get_5fmagf_5fy_28',['get_magf_Y',['../class_b_n_o08x.html#a82ed8d7b9a5c25374839df75a3d220ea',1,'BNO08x']]], + ['get_5fmagf_5fz_29',['get_magf_Z',['../class_b_n_o08x.html#ab4c48a91d2f8b29430abc17b7f015282',1,'BNO08x']]], + ['get_5fpitch_30',['get_pitch',['../class_b_n_o08x.html#a1b91f234d81c45f1f5ca2f27c9f0f6a3',1,'BNO08x']]], + ['get_5fpitch_5fdeg_31',['get_pitch_deg',['../class_b_n_o08x.html#af50010400cbd1445e9ddfa259384b412',1,'BNO08x']]], + ['get_5fq1_32',['get_Q1',['../class_b_n_o08x.html#a4421c43323945946ad605f8422958dcf',1,'BNO08x']]], + ['get_5fq2_33',['get_Q2',['../class_b_n_o08x.html#a954dccdcbe8a8c4f1787f13ebb8d932b',1,'BNO08x']]], + ['get_5fq3_34',['get_Q3',['../class_b_n_o08x.html#a1590ba793668f9cb1a32a1f4dd07cb9a',1,'BNO08x']]], + ['get_5fquat_35',['get_quat',['../class_b_n_o08x.html#a51a6d594824de2292e70f788454f8a2d',1,'BNO08x']]], + ['get_5fquat_5faccuracy_36',['get_quat_accuracy',['../class_b_n_o08x.html#a24ba760d064a1dc45f972c79b9c8d98d',1,'BNO08x']]], + ['get_5fquat_5fi_37',['get_quat_I',['../class_b_n_o08x.html#a12c12a8e078b28480fb8828d306656f5',1,'BNO08x']]], + ['get_5fquat_5fj_38',['get_quat_J',['../class_b_n_o08x.html#a9f6bb642fa0297a7b9bcc94dd7374015',1,'BNO08x']]], + ['get_5fquat_5fk_39',['get_quat_K',['../class_b_n_o08x.html#a9f42c70c2337a0d831064a40ecfe2dd8',1,'BNO08x']]], + ['get_5fquat_5fradian_5faccuracy_40',['get_quat_radian_accuracy',['../class_b_n_o08x.html#a61b7d10a98afc6903fea6b2cede27630',1,'BNO08x']]], + ['get_5fquat_5freal_41',['get_quat_real',['../class_b_n_o08x.html#a5a556c5ec1baaa7f1156779dbe47a7b7',1,'BNO08x']]], + ['get_5frange_42',['get_range',['../class_b_n_o08x.html#a0fff04c42c9502615ad73cd1457cb9b0',1,'BNO08x']]], + ['get_5fraw_5faccel_5fx_43',['get_raw_accel_X',['../class_b_n_o08x.html#a1de356dd604c1dffcd1a32faeb4fafe2',1,'BNO08x']]], + ['get_5fraw_5faccel_5fy_44',['get_raw_accel_Y',['../class_b_n_o08x.html#a96563de0eb597a52d595d19da827b1ac',1,'BNO08x']]], + ['get_5fraw_5faccel_5fz_45',['get_raw_accel_Z',['../class_b_n_o08x.html#a718cdd910e5e7e03fd0a1ad04ee6f0ce',1,'BNO08x']]], + ['get_5fraw_5fgyro_5fx_46',['get_raw_gyro_X',['../class_b_n_o08x.html#af1b2c3a383a84fc6dfaddae1052b44d4',1,'BNO08x']]], + ['get_5fraw_5fgyro_5fy_47',['get_raw_gyro_Y',['../class_b_n_o08x.html#aff7714441d242b3b9b0c03f94e0a9374',1,'BNO08x']]], + ['get_5fraw_5fgyro_5fz_48',['get_raw_gyro_Z',['../class_b_n_o08x.html#a2e28b5a79c442a6baa2fa5165b9ce37d',1,'BNO08x']]], + ['get_5fraw_5fmagf_5fx_49',['get_raw_magf_X',['../class_b_n_o08x.html#adf12600b39de41d258439a343fcc1ad8',1,'BNO08x']]], + ['get_5fraw_5fmagf_5fy_50',['get_raw_magf_Y',['../class_b_n_o08x.html#a2c842e43ceae19149f6525bcbc48f1cf',1,'BNO08x']]], + ['get_5fraw_5fmagf_5fz_51',['get_raw_magf_Z',['../class_b_n_o08x.html#a99c1bcc2ec3ca3d8feafd6dd61f9d269',1,'BNO08x']]], + ['get_5freadings_52',['get_readings',['../class_b_n_o08x.html#a9cc47f0e5b7d679c80992c993a910ccf',1,'BNO08x']]], + ['get_5freset_5freason_53',['get_reset_reason',['../class_b_n_o08x.html#a11bb1b3fa44ad8f28c1492b5c07af886',1,'BNO08x']]], + ['get_5fresolution_54',['get_resolution',['../class_b_n_o08x.html#a1d6ea02d0d4b23ff6a15e9d5c6c92372',1,'BNO08x']]], + ['get_5froll_55',['get_roll',['../class_b_n_o08x.html#a89618eba08186ee8e679e7313907ddef',1,'BNO08x']]], + ['get_5froll_5fdeg_56',['get_roll_deg',['../class_b_n_o08x.html#a7077b9a130f1dcf0192454e387968dd6',1,'BNO08x']]], + ['get_5fstability_5fclassifier_57',['get_stability_classifier',['../class_b_n_o08x.html#a0d148e00abcfeec48c689e3084a7e786',1,'BNO08x']]], + ['get_5fstep_5fcount_58',['get_step_count',['../class_b_n_o08x.html#adaff49f3d80fdd19fd4210f0c56d41ef',1,'BNO08x']]], + ['get_5ftap_5fdetector_59',['get_tap_detector',['../class_b_n_o08x.html#a4797ec731de4c158716da1a7af9d1602',1,'BNO08x']]], + ['get_5ftime_5fstamp_60',['get_time_stamp',['../class_b_n_o08x.html#ad9137777271421a58159f3fe5e05ed20',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_61',['get_uncalibrated_gyro',['../class_b_n_o08x.html#a1bd3c33e70354bd35a78b83b6786b531',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5faccuracy_62',['get_uncalibrated_gyro_accuracy',['../class_b_n_o08x.html#a3285613f18b2f2f4c3f9e6d5c971af10',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5fbias_5fx_63',['get_uncalibrated_gyro_bias_X',['../class_b_n_o08x.html#ad228cdf352b7ea95e484da993045a47b',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5fbias_5fy_64',['get_uncalibrated_gyro_bias_Y',['../class_b_n_o08x.html#a74725517129dd548c7a3de705d5861bd',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5fbias_5fz_65',['get_uncalibrated_gyro_bias_Z',['../class_b_n_o08x.html#a5050359272abd146ab3c7a6101effbd7',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5fx_66',['get_uncalibrated_gyro_X',['../class_b_n_o08x.html#a289ff66f51c94be62c4a556f3a5997bf',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5fy_67',['get_uncalibrated_gyro_Y',['../class_b_n_o08x.html#a1874e4bd457bb5b6ecc2c64039b88ba4',1,'BNO08x']]], + ['get_5funcalibrated_5fgyro_5fz_68',['get_uncalibrated_gyro_Z',['../class_b_n_o08x.html#a0a73633d8929ce4058b14cefc8cad717',1,'BNO08x']]], + ['get_5fyaw_69',['get_yaw',['../class_b_n_o08x.html#a64d3e41750c6de9413d6982511f78f17',1,'BNO08x']]], + ['get_5fyaw_5fdeg_70',['get_yaw_deg',['../class_b_n_o08x.html#af80f7795656e695e036d3b1557aed94c',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_6.js b/documentation/html/search/functions_6.js new file mode 100644 index 0000000..0c3122f --- /dev/null +++ b/documentation/html/search/functions_6.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['hard_5freset_0',['hard_reset',['../class_b_n_o08x.html#a28cd1c0b3477571d87133234e6358503',1,'BNO08x']]], + ['hint_5fhandler_1',['hint_handler',['../class_b_n_o08x.html#a804b95c58c30d36933fd251626b85bf7',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_7.js b/documentation/html/search/functions_7.js new file mode 100644 index 0000000..5215833 --- /dev/null +++ b/documentation/html/search/functions_7.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['initialize_0',['initialize',['../class_b_n_o08x.html#aea8e2c6dd7a2c9899479a7f39fe94798',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_8.js b/documentation/html/search/functions_8.js new file mode 100644 index 0000000..2b8cc0c --- /dev/null +++ b/documentation/html/search/functions_8.js @@ -0,0 +1,5 @@ +var searchData= +[ + ['mode_5fon_0',['mode_on',['../class_b_n_o08x.html#ac1b3de9b552c611ee9c455d7f19be698',1,'BNO08x']]], + ['mode_5fsleep_1',['mode_sleep',['../class_b_n_o08x.html#a176ae0112325c05105eacb4566bbfa0b',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_9.js b/documentation/html/search/functions_9.js new file mode 100644 index 0000000..475a0c5 --- /dev/null +++ b/documentation/html/search/functions_9.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['parse_5fcommand_5freport_0',['parse_command_report',['../class_b_n_o08x.html#a3762125be0025a335f0d918415f4ce18',1,'BNO08x']]], + ['parse_5finput_5freport_1',['parse_input_report',['../class_b_n_o08x.html#a7ba1d779ed68edf30090dd0f938a5709',1,'BNO08x']]], + ['print_5fheader_2',['print_header',['../class_b_n_o08x.html#a08f037df7b3c7e2fc3f0e968f4a5f68c',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_a.js b/documentation/html/search/functions_a.js new file mode 100644 index 0000000..2ec56f8 --- /dev/null +++ b/documentation/html/search/functions_a.js @@ -0,0 +1,10 @@ +var searchData= +[ + ['q_5fto_5ffloat_0',['q_to_float',['../class_b_n_o08x.html#a27fb24e894f794ec6228ef142b6ff8d9',1,'BNO08x']]], + ['queue_5fcalibrate_5fcommand_1',['queue_calibrate_command',['../class_b_n_o08x.html#ad097849616c5caab1fd3eb3632ee2b91',1,'BNO08x']]], + ['queue_5fcommand_2',['queue_command',['../class_b_n_o08x.html#a1742d6445ffb6e9297b8bf84dec24f22',1,'BNO08x']]], + ['queue_5ffeature_5fcommand_3',['queue_feature_command',['../class_b_n_o08x.html#a6c004a16b146527aa9eeeb6ff37db281',1,'BNO08x::queue_feature_command(uint8_t report_ID, uint16_t time_between_reports)'],['../class_b_n_o08x.html#af0a0686a78c929aad43af2eaeba12878',1,'BNO08x::queue_feature_command(uint8_t report_ID, uint16_t time_between_reports, uint32_t specific_config)']]], + ['queue_5fpacket_4',['queue_packet',['../class_b_n_o08x.html#a67d0b5302a60083cef1b31936e2b65d8',1,'BNO08x']]], + ['queue_5frequest_5fproduct_5fid_5fcommand_5',['queue_request_product_id_command',['../class_b_n_o08x.html#ab5f200069a2f8cb74cb79c6f162da5a1',1,'BNO08x']]], + ['queue_5ftare_5fcommand_6',['queue_tare_command',['../class_b_n_o08x.html#a4c6353e795f734ed28613f9a3d161ea2',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_b.js b/documentation/html/search/functions_b.js new file mode 100644 index 0000000..1678ee0 --- /dev/null +++ b/documentation/html/search/functions_b.js @@ -0,0 +1,6 @@ +var searchData= +[ + ['receive_5fpacket_0',['receive_packet',['../class_b_n_o08x.html#ae540799865934fcff54caed0772df071',1,'BNO08x']]], + ['request_5fcalibration_5fstatus_1',['request_calibration_status',['../class_b_n_o08x.html#affaaa35abbb872da5299ebab6e2c9b11',1,'BNO08x']]], + ['run_5ffull_5fcalibration_5froutine_2',['run_full_calibration_routine',['../class_b_n_o08x.html#ae6e875a27ae74ebed806ee1a4576845a',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_c.js b/documentation/html/search/functions_c.js new file mode 100644 index 0000000..6d61e15 --- /dev/null +++ b/documentation/html/search/functions_c.js @@ -0,0 +1,9 @@ +var searchData= +[ + ['save_5fcalibration_0',['save_calibration',['../class_b_n_o08x.html#aa16609de88bfb7b389348859aa0cee54',1,'BNO08x']]], + ['save_5ftare_1',['save_tare',['../class_b_n_o08x.html#afb2ffc4e7ff0498917bc14a83af306e2',1,'BNO08x']]], + ['send_5fpacket_2',['send_packet',['../class_b_n_o08x.html#a0ee58cedbc06d4a7db8821f40c0ee207',1,'BNO08x']]], + ['soft_5freset_3',['soft_reset',['../class_b_n_o08x.html#a973a1b1785f3302ee1b2702c6a27646e',1,'BNO08x']]], + ['spi_5ftask_4',['spi_task',['../class_b_n_o08x.html#a2ecd4ed60f82730ae230c61687ec92bf',1,'BNO08x']]], + ['spi_5ftask_5ftrampoline_5',['spi_task_trampoline',['../class_b_n_o08x.html#a0ce6d9db873555f1ebe7e095251eab74',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_d.js b/documentation/html/search/functions_d.js new file mode 100644 index 0000000..7e8b9f8 --- /dev/null +++ b/documentation/html/search/functions_d.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['tare_5fnow_0',['tare_now',['../class_b_n_o08x.html#a4549bbef48208bd9c745fc755b93012f',1,'BNO08x']]] +]; diff --git a/documentation/html/search/functions_e.js b/documentation/html/search/functions_e.js new file mode 100644 index 0000000..1e57a56 --- /dev/null +++ b/documentation/html/search/functions_e.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['wait_5ffor_5fdevice_5fint_0',['wait_for_device_int',['../class_b_n_o08x.html#a988c45b4afa4dcd6a24610ff308c1faa',1,'BNO08x']]] +]; diff --git a/documentation/html/search/mag.svg b/documentation/html/search/mag.svg new file mode 100644 index 0000000..ffb6cf0 --- /dev/null +++ b/documentation/html/search/mag.svg @@ -0,0 +1,24 @@ + + + + + + + diff --git a/documentation/html/search/mag_d.svg b/documentation/html/search/mag_d.svg new file mode 100644 index 0000000..4122773 --- /dev/null +++ b/documentation/html/search/mag_d.svg @@ -0,0 +1,24 @@ + + + + + + + diff --git a/documentation/html/search/mag_sel.svg b/documentation/html/search/mag_sel.svg new file mode 100644 index 0000000..553dba8 --- /dev/null +++ b/documentation/html/search/mag_sel.svg @@ -0,0 +1,31 @@ + + + + + + + + + diff --git a/documentation/html/search/mag_seld.svg b/documentation/html/search/mag_seld.svg new file mode 100644 index 0000000..c906f84 --- /dev/null +++ b/documentation/html/search/mag_seld.svg @@ -0,0 +1,31 @@ + + + + + + + + + diff --git a/documentation/html/search/pages_0.js b/documentation/html/search/pages_0.js new file mode 100644 index 0000000..92dba20 --- /dev/null +++ b/documentation/html/search/pages_0.js @@ -0,0 +1,4 @@ +var searchData= +[ + ['readme_0',['README',['../md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e.html',1,'']]] +]; diff --git a/documentation/html/search/search.css b/documentation/html/search/search.css new file mode 100644 index 0000000..19f76f9 --- /dev/null +++ b/documentation/html/search/search.css @@ -0,0 +1,291 @@ +/*---------------- Search Box positioning */ + +#main-menu > li:last-child { + /* This
  • object is the parent of the search bar */ + display: flex; + justify-content: center; + align-items: center; + height: 36px; + margin-right: 1em; +} + +/*---------------- Search box styling */ + +.SRPage * { + font-weight: normal; + line-height: normal; +} + +dark-mode-toggle { + margin-left: 5px; + display: flex; + float: right; +} + +#MSearchBox { + display: inline-block; + white-space : nowrap; + background: var(--search-background-color); + border-radius: 0.65em; + box-shadow: var(--search-box-shadow); + z-index: 102; +} + +#MSearchBox .left { + display: inline-block; + vertical-align: middle; + height: 1.4em; +} + +#MSearchSelect { + display: inline-block; + vertical-align: middle; + width: 20px; + height: 19px; + background-image: var(--search-magnification-select-image); + margin: 0 0 0 0.3em; + padding: 0; +} + +#MSearchSelectExt { + display: inline-block; + vertical-align: middle; + width: 10px; + height: 19px; + background-image: var(--search-magnification-image); + margin: 0 0 0 0.5em; + padding: 0; +} + + +#MSearchField { + display: inline-block; + vertical-align: middle; + width: 7.5em; + height: 19px; + margin: 0 0.15em; + padding: 0; + line-height: 1em; + border:none; + color: var(--search-foreground-color); + outline: none; + font-family: var(--font-family-search); + -webkit-border-radius: 0px; + border-radius: 0px; + background: none; +} + +@media(hover: none) { + /* to avoid zooming on iOS */ + #MSearchField { + font-size: 16px; + } +} + +#MSearchBox .right { + display: inline-block; + vertical-align: middle; + width: 1.4em; + height: 1.4em; +} + +#MSearchClose { + display: none; + font-size: inherit; + background : none; + border: none; + margin: 0; + padding: 0; + outline: none; + +} + +#MSearchCloseImg { + padding: 0.3em; + margin: 0; +} + +.MSearchBoxActive #MSearchField { + color: var(--search-active-color); +} + + + +/*---------------- Search filter selection */ + +#MSearchSelectWindow { + display: none; + position: absolute; + left: 0; top: 0; + border: 1px solid var(--search-filter-border-color); + background-color: var(--search-filter-background-color); + z-index: 10001; + padding-top: 4px; + padding-bottom: 4px; + -moz-border-radius: 4px; + -webkit-border-top-left-radius: 4px; + -webkit-border-top-right-radius: 4px; + -webkit-border-bottom-left-radius: 4px; + -webkit-border-bottom-right-radius: 4px; + -webkit-box-shadow: 5px 5px 5px rgba(0, 0, 0, 0.15); +} + +.SelectItem { + font: 8pt var(--font-family-search); + padding-left: 2px; + padding-right: 12px; + border: 0px; +} + +span.SelectionMark { + margin-right: 4px; + font-family: var(--font-family-monospace); + outline-style: none; + text-decoration: none; +} + +a.SelectItem { + display: block; + outline-style: none; + color: var(--search-filter-foreground-color); + text-decoration: none; + padding-left: 6px; + padding-right: 12px; +} + +a.SelectItem:focus, +a.SelectItem:active { + color: var(--search-filter-foreground-color); + outline-style: none; + text-decoration: none; +} + +a.SelectItem:hover { + color: var(--search-filter-highlight-text-color); + background-color: var(--search-filter-highlight-bg-color); + outline-style: none; + text-decoration: none; + cursor: pointer; + display: block; +} + +/*---------------- Search results window */ + +iframe#MSearchResults { + /*width: 60ex;*/ + height: 15em; +} + +#MSearchResultsWindow { + display: none; + position: absolute; + left: 0; top: 0; + border: 1px solid var(--search-results-border-color); + background-color: var(--search-results-background-color); + z-index:10000; + width: 300px; + height: 400px; + overflow: auto; +} + +/* ----------------------------------- */ + + +#SRIndex { + clear:both; +} + +.SREntry { + font-size: 10pt; + padding-left: 1ex; +} + +.SRPage .SREntry { + font-size: 8pt; + padding: 1px 5px; +} + +div.SRPage { + margin: 5px 2px; + background-color: var(--search-results-background-color); +} + +.SRChildren { + padding-left: 3ex; padding-bottom: .5em +} + +.SRPage .SRChildren { + display: none; +} + +.SRSymbol { + font-weight: bold; + color: var(--search-results-foreground-color); + font-family: var(--font-family-search); + text-decoration: none; + outline: none; +} + +a.SRScope { + display: block; + color: var(--search-results-foreground-color); + font-family: var(--font-family-search); + font-size: 8pt; + text-decoration: none; + outline: none; +} + +a.SRSymbol:focus, a.SRSymbol:active, +a.SRScope:focus, a.SRScope:active { + text-decoration: underline; +} + +span.SRScope { + padding-left: 4px; + font-family: var(--font-family-search); +} + +.SRPage .SRStatus { + padding: 2px 5px; + font-size: 8pt; + font-style: italic; + font-family: var(--font-family-search); +} + +.SRResult { + display: none; +} + +div.searchresults { + margin-left: 10px; + margin-right: 10px; +} + +/*---------------- External search page results */ + +.pages b { + color: white; + padding: 5px 5px 3px 5px; + background-image: var(--nav-gradient-active-image-parent); + background-repeat: repeat-x; + text-shadow: 0 1px 1px #000000; +} + +.pages { + line-height: 17px; + margin-left: 4px; + text-decoration: none; +} + +.hl { + font-weight: bold; +} + +#searchresults { + margin-bottom: 20px; +} + +.searchpages { + margin-top: 10px; +} + diff --git a/documentation/html/search/search.js b/documentation/html/search/search.js new file mode 100644 index 0000000..9b7a52a --- /dev/null +++ b/documentation/html/search/search.js @@ -0,0 +1,820 @@ +/* + @licstart The following is the entire license notice for the JavaScript code in this file. + + The MIT License (MIT) + + Copyright (C) 1997-2020 by Dimitri van Heesch + + Permission is hereby granted, free of charge, to any person obtaining a copy of this software + and associated documentation files (the "Software"), to deal in the Software without restriction, + including without limitation the rights to use, copy, modify, merge, publish, distribute, + sublicense, and/or sell copies of the Software, and to permit persons to whom the Software is + furnished to do so, subject to the following conditions: + + The above copyright notice and this permission notice shall be included in all copies or + substantial portions of the Software. + + THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR IMPLIED, INCLUDING + BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, FITNESS FOR A PARTICULAR PURPOSE AND + NONINFRINGEMENT. IN NO EVENT SHALL THE AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, + DAMAGES OR OTHER LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM, + OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE SOFTWARE. + + @licend The above is the entire license notice for the JavaScript code in this file + */ +function convertToId(search) +{ + var result = ''; + for (i=0;i do a search + { + this.Search(); + } + } + + this.OnSearchSelectKey = function(evt) + { + var e = (evt) ? evt : window.event; // for IE + if (e.keyCode==40 && this.searchIndex0) // Up + { + this.searchIndex--; + this.OnSelectItem(this.searchIndex); + } + else if (e.keyCode==13 || e.keyCode==27) + { + this.OnSelectItem(this.searchIndex); + this.CloseSelectionWindow(); + this.DOMSearchField().focus(); + } + return false; + } + + // --------- Actions + + // Closes the results window. + this.CloseResultsWindow = function() + { + this.DOMPopupSearchResultsWindow().style.display = 'none'; + this.DOMSearchClose().style.display = 'none'; + this.Activate(false); + } + + this.CloseSelectionWindow = function() + { + this.DOMSearchSelectWindow().style.display = 'none'; + } + + // Performs a search. + this.Search = function() + { + this.keyTimeout = 0; + + // strip leading whitespace + var searchValue = this.DOMSearchField().value.replace(/^ +/, ""); + + var code = searchValue.toLowerCase().charCodeAt(0); + var idxChar = searchValue.substr(0, 1).toLowerCase(); + if ( 0xD800 <= code && code <= 0xDBFF && searchValue > 1) // surrogate pair + { + idxChar = searchValue.substr(0, 2); + } + + var jsFile; + + var idx = indexSectionsWithContent[this.searchIndex].indexOf(idxChar); + if (idx!=-1) + { + var hexCode=idx.toString(16); + jsFile = this.resultsPath + indexSectionNames[this.searchIndex] + '_' + hexCode + '.js'; + } + + var loadJS = function(url, impl, loc){ + var scriptTag = document.createElement('script'); + scriptTag.src = url; + scriptTag.onload = impl; + scriptTag.onreadystatechange = impl; + loc.appendChild(scriptTag); + } + + var domPopupSearchResultsWindow = this.DOMPopupSearchResultsWindow(); + var domSearchBox = this.DOMSearchBox(); + var domPopupSearchResults = this.DOMPopupSearchResults(); + var domSearchClose = this.DOMSearchClose(); + var resultsPath = this.resultsPath; + + var handleResults = function() { + document.getElementById("Loading").style.display="none"; + if (typeof searchData !== 'undefined') { + createResults(resultsPath); + document.getElementById("NoMatches").style.display="none"; + } + + if (idx!=-1) { + searchResults.Search(searchValue); + } else { // no file with search results => force empty search results + searchResults.Search('===='); + } + + if (domPopupSearchResultsWindow.style.display!='block') + { + domSearchClose.style.display = 'inline-block'; + var left = getXPos(domSearchBox) + 150; + var top = getYPos(domSearchBox) + 20; + domPopupSearchResultsWindow.style.display = 'block'; + left -= domPopupSearchResults.offsetWidth; + var maxWidth = document.body.clientWidth; + var maxHeight = document.body.clientHeight; + var width = 300; + if (left<10) left=10; + if (width+left+8>maxWidth) width=maxWidth-left-8; + var height = 400; + if (height+top+8>maxHeight) height=maxHeight-top-8; + domPopupSearchResultsWindow.style.top = top + 'px'; + domPopupSearchResultsWindow.style.left = left + 'px'; + domPopupSearchResultsWindow.style.width = width + 'px'; + domPopupSearchResultsWindow.style.height = height + 'px'; + } + } + + if (jsFile) { + loadJS(jsFile, handleResults, this.DOMPopupSearchResultsWindow()); + } else { + handleResults(); + } + + this.lastSearchValue = searchValue; + } + + // -------- Activation Functions + + // Activates or deactivates the search panel, resetting things to + // their default values if necessary. + this.Activate = function(isActive) + { + if (isActive || // open it + this.DOMPopupSearchResultsWindow().style.display == 'block' + ) + { + this.DOMSearchBox().className = 'MSearchBoxActive'; + this.searchActive = true; + } + else if (!isActive) // directly remove the panel + { + this.DOMSearchBox().className = 'MSearchBoxInactive'; + this.searchActive = false; + this.lastSearchValue = '' + this.lastResultsPage = ''; + this.DOMSearchField().value = ''; + } + } +} + +// ----------------------------------------------------------------------- + +// The class that handles everything on the search results page. +function SearchResults(name) +{ + // The number of matches from the last run of . + this.lastMatchCount = 0; + this.lastKey = 0; + this.repeatOn = false; + + // Toggles the visibility of the passed element ID. + this.FindChildElement = function(id) + { + var parentElement = document.getElementById(id); + var element = parentElement.firstChild; + + while (element && element!=parentElement) + { + if (element.nodeName.toLowerCase() == 'div' && element.className == 'SRChildren') + { + return element; + } + + if (element.nodeName.toLowerCase() == 'div' && element.hasChildNodes()) + { + element = element.firstChild; + } + else if (element.nextSibling) + { + element = element.nextSibling; + } + else + { + do + { + element = element.parentNode; + } + while (element && element!=parentElement && !element.nextSibling); + + if (element && element!=parentElement) + { + element = element.nextSibling; + } + } + } + } + + this.Toggle = function(id) + { + var element = this.FindChildElement(id); + if (element) + { + if (element.style.display == 'block') + { + element.style.display = 'none'; + } + else + { + element.style.display = 'block'; + } + } + } + + // Searches for the passed string. If there is no parameter, + // it takes it from the URL query. + // + // Always returns true, since other documents may try to call it + // and that may or may not be possible. + this.Search = function(search) + { + if (!search) // get search word from URL + { + search = window.location.search; + search = search.substring(1); // Remove the leading '?' + search = unescape(search); + } + + search = search.replace(/^ +/, ""); // strip leading spaces + search = search.replace(/ +$/, ""); // strip trailing spaces + search = search.toLowerCase(); + search = convertToId(search); + + var resultRows = document.getElementsByTagName("div"); + var matches = 0; + + var i = 0; + while (i < resultRows.length) + { + var row = resultRows.item(i); + if (row.className == "SRResult") + { + var rowMatchName = row.id.toLowerCase(); + rowMatchName = rowMatchName.replace(/^sr\d*_/, ''); // strip 'sr123_' + + if (search.length<=rowMatchName.length && + rowMatchName.substr(0, search.length)==search) + { + row.style.display = 'block'; + matches++; + } + else + { + row.style.display = 'none'; + } + } + i++; + } + document.getElementById("Searching").style.display='none'; + if (matches == 0) // no results + { + document.getElementById("NoMatches").style.display='block'; + } + else // at least one result + { + document.getElementById("NoMatches").style.display='none'; + } + this.lastMatchCount = matches; + return true; + } + + // return the first item with index index or higher that is visible + this.NavNext = function(index) + { + var focusItem; + while (1) + { + var focusName = 'Item'+index; + focusItem = document.getElementById(focusName); + if (focusItem && focusItem.parentNode.parentNode.style.display=='block') + { + break; + } + else if (!focusItem) // last element + { + break; + } + focusItem=null; + index++; + } + return focusItem; + } + + this.NavPrev = function(index) + { + var focusItem; + while (1) + { + var focusName = 'Item'+index; + focusItem = document.getElementById(focusName); + if (focusItem && focusItem.parentNode.parentNode.style.display=='block') + { + break; + } + else if (!focusItem) // last element + { + break; + } + focusItem=null; + index--; + } + return focusItem; + } + + this.ProcessKeys = function(e) + { + if (e.type == "keydown") + { + this.repeatOn = false; + this.lastKey = e.keyCode; + } + else if (e.type == "keypress") + { + if (!this.repeatOn) + { + if (this.lastKey) this.repeatOn = true; + return false; // ignore first keypress after keydown + } + } + else if (e.type == "keyup") + { + this.lastKey = 0; + this.repeatOn = false; + } + return this.lastKey!=0; + } + + this.Nav = function(evt,itemIndex) + { + var e = (evt) ? evt : window.event; // for IE + if (e.keyCode==13) return true; + if (!this.ProcessKeys(e)) return false; + + if (this.lastKey==38) // Up + { + var newIndex = itemIndex-1; + var focusItem = this.NavPrev(newIndex); + if (focusItem) + { + var child = this.FindChildElement(focusItem.parentNode.parentNode.id); + if (child && child.style.display == 'block') // children visible + { + var n=0; + var tmpElem; + while (1) // search for last child + { + tmpElem = document.getElementById('Item'+newIndex+'_c'+n); + if (tmpElem) + { + focusItem = tmpElem; + } + else // found it! + { + break; + } + n++; + } + } + } + if (focusItem) + { + focusItem.focus(); + } + else // return focus to search field + { + document.getElementById("MSearchField").focus(); + } + } + else if (this.lastKey==40) // Down + { + var newIndex = itemIndex+1; + var focusItem; + var item = document.getElementById('Item'+itemIndex); + var elem = this.FindChildElement(item.parentNode.parentNode.id); + if (elem && elem.style.display == 'block') // children visible + { + focusItem = document.getElementById('Item'+itemIndex+'_c0'); + } + if (!focusItem) focusItem = this.NavNext(newIndex); + if (focusItem) focusItem.focus(); + } + else if (this.lastKey==39) // Right + { + var item = document.getElementById('Item'+itemIndex); + var elem = this.FindChildElement(item.parentNode.parentNode.id); + if (elem) elem.style.display = 'block'; + } + else if (this.lastKey==37) // Left + { + var item = document.getElementById('Item'+itemIndex); + var elem = this.FindChildElement(item.parentNode.parentNode.id); + if (elem) elem.style.display = 'none'; + } + else if (this.lastKey==27) // Escape + { + searchBox.CloseResultsWindow(); + document.getElementById("MSearchField").focus(); + } + else if (this.lastKey==13) // Enter + { + return true; + } + return false; + } + + this.NavChild = function(evt,itemIndex,childIndex) + { + var e = (evt) ? evt : window.event; // for IE + if (e.keyCode==13) return true; + if (!this.ProcessKeys(e)) return false; + + if (this.lastKey==38) // Up + { + if (childIndex>0) + { + var newIndex = childIndex-1; + document.getElementById('Item'+itemIndex+'_c'+newIndex).focus(); + } + else // already at first child, jump to parent + { + document.getElementById('Item'+itemIndex).focus(); + } + } + else if (this.lastKey==40) // Down + { + var newIndex = childIndex+1; + var elem = document.getElementById('Item'+itemIndex+'_c'+newIndex); + if (!elem) // last child, jump to parent next parent + { + elem = this.NavNext(itemIndex+1); + } + if (elem) + { + elem.focus(); + } + } + else if (this.lastKey==27) // Escape + { + searchBox.CloseResultsWindow(); + document.getElementById("MSearchField").focus(); + } + else if (this.lastKey==13) // Enter + { + return true; + } + return false; + } +} + +function setKeyActions(elem,action) +{ + elem.setAttribute('onkeydown',action); + elem.setAttribute('onkeypress',action); + elem.setAttribute('onkeyup',action); +} + +function setClassAttr(elem,attr) +{ + elem.setAttribute('class',attr); + elem.setAttribute('className',attr); +} + +function createResults(resultsPath) +{ + var results = document.getElementById("SRResults"); + results.innerHTML = ''; + for (var e=0; e + + + + + + +esp32_BNO08x: Member List + + + + + + + + + +
    +
    + + + + + + +
    +
    esp32_BNO08x 1.00 +
    +
    C++ BNO08x IMU driver component for esp-idf.
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    +
    bno08x_config_t Member List
    +
    + + + + + diff --git a/documentation/html/structbno08x__config__t.html b/documentation/html/structbno08x__config__t.html new file mode 100644 index 0000000..0dfbc23 --- /dev/null +++ b/documentation/html/structbno08x__config__t.html @@ -0,0 +1,164 @@ + + + + + + + +esp32_BNO08x: bno08x_config_t Struct Reference + + + + + + + + + +
    +
    + + + + + + +
    +
    esp32_BNO08x 1.00 +
    +
    C++ BNO08x IMU driver component for esp-idf.
    +
    +
    + + + + + + + + +
    +
    + + +
    +
    +
    +
    +
    +
    Loading...
    +
    Searching...
    +
    No Matches
    +
    +
    +
    +
    + +
    +
    + +
    bno08x_config_t Struct Reference
    +
    +
    + +

    IMU configuration settings passed into constructor. + More...

    + +

    #include <BNO08x.hpp>

    + + + + + +

    +Public Member Functions

    bno08x_config_t ()
     Default IMU configuration settings
    +
     
    + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + +

    +Public Attributes

    +spi_host_device_t spi_peripheral
     SPI peripheral to be used.
     
    +gpio_num_t io_mosi
     MOSI GPIO pin (connects to BNO08x DI pin)
     
    +gpio_num_t io_miso
     MISO GPIO pin (connects to BNO08x SDA pin)
     
    +gpio_num_t io_sclk
     SCLK pin (connects to BNO08x SCL pin)
     
    +gpio_num_t io_cs
     
    +gpio_num_t io_int
     Chip select pin (connects to BNO08x CS pin)
     
    +gpio_num_t io_rst
     Host interrupt pin (connects to BNO08x INT pin)
     
    gpio_num_t io_wake
     Reset pin (connects to BNO08x RST pin)
     
    +uint64_t sclk_speed
     Desired SPI SCLK speed in Hz (max 3MHz)
     
    +bool debug_en
     Whether or not debugging print statements are enabled.
     
    +

    Detailed Description

    +

    IMU configuration settings passed into constructor.

    +

    Member Data Documentation

    + +

    ◆ io_wake

    + +
    +
    + + + + +
    gpio_num_t bno08x_config_t::io_wake
    +
    + +

    Reset pin (connects to BNO08x RST pin)

    +

    Wake pin (optional, connects to BNO08x P0)

    + +
    +
    +
    The documentation for this struct was generated from the following file: +
    + + + + diff --git a/documentation/html/sync_off.png b/documentation/html/sync_off.png new file mode 100644 index 0000000..3b443fc Binary files /dev/null and b/documentation/html/sync_off.png differ diff --git a/documentation/html/sync_on.png b/documentation/html/sync_on.png new file mode 100644 index 0000000..e08320f Binary files /dev/null and b/documentation/html/sync_on.png differ diff --git a/documentation/html/tab_a.png b/documentation/html/tab_a.png new file mode 100644 index 0000000..3b725c4 Binary files /dev/null and b/documentation/html/tab_a.png differ diff --git a/documentation/html/tab_ad.png b/documentation/html/tab_ad.png new file mode 100644 index 0000000..e34850a Binary files /dev/null and b/documentation/html/tab_ad.png differ diff --git a/documentation/html/tab_b.png b/documentation/html/tab_b.png new file mode 100644 index 0000000..e2b4a86 Binary files /dev/null and b/documentation/html/tab_b.png differ diff --git a/documentation/html/tab_bd.png b/documentation/html/tab_bd.png new file mode 100644 index 0000000..91c2524 Binary files /dev/null and b/documentation/html/tab_bd.png differ diff --git a/documentation/html/tab_h.png b/documentation/html/tab_h.png new file mode 100644 index 0000000..fd5cb70 Binary files /dev/null and b/documentation/html/tab_h.png differ diff --git a/documentation/html/tab_hd.png b/documentation/html/tab_hd.png new file mode 100644 index 0000000..2489273 Binary files /dev/null and b/documentation/html/tab_hd.png differ diff --git a/documentation/html/tab_s.png b/documentation/html/tab_s.png new file mode 100644 index 0000000..ab478c9 Binary files /dev/null and b/documentation/html/tab_s.png differ diff --git a/documentation/html/tab_sd.png b/documentation/html/tab_sd.png new file mode 100644 index 0000000..757a565 Binary files /dev/null and b/documentation/html/tab_sd.png differ diff --git a/documentation/html/tabs.css b/documentation/html/tabs.css new file mode 100644 index 0000000..71c8a47 --- /dev/null +++ b/documentation/html/tabs.css @@ -0,0 +1 @@ +.sm{position:relative;z-index:9999}.sm,.sm ul,.sm li{display:block;list-style:none;margin:0;padding:0;line-height:normal;direction:ltr;text-align:left;-webkit-tap-highlight-color:rgba(0,0,0,0)}.sm-rtl,.sm-rtl ul,.sm-rtl li{direction:rtl;text-align:right}.sm>li>h1,.sm>li>h2,.sm>li>h3,.sm>li>h4,.sm>li>h5,.sm>li>h6{margin:0;padding:0}.sm ul{display:none}.sm li,.sm a{position:relative}.sm a{display:block}.sm a.disabled{cursor:not-allowed}.sm:after{content:"\00a0";display:block;height:0;font:0/0 serif;clear:both;visibility:hidden;overflow:hidden}.sm,.sm *,.sm *:before,.sm *:after{-moz-box-sizing:border-box;-webkit-box-sizing:border-box;box-sizing:border-box}.main-menu-btn{position:relative;display:inline-block;width:36px;height:36px;text-indent:36px;margin-left:8px;white-space:nowrap;overflow:hidden;cursor:pointer;-webkit-tap-highlight-color:rgba(0,0,0,0)}.main-menu-btn-icon,.main-menu-btn-icon:before,.main-menu-btn-icon:after{position:absolute;top:50%;left:2px;height:2px;width:24px;background:var(--nav-menu-button-color);-webkit-transition:all .25s;transition:all .25s}.main-menu-btn-icon:before{content:'';top:-7px;left:0}.main-menu-btn-icon:after{content:'';top:7px;left:0}#main-menu-state:checked ~ .main-menu-btn .main-menu-btn-icon{height:0}#main-menu-state:checked ~ .main-menu-btn .main-menu-btn-icon:before{top:0;-webkit-transform:rotate(-45deg);transform:rotate(-45deg)}#main-menu-state:checked ~ .main-menu-btn .main-menu-btn-icon:after{top:0;-webkit-transform:rotate(45deg);transform:rotate(45deg)}#main-menu-state{position:absolute;width:1px;height:1px;margin:-1px;border:0;padding:0;overflow:hidden;clip:rect(1px,1px,1px,1px)}#main-menu-state:not(:checked) ~ #main-menu{display:none}#main-menu-state:checked ~ #main-menu{display:block}@media(min-width:768px){.main-menu-btn{position:absolute;top:-99999px}#main-menu-state:not(:checked) ~ #main-menu{display:block}}.sm-dox{background-image:var(--nav-gradient-image)}.sm-dox a,.sm-dox a:focus,.sm-dox a:hover,.sm-dox a:active{padding:0 12px;padding-right:43px;font-family:var(--font-family-nav);font-size:13px;font-weight:bold;line-height:36px;text-decoration:none;text-shadow:var(--nav-text-normal-shadow);color:var(--nav-text-normal-color);outline:0}.sm-dox a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:var(--nav-text-hover-shadow)}.sm-dox a.current{color:#d23600}.sm-dox a.disabled{color:#bbb}.sm-dox a span.sub-arrow{position:absolute;top:50%;margin-top:-14px;left:auto;right:3px;width:28px;height:28px;overflow:hidden;font:bold 12px/28px monospace !important;text-align:center;text-shadow:none;background:var(--nav-menu-toggle-color);-moz-border-radius:5px;-webkit-border-radius:5px;border-radius:5px}.sm-dox a span.sub-arrow:before{display:block;content:'+'}.sm-dox a.highlighted span.sub-arrow:before{display:block;content:'-'}.sm-dox>li:first-child>a,.sm-dox>li:first-child>:not(ul) a{-moz-border-radius:5px 5px 0 0;-webkit-border-radius:5px;border-radius:5px 5px 0 0}.sm-dox>li:last-child>a,.sm-dox>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul{-moz-border-radius:0 0 5px 5px;-webkit-border-radius:0;border-radius:0 0 5px 5px}.sm-dox>li:last-child>a.highlighted,.sm-dox>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>a.highlighted,.sm-dox>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>ul>li:last-child>*:not(ul) a.highlighted{-moz-border-radius:0;-webkit-border-radius:0;border-radius:0}.sm-dox ul{background:var(--nav-menu-background-color)}.sm-dox ul a,.sm-dox ul a:focus,.sm-dox ul a:hover,.sm-dox ul a:active{font-size:12px;border-left:8px solid transparent;line-height:36px;text-shadow:none;background-color:var(--nav-menu-background-color);background-image:none}.sm-dox ul a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:0 1px 1px black}.sm-dox ul ul a,.sm-dox ul ul a:hover,.sm-dox ul ul a:focus,.sm-dox ul ul a:active{border-left:16px solid transparent}.sm-dox ul ul ul a,.sm-dox ul ul ul a:hover,.sm-dox ul ul ul a:focus,.sm-dox ul ul ul a:active{border-left:24px solid transparent}.sm-dox ul ul ul ul a,.sm-dox ul ul ul ul a:hover,.sm-dox ul ul ul ul a:focus,.sm-dox ul ul ul ul a:active{border-left:32px solid transparent}.sm-dox ul ul ul ul ul a,.sm-dox ul ul ul ul ul a:hover,.sm-dox ul ul ul ul ul a:focus,.sm-dox ul ul ul ul ul a:active{border-left:40px solid transparent}@media(min-width:768px){.sm-dox ul{position:absolute;width:12em}.sm-dox li{float:left}.sm-dox.sm-rtl li{float:right}.sm-dox ul li,.sm-dox.sm-rtl ul li,.sm-dox.sm-vertical li{float:none}.sm-dox a{white-space:nowrap}.sm-dox ul a,.sm-dox.sm-vertical a{white-space:normal}.sm-dox .sm-nowrap>li>a,.sm-dox .sm-nowrap>li>:not(ul) a{white-space:nowrap}.sm-dox{padding:0 10px;background-image:var(--nav-gradient-image);line-height:36px}.sm-dox a span.sub-arrow{top:50%;margin-top:-2px;right:12px;width:0;height:0;border-width:4px;border-style:solid dashed dashed dashed;border-color:var(--nav-text-normal-color) transparent transparent transparent;background:transparent;-moz-border-radius:0;-webkit-border-radius:0;border-radius:0}.sm-dox a,.sm-dox a:focus,.sm-dox a:active,.sm-dox a:hover,.sm-dox a.highlighted{padding:0 12px;background-image:var(--nav-separator-image);background-repeat:no-repeat;background-position:right;-moz-border-radius:0 !important;-webkit-border-radius:0;border-radius:0 !important}.sm-dox a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:var(--nav-text-hover-shadow)}.sm-dox a:hover span.sub-arrow{border-color:var(--nav-text-hover-color) transparent transparent transparent}.sm-dox a.has-submenu{padding-right:24px}.sm-dox li{border-top:0}.sm-dox>li>ul:before,.sm-dox>li>ul:after{content:'';position:absolute;top:-18px;left:30px;width:0;height:0;overflow:hidden;border-width:9px;border-style:dashed dashed solid dashed;border-color:transparent transparent #bbb transparent}.sm-dox>li>ul:after{top:-16px;left:31px;border-width:8px;border-color:transparent transparent var(--nav-menu-background-color) transparent}.sm-dox ul{border:1px solid #bbb;padding:5px 0;background:var(--nav-menu-background-color);-moz-border-radius:5px !important;-webkit-border-radius:5px;border-radius:5px !important;-moz-box-shadow:0 5px 9px rgba(0,0,0,0.2);-webkit-box-shadow:0 5px 9px rgba(0,0,0,0.2);box-shadow:0 5px 9px rgba(0,0,0,0.2)}.sm-dox ul a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-color:transparent transparent transparent var(--nav-menu-foreground-color);border-style:dashed dashed dashed solid}.sm-dox ul a,.sm-dox ul a:hover,.sm-dox ul a:focus,.sm-dox ul a:active,.sm-dox ul a.highlighted{color:var(--nav-menu-foreground-color);background-image:none;border:0 !important;color:var(--nav-menu-foreground-color);background-image:none}.sm-dox ul a:hover{background-image:var(--nav-gradient-active-image);background-repeat:repeat-x;color:var(--nav-text-hover-color);text-shadow:var(--nav-text-hover-shadow)}.sm-dox ul a:hover span.sub-arrow{border-color:transparent transparent transparent var(--nav-text-hover-color)}.sm-dox span.scroll-up,.sm-dox span.scroll-down{position:absolute;display:none;visibility:hidden;overflow:hidden;background:var(--nav-menu-background-color);height:36px}.sm-dox span.scroll-up:hover,.sm-dox span.scroll-down:hover{background:#eee}.sm-dox span.scroll-up:hover span.scroll-up-arrow,.sm-dox span.scroll-up:hover span.scroll-down-arrow{border-color:transparent transparent #d23600 transparent}.sm-dox span.scroll-down:hover span.scroll-down-arrow{border-color:#d23600 transparent transparent transparent}.sm-dox span.scroll-up-arrow,.sm-dox span.scroll-down-arrow{position:absolute;top:0;left:50%;margin-left:-6px;width:0;height:0;overflow:hidden;border-width:6px;border-style:dashed dashed solid dashed;border-color:transparent transparent var(--nav-menu-foreground-color) transparent}.sm-dox span.scroll-down-arrow{top:8px;border-style:solid dashed dashed dashed;border-color:var(--nav-menu-foreground-color) transparent transparent transparent}.sm-dox.sm-rtl a.has-submenu{padding-right:12px;padding-left:24px}.sm-dox.sm-rtl a span.sub-arrow{right:auto;left:12px}.sm-dox.sm-rtl.sm-vertical a.has-submenu{padding:10px 20px}.sm-dox.sm-rtl.sm-vertical a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-rtl>li>ul:before{left:auto;right:30px}.sm-dox.sm-rtl>li>ul:after{left:auto;right:31px}.sm-dox.sm-rtl ul a.has-submenu{padding:10px 20px !important}.sm-dox.sm-rtl ul a span.sub-arrow{right:auto;left:8px;border-style:dashed solid dashed dashed;border-color:transparent #555 transparent transparent}.sm-dox.sm-vertical{padding:10px 0;-moz-border-radius:5px;-webkit-border-radius:5px;border-radius:5px}.sm-dox.sm-vertical a{padding:10px 20px}.sm-dox.sm-vertical a:hover,.sm-dox.sm-vertical a:focus,.sm-dox.sm-vertical a:active,.sm-dox.sm-vertical a.highlighted{background:#fff}.sm-dox.sm-vertical a.disabled{background-image:var(--nav-gradient-image)}.sm-dox.sm-vertical a span.sub-arrow{right:8px;top:50%;margin-top:-5px;border-width:5px;border-style:dashed dashed dashed solid;border-color:transparent transparent transparent #555}.sm-dox.sm-vertical>li>ul:before,.sm-dox.sm-vertical>li>ul:after{display:none}.sm-dox.sm-vertical ul a{padding:10px 20px}.sm-dox.sm-vertical ul a:hover,.sm-dox.sm-vertical ul a:focus,.sm-dox.sm-vertical ul a:active,.sm-dox.sm-vertical ul a.highlighted{background:#eee}.sm-dox.sm-vertical ul a.disabled{background:var(--nav-menu-background-color)}} \ No newline at end of file diff --git a/documentation/latex/Makefile b/documentation/latex/Makefile new file mode 100644 index 0000000..7f82972 --- /dev/null +++ b/documentation/latex/Makefile @@ -0,0 +1,27 @@ +LATEX_CMD?=pdflatex +MKIDX_CMD?=makeindex +BIBTEX_CMD?=bibtex +LATEX_COUNT?=8 +MANUAL_FILE?=refman + +all: $(MANUAL_FILE).pdf + +pdf: $(MANUAL_FILE).pdf + +$(MANUAL_FILE).pdf: clean $(MANUAL_FILE).tex + $(LATEX_CMD) $(MANUAL_FILE) + $(MKIDX_CMD) $(MANUAL_FILE).idx + $(LATEX_CMD) $(MANUAL_FILE) + latex_count=$(LATEX_COUNT) ; \ + while grep -E -s 'Rerun (LaTeX|to get cross-references right|to get bibliographical references right)' $(MANUAL_FILE).log && [ $$latex_count -gt 0 ] ;\ + do \ + echo "Rerunning latex...." ;\ + $(LATEX_CMD) $(MANUAL_FILE) ;\ + latex_count=`expr $$latex_count - 1` ;\ + done + $(MKIDX_CMD) $(MANUAL_FILE).idx + $(LATEX_CMD) $(MANUAL_FILE) + + +clean: + rm -f *.ps *.dvi *.aux *.toc *.idx *.ind *.ilg *.log *.out *.brf *.blg *.bbl $(MANUAL_FILE).pdf diff --git a/documentation/latex/_b_n_o08x_8hpp_source.tex b/documentation/latex/_b_n_o08x_8hpp_source.tex new file mode 100644 index 0000000..e62f6cc --- /dev/null +++ b/documentation/latex/_b_n_o08x_8hpp_source.tex @@ -0,0 +1,369 @@ +\doxysection{BNO08x.\+hpp} +\label{_b_n_o08x_8hpp_source}\index{D:/development/git/esp32\_BNO08x/BNO08x.hpp@{D:/development/git/esp32\_BNO08x/BNO08x.hpp}} + +\begin{DoxyCode}{0} +\DoxyCodeLine{00001\ \textcolor{preprocessor}{\#pragma\ once}} +\DoxyCodeLine{00002\ } +\DoxyCodeLine{00003\ \textcolor{comment}{//standard\ library\ includes}} +\DoxyCodeLine{00004\ \textcolor{preprocessor}{\#include\ }} +\DoxyCodeLine{00005\ \textcolor{preprocessor}{\#include\ }} +\DoxyCodeLine{00006\ \textcolor{preprocessor}{\#include\ }} +\DoxyCodeLine{00007\ \textcolor{preprocessor}{\#include\ }} +\DoxyCodeLine{00008\ } +\DoxyCodeLine{00009\ \textcolor{comment}{//esp-\/idf\ includes}} +\DoxyCodeLine{00010\ \textcolor{preprocessor}{\#include\ "{}driver/gpio.h"{}}} +\DoxyCodeLine{00011\ \textcolor{preprocessor}{\#include\ "{}esp\_rom\_gpio.h"{}}} +\DoxyCodeLine{00012\ \textcolor{preprocessor}{\#include\ "{}driver/spi\_common.h"{}}} +\DoxyCodeLine{00013\ \textcolor{preprocessor}{\#include\ "{}driver/spi\_master.h"{}}} +\DoxyCodeLine{00014\ \textcolor{preprocessor}{\#include\ "{}freertos/FreeRTOS.h"{}}} +\DoxyCodeLine{00015\ \textcolor{preprocessor}{\#include\ "{}freertos/task.h"{}}} +\DoxyCodeLine{00016\ \textcolor{preprocessor}{\#include\ "{}freertos/semphr.h"{}}} +\DoxyCodeLine{00017\ \textcolor{preprocessor}{\#include\ "{}esp\_log.h"{}}} +\DoxyCodeLine{00018\ \textcolor{preprocessor}{\#include\ "{}esp\_timer.h"{}}} +\DoxyCodeLine{00019\ \textcolor{preprocessor}{\#include\ "{}rom/ets\_sys.h"{}}} +\DoxyCodeLine{00020\ } +\DoxyCodeLine{00022\ \textcolor{keyword}{enum}\ channels\_t\ } +\DoxyCodeLine{00023\ \{} +\DoxyCodeLine{00024\ \ \ \ \ CHANNEL\_COMMAND,\ } +\DoxyCodeLine{00025\ \ \ \ \ CHANNEL\_EXECUTABLE,} +\DoxyCodeLine{00026\ \ \ \ \ CHANNEL\_CONTROL,} +\DoxyCodeLine{00027\ \ \ \ \ CHANNEL\_REPORTS,} +\DoxyCodeLine{00028\ \ \ \ \ CHANNEL\_WAKE\_REPORTS,} +\DoxyCodeLine{00029\ \ \ \ \ CHANNEL\_GYRO} +\DoxyCodeLine{00030\ \};} +\DoxyCodeLine{00031\ } +\DoxyCodeLine{00033\ \textcolor{keyword}{enum}\ sensor\_accuracy\_t} +\DoxyCodeLine{00034\ \{\ \ \ } +\DoxyCodeLine{00035\ \ \ \ \ LOW\_ACCURACY\ =\ 1,} +\DoxyCodeLine{00036\ \ \ \ \ MED\_ACCURACY,} +\DoxyCodeLine{00037\ \ \ \ \ HIGH\_ACCURACY} +\DoxyCodeLine{00038\ \};} +\DoxyCodeLine{00039\ } +\DoxyCodeLine{00041\ \textcolor{keyword}{typedef}\ \textcolor{keyword}{struct\ }bno08x\_config\_t\ } +\DoxyCodeLine{00042\ \{} +\DoxyCodeLine{00043\ \ \ \ \ spi\_host\_device\_t\ spi\_peripheral;\ } +\DoxyCodeLine{00044\ \ \ \ \ gpio\_num\_t\ io\_mosi;\ } +\DoxyCodeLine{00045\ \ \ \ \ gpio\_num\_t\ io\_miso;\ } +\DoxyCodeLine{00046\ \ \ \ \ gpio\_num\_t\ io\_sclk;\ } +\DoxyCodeLine{00047\ \ \ \ \ gpio\_num\_t\ io\_cs;\ } +\DoxyCodeLine{00048\ \ \ \ \ gpio\_num\_t\ io\_int;\ } +\DoxyCodeLine{00049\ \ \ \ \ gpio\_num\_t\ io\_rst;\ } +\DoxyCodeLine{00050\ \ \ \ \ gpio\_num\_t\ io\_wake;\ \ } +\DoxyCodeLine{00051\ \ \ \ \ uint64\_t\ sclk\_speed;\ } +\DoxyCodeLine{00052\ \ \ \ \ \textcolor{keywordtype}{bool}\ debug\_en;\ } +\DoxyCodeLine{00053\ \ \ \ \ } +\DoxyCodeLine{00055\ \ \ \ \ bno08x\_config\_t()\ :\ } +\DoxyCodeLine{00056\ \ \ \ \ spi\_peripheral(SPI3\_HOST),\ } +\DoxyCodeLine{00057\ \ \ \ \ io\_mosi(GPIO\_NUM\_23),\ } +\DoxyCodeLine{00058\ \ \ \ \ io\_miso(GPIO\_NUM\_19),\ } +\DoxyCodeLine{00059\ \ \ \ \ io\_sclk(GPIO\_NUM\_18),\ \ } +\DoxyCodeLine{00060\ \ \ \ \ io\_cs(GPIO\_NUM\_33),\ } +\DoxyCodeLine{00061\ \ \ \ \ io\_int(GPIO\_NUM\_26),\ } +\DoxyCodeLine{00062\ \ \ \ \ io\_rst(GPIO\_NUM\_32),} +\DoxyCodeLine{00063\ \ \ \ \ io\_wake(GPIO\_NUM\_4),} +\DoxyCodeLine{00064\ \ \ \ \ \textcolor{comment}{//sclk\_speed(10000U),\ //clock\ slowed\ to\ see\ on\ AD2}} +\DoxyCodeLine{00065\ \ \ \ \ sclk\_speed(2000000U),\ \textcolor{comment}{//1MHz\ SCLK\ speed\ }} +\DoxyCodeLine{00066\ \ \ \ \ debug\_en(false)} +\DoxyCodeLine{00067\ } +\DoxyCodeLine{00068\ \ \ \ \ \{} +\DoxyCodeLine{00069\ \ \ \ \ \}\ \ } +\DoxyCodeLine{00070\ } +\DoxyCodeLine{00071\ \}\ bno08x\_config\_t;} +\DoxyCodeLine{00072\ } +\DoxyCodeLine{00073\ \textcolor{keyword}{class\ }BNO08x\ } +\DoxyCodeLine{00074\ \{} +\DoxyCodeLine{00075\ \ \ \ \ \textcolor{keyword}{public}:} +\DoxyCodeLine{00076\ \ \ \ \ \ \ \ \ BNO08x(bno08x\_config\_t\ imu\_config\ =\ default\_imu\_config);} +\DoxyCodeLine{00077\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ initialize();} +\DoxyCodeLine{00078\ } +\DoxyCodeLine{00079\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ hard\_reset();} +\DoxyCodeLine{00080\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ soft\_reset();} +\DoxyCodeLine{00081\ \ \ \ \ \ \ \ \ uint8\_t\ get\_reset\_reason();} +\DoxyCodeLine{00082\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ mode\_sleep();} +\DoxyCodeLine{00083\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ mode\_on();\ } +\DoxyCodeLine{00084\ \ \ \ \ \ \ \ \ } +\DoxyCodeLine{00085\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ q\_to\_float(int16\_t\ fixed\_point\_value,\ uint8\_t\ q\_point);} +\DoxyCodeLine{00086\ \ \ \ \ \ \ \ \ } +\DoxyCodeLine{00087\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ run\_full\_calibration\_routine();\ } +\DoxyCodeLine{00088\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ calibrate\_all();} +\DoxyCodeLine{00089\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ calibrate\_accelerometer();} +\DoxyCodeLine{00090\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ calibrate\_gyro();} +\DoxyCodeLine{00091\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ calibrate\_magnetometer();} +\DoxyCodeLine{00092\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ calibrate\_planar\_accelerometer();} +\DoxyCodeLine{00093\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ request\_calibration\_status();\ } +\DoxyCodeLine{00094\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ calibration\_complete();\ } +\DoxyCodeLine{00095\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ end\_calibration();} +\DoxyCodeLine{00096\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ save\_calibration();} +\DoxyCodeLine{00097\ } +\DoxyCodeLine{00098\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_rotation\_vector(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00099\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_game\_rotation\_vector(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00100\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_ARVR\_stabilized\_rotation\_vector(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00101\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_ARVR\_stabilized\_game\_rotation\_vector(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00102\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_gyro\_integrated\_rotation\_vector(uint16\_t\ timeBetweenReports);} +\DoxyCodeLine{00103\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_accelerometer(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00104\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_linear\_accelerometer(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00105\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_gravity(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00106\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_gyro(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00107\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_uncalibrated\_gyro(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00108\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_magnetometer(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00109\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_tap\_detector(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00110\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_step\_counter(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00111\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_stability\_classifier(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00112\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_activity\_classifier(uint16\_t\ time\_between\_reports,\ uint32\_t\ activities\_to\_enable,\ uint8\_t\ (\&activity\_confidence\_vals)[9]);} +\DoxyCodeLine{00113\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_raw\_accelerometer(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00114\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_raw\_gyro(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00115\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ enable\_raw\_magnetometer(uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00116\ \ \ \ } +\DoxyCodeLine{00117\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ tare\_now(uint8\_t\ axis\_sel\ =\ TARE\_AXIS\_ALL,\ uint8\_t\ rotation\_vector\_basis\ =\ TARE\_ROTATION\_VECTOR);} +\DoxyCodeLine{00118\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ save\_tare();} +\DoxyCodeLine{00119\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ clear\_tare();\ } +\DoxyCodeLine{00120\ } +\DoxyCodeLine{00121\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ data\_available();\ } +\DoxyCodeLine{00122\ \ \ \ \ \ \ \ \ uint16\_t\ parse\_input\_report();\ \ \ } +\DoxyCodeLine{00123\ \ \ \ \ \ \ \ \ uint16\_t\ parse\_command\_report();\ } +\DoxyCodeLine{00124\ \ \ \ \ \ \ \ \ uint16\_t\ get\_readings();} +\DoxyCodeLine{00125\ } +\DoxyCodeLine{00126\ \ \ \ \ \ \ \ \ uint32\_t\ get\_time\_stamp();} +\DoxyCodeLine{00127\ } +\DoxyCodeLine{00128\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ get\_magf(\textcolor{keywordtype}{float}\ \&x,\ \textcolor{keywordtype}{float}\ \&y,\ \textcolor{keywordtype}{float}\ \&z,\ uint8\_t\ \&accuracy);} +\DoxyCodeLine{00129\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_magf\_X();} +\DoxyCodeLine{00130\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_magf\_Y();} +\DoxyCodeLine{00131\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_magf\_Z();} +\DoxyCodeLine{00132\ \ \ \ \ \ \ \ \ uint8\_t\ get\_magf\_accuracy();} +\DoxyCodeLine{00133\ } +\DoxyCodeLine{00134\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ get\_gravity(\textcolor{keywordtype}{float}\ \&x,\ \textcolor{keywordtype}{float}\ \&y,\ \textcolor{keywordtype}{float}\ \&z,\ uint8\_t\ \&accuracy);} +\DoxyCodeLine{00135\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_gravity\_X();} +\DoxyCodeLine{00136\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_gravity\_Y();} +\DoxyCodeLine{00137\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_gravity\_Z();} +\DoxyCodeLine{00138\ \ \ \ \ \ \ \ \ uint8\_t\ get\_gravity\_accuracy();} +\DoxyCodeLine{00139\ } +\DoxyCodeLine{00140\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_roll();} +\DoxyCodeLine{00141\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_pitch();} +\DoxyCodeLine{00142\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_yaw();} +\DoxyCodeLine{00143\ } +\DoxyCodeLine{00144\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_roll\_deg();} +\DoxyCodeLine{00145\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_pitch\_deg();} +\DoxyCodeLine{00146\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_yaw\_deg();} +\DoxyCodeLine{00147\ } +\DoxyCodeLine{00148\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ get\_quat(\textcolor{keywordtype}{float}\ \&i,\ \textcolor{keywordtype}{float}\ \&j,\ \textcolor{keywordtype}{float}\ \&k,\ \textcolor{keywordtype}{float}\ \&real,\ \textcolor{keywordtype}{float}\ \&rad\_accuracy,\ uint8\_t\ \&accuracy);} +\DoxyCodeLine{00149\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_quat\_I();} +\DoxyCodeLine{00150\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_quat\_J();} +\DoxyCodeLine{00151\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_quat\_K();} +\DoxyCodeLine{00152\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_quat\_real();} +\DoxyCodeLine{00153\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_quat\_radian\_accuracy();} +\DoxyCodeLine{00154\ \ \ \ \ \ \ \ \ uint8\_t\ get\_quat\_accuracy();} +\DoxyCodeLine{00155\ } +\DoxyCodeLine{00156\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ get\_accel(\textcolor{keywordtype}{float}\ \&x,\ \textcolor{keywordtype}{float}\ \&y,\ \textcolor{keywordtype}{float}\ \&z,\ uint8\_t\ \&accuracy);} +\DoxyCodeLine{00157\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_accel\_X();} +\DoxyCodeLine{00158\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_accel\_Y();} +\DoxyCodeLine{00159\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_accel\_Z();} +\DoxyCodeLine{00160\ \ \ \ \ \ \ \ \ uint8\_t\ get\_accel\_accuracy();} +\DoxyCodeLine{00161\ \ \ \ \ \ \ \ \ } +\DoxyCodeLine{00162\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ get\_linear\_accel(\textcolor{keywordtype}{float}\ \&x,\ \textcolor{keywordtype}{float}\ \&y,\ \textcolor{keywordtype}{float}\ \&z,\ uint8\_t\ \&accuracy);} +\DoxyCodeLine{00163\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_linear\_accel\_X();} +\DoxyCodeLine{00164\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_linear\_accel\_Y();} +\DoxyCodeLine{00165\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_linear\_accel\_Z();} +\DoxyCodeLine{00166\ \ \ \ \ \ \ \ \ uint8\_t\ get\_linear\_accel\_accuracy();} +\DoxyCodeLine{00167\ } +\DoxyCodeLine{00168\ \ \ \ \ \ \ \ \ int16\_t\ get\_raw\_accel\_X();} +\DoxyCodeLine{00169\ \ \ \ \ \ \ \ \ int16\_t\ get\_raw\_accel\_Y();} +\DoxyCodeLine{00170\ \ \ \ \ \ \ \ \ int16\_t\ get\_raw\_accel\_Z();} +\DoxyCodeLine{00171\ } +\DoxyCodeLine{00172\ \ \ \ \ \ \ \ \ int16\_t\ get\_raw\_gyro\_X();} +\DoxyCodeLine{00173\ \ \ \ \ \ \ \ \ int16\_t\ get\_raw\_gyro\_Y();} +\DoxyCodeLine{00174\ \ \ \ \ \ \ \ \ int16\_t\ get\_raw\_gyro\_Z();} +\DoxyCodeLine{00175\ } +\DoxyCodeLine{00176\ \ \ \ \ \ \ \ \ int16\_t\ get\_raw\_magf\_X();} +\DoxyCodeLine{00177\ \ \ \ \ \ \ \ \ int16\_t\ get\_raw\_magf\_Y();} +\DoxyCodeLine{00178\ \ \ \ \ \ \ \ \ int16\_t\ get\_raw\_magf\_Z();} +\DoxyCodeLine{00179\ } +\DoxyCodeLine{00180\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ get\_gyro\_calibrated\_velocity(\textcolor{keywordtype}{float}\ \&x,\ \textcolor{keywordtype}{float}\ \&y,\ \textcolor{keywordtype}{float}\ \&z,\ uint8\_t\ \&accuracy);} +\DoxyCodeLine{00181\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_gyro\_calibrated\_velocity\_X();} +\DoxyCodeLine{00182\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_gyro\_calibrated\_velocity\_Y();} +\DoxyCodeLine{00183\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_gyro\_calibrated\_velocity\_Z();} +\DoxyCodeLine{00184\ \ \ \ \ \ \ \ \ uint8\_t\ get\_gyro\_accuracy();} +\DoxyCodeLine{00185\ } +\DoxyCodeLine{00186\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ get\_uncalibrated\_gyro(\textcolor{keywordtype}{float}\ \&x,\ \textcolor{keywordtype}{float}\ \&y,\ \textcolor{keywordtype}{float}\ \&z,\ \textcolor{keywordtype}{float}\ \&bx,\ \textcolor{keywordtype}{float}\ \&by,\ \textcolor{keywordtype}{float}\ \&bz,\ uint8\_t\ \&accuracy);} +\DoxyCodeLine{00187\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_uncalibrated\_gyro\_X();} +\DoxyCodeLine{00188\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_uncalibrated\_gyro\_Y();} +\DoxyCodeLine{00189\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_uncalibrated\_gyro\_Z();} +\DoxyCodeLine{00190\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_uncalibrated\_gyro\_bias\_X();} +\DoxyCodeLine{00191\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_uncalibrated\_gyro\_bias\_Y();} +\DoxyCodeLine{00192\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_uncalibrated\_gyro\_bias\_Z();} +\DoxyCodeLine{00193\ \ \ \ \ \ \ \ \ uint8\_t\ get\_uncalibrated\_gyro\_accuracy();} +\DoxyCodeLine{00194\ } +\DoxyCodeLine{00195\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ get\_gyro\_velocity(\textcolor{keywordtype}{float}\ \&x,\ \textcolor{keywordtype}{float}\ \&y,\ \textcolor{keywordtype}{float}\ \&z);} +\DoxyCodeLine{00196\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_gyro\_velocity\_X();} +\DoxyCodeLine{00197\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_gyro\_velocity\_Y();} +\DoxyCodeLine{00198\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_gyro\_velocity\_Z();} +\DoxyCodeLine{00199\ } +\DoxyCodeLine{00200\ \ \ \ \ \ \ \ \ uint8\_t\ get\_tap\_detector();} +\DoxyCodeLine{00201\ \ \ \ \ \ \ \ \ uint16\_t\ get\_step\_count();} +\DoxyCodeLine{00202\ \ \ \ \ \ \ \ \ int8\_t\ get\_stability\_classifier();} +\DoxyCodeLine{00203\ \ \ \ \ \ \ \ \ uint8\_t\ get\_activity\_classifier();} +\DoxyCodeLine{00204\ } +\DoxyCodeLine{00205\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ print\_header();} +\DoxyCodeLine{00206\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ print\_packet();} +\DoxyCodeLine{00207\ } +\DoxyCodeLine{00208\ \ \ \ \ \ \ \ \ \textcolor{comment}{//Metadata\ functions}} +\DoxyCodeLine{00209\ \ \ \ \ \ \ \ \ int16\_t\ get\_Q1(uint16\_t\ record\_ID);} +\DoxyCodeLine{00210\ \ \ \ \ \ \ \ \ int16\_t\ get\_Q2(uint16\_t\ record\_ID);} +\DoxyCodeLine{00211\ \ \ \ \ \ \ \ \ int16\_t\ get\_Q3(uint16\_t\ record\_ID);} +\DoxyCodeLine{00212\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_resolution(uint16\_t\ record\_ID);} +\DoxyCodeLine{00213\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{float}\ get\_range(uint16\_t\ record\_ID);} +\DoxyCodeLine{00214\ \ \ \ \ \ \ \ \ uint32\_t\ FRS\_read\_word(uint16\_t\ record\_ID,\ uint8\_t\ word\_number);} +\DoxyCodeLine{00215\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ FRS\_read\_request(uint16\_t\ record\_ID,\ uint16\_t\ read\_offset,\ uint16\_t\ block\_size);} +\DoxyCodeLine{00216\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ FRS\_read\_data(uint16\_t\ record\_ID,\ uint8\_t\ start\_location,\ uint8\_t\ words\_to\_read);} +\DoxyCodeLine{00217\ } +\DoxyCodeLine{00218\ \ \ \ \ \ \ \ \ \textcolor{comment}{//Record\ IDs\ from\ figure\ 29,\ page\ 29\ reference\ manual}} +\DoxyCodeLine{00219\ \ \ \ \ \ \ \ \ \textcolor{comment}{//These\ are\ used\ to\ read\ the\ metadata\ for\ each\ sensor\ type}} +\DoxyCodeLine{00220\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint16\_t\ FRS\_RECORDID\_ACCELEROMETER\ =\ 0xE302;} +\DoxyCodeLine{00221\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint16\_t\ \ FRS\_RECORDID\_GYROSCOPE\_CALIBRATED\ =\ 0xE306;} +\DoxyCodeLine{00222\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint16\_t\ \ FRS\_RECORDID\_MAGNETIC\_FIELD\_CALIBRATED\ =\ 0xE309;} +\DoxyCodeLine{00223\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint16\_t\ \ FRS\_RECORDID\_ROTATION\_VECTOR\ =\ 0xE30B;} +\DoxyCodeLine{00224\ } +\DoxyCodeLine{00225\ \ \ \ \ } +\DoxyCodeLine{00226\ \ \ \ \ \textcolor{keyword}{private}:} +\DoxyCodeLine{00227\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ wait\_for\_device\_int();\ } +\DoxyCodeLine{00228\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{bool}\ receive\_packet();} +\DoxyCodeLine{00229\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ send\_packet();\ } +\DoxyCodeLine{00230\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ queue\_packet(uint8\_t\ channel\_number,\ uint8\_t\ data\_length);\ } +\DoxyCodeLine{00231\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ queue\_command(uint8\_t\ command);\ } +\DoxyCodeLine{00232\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ queue\_feature\_command(uint8\_t\ report\_ID,\ uint16\_t\ time\_between\_reports);} +\DoxyCodeLine{00233\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ queue\_feature\_command(uint8\_t\ report\_ID,\ uint16\_t\ time\_between\_reports,\ uint32\_t\ specific\_config);} +\DoxyCodeLine{00234\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ queue\_calibrate\_command(uint8\_t\ \_to\_calibrate);\ } +\DoxyCodeLine{00235\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ queue\_tare\_command(uint8\_t\ command,\ uint8\_t\ axis\ =\ TARE\_AXIS\_ALL,\ uint8\_t\ rotation\_vector\_basis\ =\ TARE\_ROTATION\_VECTOR);\ } +\DoxyCodeLine{00236\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ queue\_request\_product\_id\_command();\ } +\DoxyCodeLine{00237\ } +\DoxyCodeLine{00238\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ bno08x\_config\_t\ default\_imu\_config;\ } +\DoxyCodeLine{00239\ } +\DoxyCodeLine{00240\ \ \ \ \ \ \ \ \ \textcolor{keyword}{volatile}\ uint8\_t\ tx\_packet\_queued;\ } +\DoxyCodeLine{00241\ \ \ \ \ \ \ \ \ SemaphoreHandle\_t\ tx\_semaphore;\ } +\DoxyCodeLine{00242\ \ \ \ \ \ \ \ \ uint8\_t\ rx\_buffer[300];\ } +\DoxyCodeLine{00243\ \ \ \ \ \ \ \ \ uint8\_t\ tx\_buffer[50];\ } +\DoxyCodeLine{00244\ \ \ \ \ \ \ \ \ uint8\_t\ packet\_header\_rx[4];\ } +\DoxyCodeLine{00245\ \ \ \ \ \ \ \ \ uint8\_t\ commands[20];\ } +\DoxyCodeLine{00246\ \ \ \ \ \ \ \ \ uint8\_t\ sequence\_number[6];\ } +\DoxyCodeLine{00247\ \ \ \ \ \ \ \ \ uint32\_t\ meta\_data[9];\ } +\DoxyCodeLine{00248\ \ \ \ \ \ \ \ \ uint8\_t\ command\_sequence\_number\ =\ 0;\ } +\DoxyCodeLine{00249\ \ \ \ \ \ \ \ \ uint16\_t\ packet\_length\_tx\ =\ 0;\ } +\DoxyCodeLine{00250\ \ \ \ \ \ \ \ \ uint16\_t\ packet\_length\_rx\ =\ 0;\ } +\DoxyCodeLine{00251\ } +\DoxyCodeLine{00252\ \ \ \ \ \ \ \ \ bno08x\_config\_t\ imu\_config\{\};\ } +\DoxyCodeLine{00253\ \ \ \ \ \ \ \ \ spi\_bus\_config\_t\ bus\_config\{\};\ } +\DoxyCodeLine{00254\ \ \ \ \ \ \ \ \ spi\_device\_interface\_config\_t\ imu\_spi\_config\{\};\ } +\DoxyCodeLine{00255\ \ \ \ \ \ \ \ \ spi\_device\_handle\_t\ spi\_hdl\{\};\ } +\DoxyCodeLine{00256\ \ \ \ \ \ \ \ \ spi\_transaction\_t\ spi\_transaction\{\};\ } +\DoxyCodeLine{00257\ } +\DoxyCodeLine{00258\ \ \ \ \ \ \ \ \ \textcolor{comment}{//These\ are\ the\ raw\ sensor\ values\ (without\ Q\ applied)\ pulled\ from\ the\ user\ requested\ Input\ Report}} +\DoxyCodeLine{00259\ \ \ \ \ \ \ \ \ uint32\_t\ time\_stamp;\ } +\DoxyCodeLine{00260\ \ \ \ \ \ \ \ \ uint16\_t\ raw\_accel\_X,\ raw\_accel\_Y,\ raw\_accel\_Z,\ accel\_accuracy;\ } +\DoxyCodeLine{00261\ \ \ \ \ \ \ \ \ uint16\_t\ raw\_lin\_accel\_X,\ raw\_lin\_accel\_Y,\ raw\_lin\_accel\_Z,\ accel\_lin\_accuracy;\ } +\DoxyCodeLine{00262\ \ \ \ \ \ \ \ \ uint16\_t\ raw\_gyro\_X,\ raw\_gyro\_Y,\ raw\_gyro\_Z,\ gyro\_accuracy;\ } +\DoxyCodeLine{00263\ \ \ \ \ \ \ \ \ uint16\_t\ raw\_quat\_I,\ raw\_quat\_J,\ raw\_quat\_K,\ raw\_quat\_real,\ raw\_quat\_radian\_accuracy,\ quat\_accuracy;\ } +\DoxyCodeLine{00264\ \ \ \ \ \ \ \ \ uint16\_t\ raw\_velocity\_gyro\_X,\ raw\_velocity\_gyro\_Y,\ raw\_velocity\_gyro\_Z;} +\DoxyCodeLine{00265\ \ \ \ \ \ \ \ \ uint16\_t\ gravity\_X,\ gravity\_Y,\ gravity\_Z,\ gravity\_accuracy;\ } +\DoxyCodeLine{00266\ \ \ \ \ \ \ \ \ uint16\_t\ raw\_uncalib\_gyro\_X,\ raw\_uncalib\_gyro\_Y,\ raw\_uncalib\_gyro\_Z,\ raw\_bias\_X,\ raw\_bias\_Y,\ raw\_bias\_Z,\ uncalib\_gyro\_accuracy;\ } +\DoxyCodeLine{00267\ \ \ \ \ \ \ \ \ uint16\_t\ raw\_magf\_X,\ raw\_magf\_Y,\ raw\_magf\_Z,\ magf\_accuracy;\ } +\DoxyCodeLine{00268\ \ \ \ \ \ \ \ \ uint8\_t\ tap\_detector;\ } +\DoxyCodeLine{00269\ \ \ \ \ \ \ \ \ uint16\_t\ step\_count;\ } +\DoxyCodeLine{00270\ \ \ \ \ \ \ \ \ uint8\_t\ stability\_classifier;} +\DoxyCodeLine{00271\ \ \ \ \ \ \ \ \ uint8\_t\ activity\_classifier;\ } +\DoxyCodeLine{00272\ \ \ \ \ \ \ \ \ uint8\_t\ *activity\_confidences;} +\DoxyCodeLine{00273\ \ \ \ \ \ \ \ \ uint8\_t\ calibration\_status;\ } +\DoxyCodeLine{00274\ \ \ \ \ \ \ \ \ uint16\_t\ mems\_raw\_accel\_X,\ mems\_raw\_accel\_Y,\ mems\_raw\_accel\_Z;\ } +\DoxyCodeLine{00275\ \ \ \ \ \ \ \ \ uint16\_t\ mems\_raw\_gyro\_X,\ mems\_raw\_gyro\_Y,\ mems\_raw\_gyro\_Z;\ \ } +\DoxyCodeLine{00276\ \ \ \ \ \ \ \ \ uint16\_t\ mems\_raw\_magf\_X,\ mems\_raw\_magf\_Y,\ mems\_raw\_magf\_Z;\ \ \ \ } +\DoxyCodeLine{00277\ } +\DoxyCodeLine{00278\ \ \ \ \ \ \ \ \ \textcolor{comment}{//spi\ task}} +\DoxyCodeLine{00279\ \ \ \ \ \ \ \ \ TaskHandle\_t\ spi\_task\_hdl;\ } +\DoxyCodeLine{00280\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ spi\_task\_trampoline(\textcolor{keywordtype}{void}\ *arg);\ } +\DoxyCodeLine{00281\ \ \ \ \ \ \ \ \ \textcolor{keywordtype}{void}\ spi\_task();\ } +\DoxyCodeLine{00282\ } +\DoxyCodeLine{00283\ \ \ \ \ \ \ \ \ \textcolor{keyword}{volatile}\ \textcolor{keywordtype}{bool}\ int\_asserted;\ } +\DoxyCodeLine{00284\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{void}\ IRAM\_ATTR\ hint\_handler(\textcolor{keywordtype}{void}\ *arg);} +\DoxyCodeLine{00285\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keywordtype}{bool}\ isr\_service\_installed;\ } +\DoxyCodeLine{00286\ \ \ \ \ \ \ \ \ } +\DoxyCodeLine{00287\ } +\DoxyCodeLine{00288\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ ROTATION\_VECTOR\_Q1\ =\ 14;\ } +\DoxyCodeLine{00289\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ ROTATION\_VECTOR\_ACCURACY\_Q1\ =\ 12;\ } +\DoxyCodeLine{00290\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ ACCELEROMETER\_Q1\ =\ 8;\ } +\DoxyCodeLine{00291\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ LINEAR\_ACCELEROMETER\_Q1\ =\ 8;\ } +\DoxyCodeLine{00292\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ GYRO\_Q1\ =\ 9;\ } +\DoxyCodeLine{00293\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ MAGNETOMETER\_Q1\ =\ 4;\ } +\DoxyCodeLine{00294\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ ANGULAR\_VELOCITY\_Q1\ =\ 10;\ } +\DoxyCodeLine{00295\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ int16\_t\ GRAVITY\_Q1\ =\ 8;\ } +\DoxyCodeLine{00296\ } +\DoxyCodeLine{00297\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint64\_t\ HOST\_INT\_TIMEOUT\_US\ =\ 150000ULL;\ } +\DoxyCodeLine{00298\ } +\DoxyCodeLine{00299\ \ \ \ \ \ \ \ \ \textcolor{comment}{//Higher\ level\ calibration\ commands,\ used\ by\ queue\_calibrate\_command}} +\DoxyCodeLine{00300\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ CALIBRATE\_ACCEL\ =\ 0;\ } +\DoxyCodeLine{00301\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ CALIBRATE\_GYRO\ =\ 1;} +\DoxyCodeLine{00302\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ CALIBRATE\_MAG\ =\ 2;\ } +\DoxyCodeLine{00303\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ CALIBRATE\_PLANAR\_ACCEL\ =\ 3;\ } +\DoxyCodeLine{00304\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ CALIBRATE\_ACCEL\_GYRO\_MAG\ =\ 4;\ } +\DoxyCodeLine{00305\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ CALIBRATE\_STOP\ =\ 5;\ } +\DoxyCodeLine{00306\ } +\DoxyCodeLine{00307\ \ \ \ \ \ \ \ \ \textcolor{comment}{//Command\ IDs\ (see\ Ref.\ Manual\ 6.4)}} +\DoxyCodeLine{00308\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ COMMAND\_ERRORS\ =\ 1;} +\DoxyCodeLine{00309\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ COMMAND\_COUNTER\ =\ 2;} +\DoxyCodeLine{00310\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ COMMAND\_TARE\ =\ 3;\ } +\DoxyCodeLine{00311\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ COMMAND\_INITIALIZE\ =\ 4;\ } +\DoxyCodeLine{00312\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ COMMAND\_DCD\ =\ 6;\ } +\DoxyCodeLine{00313\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ COMMAND\_ME\_CALIBRATE\ =\ 7;\ } +\DoxyCodeLine{00314\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ COMMAND\_DCD\_PERIOD\_SAVE\ =\ 9;\ } +\DoxyCodeLine{00315\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ COMMAND\_OSCILLATOR\ =\ 10;\ } +\DoxyCodeLine{00316\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ COMMAND\_CLEAR\_DCD\ =\ 11;\ } +\DoxyCodeLine{00317\ } +\DoxyCodeLine{00318\ \ \ \ \ \ \ \ \ \textcolor{comment}{//SHTP\ channel\ 2\ control\ report\ IDs,\ used\ in\ communication\ with\ sensor\ (See\ Ref.\ Manual\ 6.2)}} +\DoxyCodeLine{00319\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SHTP\_REPORT\_COMMAND\_RESPONSE\ =\ 0xF1;\ } +\DoxyCodeLine{00320\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SHTP\_REPORT\_COMMAND\_REQUEST\ =\ 0xF2;\ } +\DoxyCodeLine{00321\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SHTP\_REPORT\_FRS\_READ\_RESPONSE\ =\ 0xF3;\ } +\DoxyCodeLine{00322\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SHTP\_REPORT\_FRS\_READ\_REQUEST\ =\ 0xF4;\ } +\DoxyCodeLine{00323\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SHTP\_REPORT\_PRODUCT\_ID\_RESPONSE\ =\ 0xF8;\ } +\DoxyCodeLine{00324\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SHTP\_REPORT\_PRODUCT\_ID\_REQUEST\ =\ 0xF9;\ } +\DoxyCodeLine{00325\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SHTP\_REPORT\_BASE\_TIMESTAMP\ =\ 0xFB;\ } +\DoxyCodeLine{00326\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SHTP\_REPORT\_SET\_FEATURE\_COMMAND\ =\ 0xFD;\ } +\DoxyCodeLine{00327\ } +\DoxyCodeLine{00328\ } +\DoxyCodeLine{00329\ \ \ \ \ \ \ \ \ \textcolor{comment}{//Sensor\ report\ IDs,\ used\ when\ enabling\ and\ reading\ BNO08x\ reports}} +\DoxyCodeLine{00330\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_ACCELEROMETER\ =\ 0x01;\ } +\DoxyCodeLine{00331\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_GYROSCOPE\ =\ 0x02;\ } +\DoxyCodeLine{00332\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_MAGNETIC\_FIELD\ =\ 0x03;\ } +\DoxyCodeLine{00333\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_LINEAR\_ACCELERATION\ =\ 0x04;\ } +\DoxyCodeLine{00334\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_ROTATION\_VECTOR\ =\ 0x05;\ } +\DoxyCodeLine{00335\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_GRAVITY\ =\ 0x06;\ } +\DoxyCodeLine{00336\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_UNCALIBRATED\_GYRO\ =\ 0x07;\ } +\DoxyCodeLine{00337\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_GAME\_ROTATION\_VECTOR\ =\ 0x08;\ } +\DoxyCodeLine{00338\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_GEOMAGNETIC\_ROTATION\_VECTOR\ =\ 0x09;\ } +\DoxyCodeLine{00339\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_GYRO\_INTEGRATED\_ROTATION\_VECTOR\ =\ 0x2A;\ } +\DoxyCodeLine{00340\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_TAP\_DETECTOR\ =\ 0x10;} +\DoxyCodeLine{00341\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_STEP\_COUNTER\ =\ 0x11;\ } +\DoxyCodeLine{00342\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_STABILITY\_CLASSIFIER\ =\ 0x13;\ } +\DoxyCodeLine{00343\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_RAW\_ACCELEROMETER\ =\ 0x14;\ } +\DoxyCodeLine{00344\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_RAW\_GYROSCOPE\ =\ 0x15;\ } +\DoxyCodeLine{00345\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_RAW\_MAGNETOMETER\ =\ 0x16;\ } +\DoxyCodeLine{00346\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_PERSONAL\_ACTIVITY\_CLASSIFIER\ =\ 0x1E;\ } +\DoxyCodeLine{00347\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_AR\_VR\_STABILIZED\_ROTATION\_VECTOR\ =\ 0x28;\ } +\DoxyCodeLine{00348\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ SENSOR\_REPORTID\_AR\_VR\_STABILIZED\_GAME\_ROTATION\_VECTOR\ =\ 0x29;\ } +\DoxyCodeLine{00349\ } +\DoxyCodeLine{00350\ \ \ \ \ \ \ \ \ \textcolor{comment}{//Tare\ commands\ used\ by\ queue\_tare\_command}} +\DoxyCodeLine{00351\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ TARE\_NOW\ =\ 0;\ } +\DoxyCodeLine{00352\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ TARE\_PERSIST\ =\ 1;\ } +\DoxyCodeLine{00353\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ TARE\_SET\_REORIENTATION\ =\ 2;\ } +\DoxyCodeLine{00354\ } +\DoxyCodeLine{00355\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ TARE\_AXIS\_ALL\ =\ 0x07;\ } +\DoxyCodeLine{00356\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ TARE\_AXIS\_Z\ \ \ =\ 0x04;\ } +\DoxyCodeLine{00357\ } +\DoxyCodeLine{00358\ \ \ \ \ \ \ \ \ \textcolor{comment}{//Which\ rotation\ vector\ to\ tare,\ BNO08x\ saves\ them\ seperately}} +\DoxyCodeLine{00359\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ TARE\_ROTATION\_VECTOR\ =\ 0;\ } +\DoxyCodeLine{00360\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ TARE\_GAME\_ROTATION\_VECTOR\ =\ 1;\ } +\DoxyCodeLine{00361\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ TARE\_GEOMAGNETIC\_ROTATION\_VECTOR\ =\ 2;} +\DoxyCodeLine{00362\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ TARE\_GYRO\_INTEGRATED\_ROTATION\_VECTOR\ =\ 3;\ } +\DoxyCodeLine{00363\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ TARE\_AR\_VR\_STABILIZED\_ROTATION\_VECTOR\ =\ 4;\ } +\DoxyCodeLine{00364\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ uint8\_t\ TARE\_AR\_VR\_STABILIZED\_GAME\_ROTATION\_VECTOR\ =\ 5;\ } +\DoxyCodeLine{00365\ } +\DoxyCodeLine{00366\ \ \ \ \ \ \ \ \ \textcolor{keyword}{static}\ \textcolor{keyword}{const}\ \textcolor{keyword}{constexpr}\ \textcolor{keywordtype}{char}\ *TAG\ =\ \textcolor{stringliteral}{"{}BNO08x"{}};\ } +\DoxyCodeLine{00367\ \};} + +\end{DoxyCode} diff --git a/documentation/latex/annotated.tex b/documentation/latex/annotated.tex new file mode 100644 index 0000000..bebfe0e --- /dev/null +++ b/documentation/latex/annotated.tex @@ -0,0 +1,5 @@ +\doxysection{Class List} +Here are the classes, structs, unions and interfaces with brief descriptions\+:\begin{DoxyCompactList} +\item\contentsline{section}{\textbf{ BNO08x} }{\pageref{class_b_n_o08x}}{} +\item\contentsline{section}{\textbf{ bno08x\+\_\+config\+\_\+t} \\*IMU configuration settings passed into constructor }{\pageref{structbno08x__config__t}}{} +\end{DoxyCompactList} diff --git a/documentation/latex/class_b_n_o08x.tex b/documentation/latex/class_b_n_o08x.tex new file mode 100644 index 0000000..22cc992 --- /dev/null +++ b/documentation/latex/class_b_n_o08x.tex @@ -0,0 +1,2711 @@ +\doxysection{BNO08x Class Reference} +\label{class_b_n_o08x}\index{BNO08x@{BNO08x}} +\doxysubsubsection*{Public Member Functions} +\begin{DoxyCompactItemize} +\item +\textbf{ BNO08x} (\textbf{ bno08x\+\_\+config\+\_\+t} \textbf{ imu\+\_\+config}=\textbf{ default\+\_\+imu\+\_\+config}) +\begin{DoxyCompactList}\small\item\em \doxyref{BNO08x}{p.}{class_b_n_o08x} imu constructor. \end{DoxyCompactList}\item +bool \textbf{ initialize} () +\begin{DoxyCompactList}\small\item\em Initializes \doxyref{BNO08x}{p.}{class_b_n_o08x} sensor. \end{DoxyCompactList}\item +bool \textbf{ hard\+\_\+reset} () +\begin{DoxyCompactList}\small\item\em Hard resets \doxyref{BNO08x}{p.}{class_b_n_o08x} sensor. \end{DoxyCompactList}\item +bool \textbf{ soft\+\_\+reset} () +\begin{DoxyCompactList}\small\item\em Soft resets \doxyref{BNO08x}{p.}{class_b_n_o08x} sensor using executable channel. \end{DoxyCompactList}\item +uint8\+\_\+t \textbf{ get\+\_\+reset\+\_\+reason} () +\begin{DoxyCompactList}\small\item\em Get the reason for the most recent reset. \end{DoxyCompactList}\item +bool \textbf{ mode\+\_\+sleep} () +\begin{DoxyCompactList}\small\item\em Puts \doxyref{BNO08x}{p.}{class_b_n_o08x} sensor into sleep/low power mode using executable channel. \end{DoxyCompactList}\item +bool \textbf{ mode\+\_\+on} () +\begin{DoxyCompactList}\small\item\em Turns on/ brings \doxyref{BNO08x}{p.}{class_b_n_o08x} sensor out of sleep mode using executable channel. \end{DoxyCompactList}\item +float \textbf{ q\+\_\+to\+\_\+float} (int16\+\_\+t fixed\+\_\+point\+\_\+value, uint8\+\_\+t q\+\_\+point) +\begin{DoxyCompactList}\small\item\em Converts a register value to a float using its associated Q point. (See {\texttt{ https\+://en.\+wikipedia.\+org/wiki/\+Q\+\_\+(number\+\_\+format)}}) \end{DoxyCompactList}\item +bool \textbf{ run\+\_\+full\+\_\+calibration\+\_\+routine} () +\begin{DoxyCompactList}\small\item\em Runs full calibration routine. \end{DoxyCompactList}\item +void \textbf{ calibrate\+\_\+all} () +\begin{DoxyCompactList}\small\item\em Sends command to calibrate accelerometer, gyro, and magnetometer. \end{DoxyCompactList}\item +void \textbf{ calibrate\+\_\+accelerometer} () +\begin{DoxyCompactList}\small\item\em Sends command to calibrate accelerometer. \end{DoxyCompactList}\item +void \textbf{ calibrate\+\_\+gyro} () +\begin{DoxyCompactList}\small\item\em Sends command to calibrate gyro. \end{DoxyCompactList}\item +void \textbf{ calibrate\+\_\+magnetometer} () +\begin{DoxyCompactList}\small\item\em Sends command to calibrate magnetometer. \end{DoxyCompactList}\item +void \textbf{ calibrate\+\_\+planar\+\_\+accelerometer} () +\begin{DoxyCompactList}\small\item\em Sends command to calibrate planar accelerometer. \end{DoxyCompactList}\item +void \textbf{ request\+\_\+calibration\+\_\+status} () +\begin{DoxyCompactList}\small\item\em Requests ME calibration status from \doxyref{BNO08x}{p.}{class_b_n_o08x} (see Ref. Manual 6.\+4.\+7.\+2) \end{DoxyCompactList}\item +bool \textbf{ calibration\+\_\+complete} () +\begin{DoxyCompactList}\small\item\em Returns true if calibration has completed. \end{DoxyCompactList}\item +void \textbf{ end\+\_\+calibration} () +\begin{DoxyCompactList}\small\item\em Sends command to end calibration procedure. \end{DoxyCompactList}\item +void \textbf{ save\+\_\+calibration} () +\begin{DoxyCompactList}\small\item\em Sends command to save internal calibration data (See Ref. Manual 6.\+4.\+7). \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+rotation\+\_\+vector} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable rotation vector reports (See Ref. Manual 6.\+5.\+18) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+game\+\_\+rotation\+\_\+vector} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable game rotation vector reports (See Ref. Manual 6.\+5.\+19) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+\+ARVR\+\_\+stabilized\+\_\+rotation\+\_\+vector} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6.\+5.\+42) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+\+ARVR\+\_\+stabilized\+\_\+game\+\_\+rotation\+\_\+vector} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6.\+5.\+43) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+gyro\+\_\+integrated\+\_\+rotation\+\_\+vector} (uint16\+\_\+t time\+Between\+Reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+accelerometer} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable accelerometer reports (See Ref. Manual 6.\+5.\+9) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+linear\+\_\+accelerometer} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable linear accelerometer reports (See Ref. Manual 6.\+5.\+10) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+gravity} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable gravity reading reports (See Ref. Manual 6.\+5.\+11) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+gyro} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable gyro reports (See Ref. Manual 6.\+5.\+13) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+uncalibrated\+\_\+gyro} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.\+5.\+14) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+magnetometer} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable magnetometer reports (See Ref. Manual 6.\+5.\+16) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+tap\+\_\+detector} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable tap detector reports (See Ref. Manual 6.\+5.\+27) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+step\+\_\+counter} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable step counter reports (See Ref. Manual 6.\+5.\+29) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+stability\+\_\+classifier} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable activity stability classifier reports (See Ref. Manual 6.\+5.\+31) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+activity\+\_\+classifier} (uint16\+\_\+t time\+\_\+between\+\_\+reports, uint32\+\_\+t activities\+\_\+to\+\_\+enable, uint8\+\_\+t(\&activity\+\_\+confidence\+\_\+vals)[9]) +\begin{DoxyCompactList}\small\item\em Sends command to enable activity classifier reports (See Ref. Manual 6.\+5.\+36) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+raw\+\_\+accelerometer} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable raw accelerometer reports (See Ref. Manual 6.\+5.\+8) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+raw\+\_\+gyro} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable raw gyro reports (See Ref. Manual 6.\+5.\+12) \end{DoxyCompactList}\item +void \textbf{ enable\+\_\+raw\+\_\+magnetometer} (uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Sends command to enable raw magnetometer reports (See Ref. Manual 6.\+5.\+15) \end{DoxyCompactList}\item +void \textbf{ tare\+\_\+now} (uint8\+\_\+t axis\+\_\+sel=\textbf{ TARE\+\_\+\+AXIS\+\_\+\+ALL}, uint8\+\_\+t rotation\+\_\+vector\+\_\+basis=\textbf{ TARE\+\_\+\+ROTATION\+\_\+\+VECTOR}) +\begin{DoxyCompactList}\small\item\em Sends command to tare an axis (See Ref. Manual 6.\+4.\+4.\+1) \end{DoxyCompactList}\item +void \textbf{ save\+\_\+tare} () +\begin{DoxyCompactList}\small\item\em Sends command to save tare into non-\/volatile memory of \doxyref{BNO08x}{p.}{class_b_n_o08x} (See Ref. Manual 6.\+4.\+4.\+2) \end{DoxyCompactList}\item +void \textbf{ clear\+\_\+tare} () +\begin{DoxyCompactList}\small\item\em Sends command to clear persistent tare settings in non-\/volatile memory of \doxyref{BNO08x}{p.}{class_b_n_o08x} (See Ref. Manual 6.\+4.\+4.\+3) \end{DoxyCompactList}\item +bool \textbf{ data\+\_\+available} () +\begin{DoxyCompactList}\small\item\em Checks if \doxyref{BNO08x}{p.}{class_b_n_o08x} has asserted interrupt and sent data. \end{DoxyCompactList}\item +uint16\+\_\+t \textbf{ parse\+\_\+input\+\_\+report} () +\begin{DoxyCompactList}\small\item\em Parses received input report sent by \doxyref{BNO08x}{p.}{class_b_n_o08x}. \end{DoxyCompactList}\item +uint16\+\_\+t \textbf{ parse\+\_\+command\+\_\+report} () +\begin{DoxyCompactList}\small\item\em Parses received command report sent by \doxyref{BNO08x}{p.}{class_b_n_o08x} (See Ref. Manual 6.\+3.\+9) \end{DoxyCompactList}\item +uint16\+\_\+t \textbf{ get\+\_\+readings} () +\begin{DoxyCompactList}\small\item\em Waits for \doxyref{BNO08x}{p.}{class_b_n_o08x} HINT pin to assert, and parses the received data. \end{DoxyCompactList}\item +uint32\+\_\+t \textbf{ get\+\_\+time\+\_\+stamp} () +\begin{DoxyCompactList}\small\item\em Return timestamp of most recent report. \end{DoxyCompactList}\item +void \textbf{ get\+\_\+magf} (float \&x, float \&y, float \&z, uint8\+\_\+t \&accuracy) +\begin{DoxyCompactList}\small\item\em Get the full magnetic field vector. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+magf\+\_\+X} () +\begin{DoxyCompactList}\small\item\em Get X component of magnetic field vector. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+magf\+\_\+Y} () +\begin{DoxyCompactList}\small\item\em Get Y component of magnetic field vector. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+magf\+\_\+Z} () +\begin{DoxyCompactList}\small\item\em Get Z component of magnetic field vector. \end{DoxyCompactList}\item +uint8\+\_\+t \textbf{ get\+\_\+magf\+\_\+accuracy} () +\begin{DoxyCompactList}\small\item\em Get accuracy of reported magnetic field vector. \end{DoxyCompactList}\item +void \textbf{ get\+\_\+gravity} (float \&x, float \&y, float \&z, uint8\+\_\+t \&accuracy) +\begin{DoxyCompactList}\small\item\em Get full reported gravity vector, units in m/s$^\wedge$2. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+gravity\+\_\+X} () +\begin{DoxyCompactList}\small\item\em Get the reported x axis gravity. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+gravity\+\_\+Y} () +\begin{DoxyCompactList}\small\item\em Get the reported y axis gravity. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+gravity\+\_\+Z} () +\begin{DoxyCompactList}\small\item\em Get the reported z axis gravity. \end{DoxyCompactList}\item +uint8\+\_\+t \textbf{ get\+\_\+gravity\+\_\+accuracy} () +\begin{DoxyCompactList}\small\item\em Get the reported gravity accuracy. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+roll} () +\begin{DoxyCompactList}\small\item\em Get the reported rotation about x axis. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+pitch} () +\begin{DoxyCompactList}\small\item\em Get the reported rotation about y axis. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+yaw} () +\begin{DoxyCompactList}\small\item\em Get the reported rotation about z axis. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+roll\+\_\+deg} () +\begin{DoxyCompactList}\small\item\em Get the reported rotation about x axis. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+pitch\+\_\+deg} () +\begin{DoxyCompactList}\small\item\em Get the reported rotation about y axis. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+yaw\+\_\+deg} () +\begin{DoxyCompactList}\small\item\em Get the reported rotation about z axis. \end{DoxyCompactList}\item +void \textbf{ get\+\_\+quat} (float \&i, float \&j, float \&k, float \&real, float \&rad\+\_\+accuracy, uint8\+\_\+t \&accuracy) +\begin{DoxyCompactList}\small\item\em Get the full quaternion reading. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+quat\+\_\+I} () +\begin{DoxyCompactList}\small\item\em Get I component of reported quaternion. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+quat\+\_\+J} () +\begin{DoxyCompactList}\small\item\em Get J component of reported quaternion. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+quat\+\_\+K} () +\begin{DoxyCompactList}\small\item\em Get K component of reported quaternion. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+quat\+\_\+real} () +\begin{DoxyCompactList}\small\item\em Get real component of reported quaternion. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+quat\+\_\+radian\+\_\+accuracy} () +\begin{DoxyCompactList}\small\item\em Get radian accuracy of reported quaternion. \end{DoxyCompactList}\item +uint8\+\_\+t \textbf{ get\+\_\+quat\+\_\+accuracy} () +\begin{DoxyCompactList}\small\item\em Get accuracy of reported quaternion. \end{DoxyCompactList}\item +void \textbf{ get\+\_\+accel} (float \&x, float \&y, float \&z, uint8\+\_\+t \&accuracy) +\begin{DoxyCompactList}\small\item\em Get full acceleration (total acceleration of device, units in m/s$^\wedge$2). \end{DoxyCompactList}\item +float \textbf{ get\+\_\+accel\+\_\+X} () +\begin{DoxyCompactList}\small\item\em Get x axis acceleration (total acceleration of device, units in m/s$^\wedge$2). \end{DoxyCompactList}\item +float \textbf{ get\+\_\+accel\+\_\+Y} () +\begin{DoxyCompactList}\small\item\em Get y axis acceleration (total acceleration of device, units in m/s$^\wedge$2). \end{DoxyCompactList}\item +float \textbf{ get\+\_\+accel\+\_\+Z} () +\begin{DoxyCompactList}\small\item\em Get z axis acceleration (total acceleration of device, units in m/s$^\wedge$2). \end{DoxyCompactList}\item +uint8\+\_\+t \textbf{ get\+\_\+accel\+\_\+accuracy} () +\begin{DoxyCompactList}\small\item\em Get accuracy of linear acceleration. \end{DoxyCompactList}\item +void \textbf{ get\+\_\+linear\+\_\+accel} (float \&x, float \&y, float \&z, uint8\+\_\+t \&accuracy) +\begin{DoxyCompactList}\small\item\em Get full linear acceleration (acceleration of the device minus gravity, units in m/s$^\wedge$2). \end{DoxyCompactList}\item +float \textbf{ get\+\_\+linear\+\_\+accel\+\_\+X} () +\begin{DoxyCompactList}\small\item\em Get x axis linear acceleration (acceleration of device minus gravity, units in m/s$^\wedge$2) \end{DoxyCompactList}\item +float \textbf{ get\+\_\+linear\+\_\+accel\+\_\+Y} () +\begin{DoxyCompactList}\small\item\em Get y axis linear acceleration (acceleration of device minus gravity, units in m/s$^\wedge$2) \end{DoxyCompactList}\item +float \textbf{ get\+\_\+linear\+\_\+accel\+\_\+Z} () +\begin{DoxyCompactList}\small\item\em Get z axis linear acceleration (acceleration of device minus gravity, units in m/s$^\wedge$2) \end{DoxyCompactList}\item +uint8\+\_\+t \textbf{ get\+\_\+linear\+\_\+accel\+\_\+accuracy} () +\begin{DoxyCompactList}\small\item\em Get accuracy of linear acceleration. \end{DoxyCompactList}\item +int16\+\_\+t \textbf{ get\+\_\+raw\+\_\+accel\+\_\+X} () +\begin{DoxyCompactList}\small\item\em Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8) \end{DoxyCompactList}\item +int16\+\_\+t \textbf{ get\+\_\+raw\+\_\+accel\+\_\+Y} () +\begin{DoxyCompactList}\small\item\em Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8) \end{DoxyCompactList}\item +int16\+\_\+t \textbf{ get\+\_\+raw\+\_\+accel\+\_\+Z} () +\begin{DoxyCompactList}\small\item\em Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8) \end{DoxyCompactList}\item +int16\+\_\+t \textbf{ get\+\_\+raw\+\_\+gyro\+\_\+X} () +\begin{DoxyCompactList}\small\item\em Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) \end{DoxyCompactList}\item +int16\+\_\+t \textbf{ get\+\_\+raw\+\_\+gyro\+\_\+Y} () +\begin{DoxyCompactList}\small\item\em Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) \end{DoxyCompactList}\item +int16\+\_\+t \textbf{ get\+\_\+raw\+\_\+gyro\+\_\+Z} () +\begin{DoxyCompactList}\small\item\em Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) \end{DoxyCompactList}\item +int16\+\_\+t \textbf{ get\+\_\+raw\+\_\+magf\+\_\+X} () +\begin{DoxyCompactList}\small\item\em Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) \end{DoxyCompactList}\item +int16\+\_\+t \textbf{ get\+\_\+raw\+\_\+magf\+\_\+Y} () +\begin{DoxyCompactList}\small\item\em Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) \end{DoxyCompactList}\item +int16\+\_\+t \textbf{ get\+\_\+raw\+\_\+magf\+\_\+Z} () +\begin{DoxyCompactList}\small\item\em Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) \end{DoxyCompactList}\item +void \textbf{ get\+\_\+gyro\+\_\+calibrated\+\_\+velocity} (float \&x, float \&y, float \&z, uint8\+\_\+t \&accuracy) +\begin{DoxyCompactList}\small\item\em Get full rotational velocity with drift compensation (units in Rad/s). \end{DoxyCompactList}\item +float \textbf{ get\+\_\+gyro\+\_\+calibrated\+\_\+velocity\+\_\+X} () +\begin{DoxyCompactList}\small\item\em Get calibrated gyro x axis angular velocity measurement. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+gyro\+\_\+calibrated\+\_\+velocity\+\_\+Y} () +\begin{DoxyCompactList}\small\item\em Get calibrated gyro y axis angular velocity measurement. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+gyro\+\_\+calibrated\+\_\+velocity\+\_\+Z} () +\begin{DoxyCompactList}\small\item\em Get calibrated gyro z axis angular velocity measurement. \end{DoxyCompactList}\item +uint8\+\_\+t \textbf{ get\+\_\+gyro\+\_\+accuracy} () +\begin{DoxyCompactList}\small\item\em Get calibrated gyro accuracy. \end{DoxyCompactList}\item +void \textbf{ get\+\_\+uncalibrated\+\_\+gyro} (float \&x, float \&y, float \&z, float \&bx, float \&by, float \&bz, uint8\+\_\+t \&accuracy) +\begin{DoxyCompactList}\small\item\em Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is given but not applied. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+uncalibrated\+\_\+gyro\+\_\+X} () +\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro x axis angular velocity measurement. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+uncalibrated\+\_\+gyro\+\_\+Y} () +\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro Y axis angular velocity measurement. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+uncalibrated\+\_\+gyro\+\_\+Z} () +\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro Z axis angular velocity measurement. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+uncalibrated\+\_\+gyro\+\_\+bias\+\_\+X} () +\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro x axis drift estimate. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+uncalibrated\+\_\+gyro\+\_\+bias\+\_\+Y} () +\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro Y axis drift estimate. \end{DoxyCompactList}\item +float \textbf{ get\+\_\+uncalibrated\+\_\+gyro\+\_\+bias\+\_\+Z} () +\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro Z axis drift estimate. \end{DoxyCompactList}\item +uint8\+\_\+t \textbf{ get\+\_\+uncalibrated\+\_\+gyro\+\_\+accuracy} () +\begin{DoxyCompactList}\small\item\em Get uncalibrated gyro accuracy. \end{DoxyCompactList}\item +void \textbf{ get\+\_\+gyro\+\_\+velocity} (float \&x, float \&y, float \&z) +\begin{DoxyCompactList}\small\item\em Full rotational velocity from gyro-\/integrated rotation vector (See Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item +float \textbf{ get\+\_\+gyro\+\_\+velocity\+\_\+X} () +\begin{DoxyCompactList}\small\item\em Get x axis angular velocity from gyro-\/integrated rotation vector. (See Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item +float \textbf{ get\+\_\+gyro\+\_\+velocity\+\_\+Y} () +\begin{DoxyCompactList}\small\item\em Get y axis angular velocity from gyro-\/integrated rotation vector. (See Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item +float \textbf{ get\+\_\+gyro\+\_\+velocity\+\_\+Z} () +\begin{DoxyCompactList}\small\item\em Get z axis angular velocity from gyro-\/integrated rotation vector. (See Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item +uint8\+\_\+t \textbf{ get\+\_\+tap\+\_\+detector} () +\begin{DoxyCompactList}\small\item\em Get if tap has occured. \end{DoxyCompactList}\item +uint16\+\_\+t \textbf{ get\+\_\+step\+\_\+count} () +\begin{DoxyCompactList}\small\item\em Get the counted amount of steps. \end{DoxyCompactList}\item +int8\+\_\+t \textbf{ get\+\_\+stability\+\_\+classifier} () +\begin{DoxyCompactList}\small\item\em Get the current stability classifier (Seee Ref. Manual 6.\+5.\+31) \end{DoxyCompactList}\item +uint8\+\_\+t \textbf{ get\+\_\+activity\+\_\+classifier} () +\begin{DoxyCompactList}\small\item\em Get the current activity classifier (Seee Ref. Manual 6.\+5.\+36) \end{DoxyCompactList}\item +void \textbf{ print\+\_\+header} () +\begin{DoxyCompactList}\small\item\em Prints the most recently received SHTP header to serial console with ESP\+\_\+\+LOG statement. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a0ef39163352bd7a54ac85952e8cb8516} +void {\bfseries print\+\_\+packet} () +\item +int16\+\_\+t \textbf{ get\+\_\+\+Q1} (uint16\+\_\+t record\+\_\+\+ID) +\begin{DoxyCompactList}\small\item\em Gets Q1 point from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system). \end{DoxyCompactList}\item +int16\+\_\+t \textbf{ get\+\_\+\+Q2} (uint16\+\_\+t record\+\_\+\+ID) +\begin{DoxyCompactList}\small\item\em Gets Q2 point from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system). \end{DoxyCompactList}\item +int16\+\_\+t \textbf{ get\+\_\+\+Q3} (uint16\+\_\+t record\+\_\+\+ID) +\begin{DoxyCompactList}\small\item\em Gets Q3 point from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system). \end{DoxyCompactList}\item +float \textbf{ get\+\_\+resolution} (uint16\+\_\+t record\+\_\+\+ID) +\begin{DoxyCompactList}\small\item\em Gets resolution from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system). \end{DoxyCompactList}\item +float \textbf{ get\+\_\+range} (uint16\+\_\+t record\+\_\+\+ID) +\begin{DoxyCompactList}\small\item\em Gets range from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system). \end{DoxyCompactList}\item +uint32\+\_\+t \textbf{ FRS\+\_\+read\+\_\+word} (uint16\+\_\+t record\+\_\+\+ID, uint8\+\_\+t word\+\_\+number) +\begin{DoxyCompactList}\small\item\em Reads meta data word from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system) given the record ID and word number. (See Ref. Manual 5.\+1 \& 6.\+3.\+7) \end{DoxyCompactList}\item +bool \textbf{ FRS\+\_\+read\+\_\+request} (uint16\+\_\+t record\+\_\+\+ID, uint16\+\_\+t read\+\_\+offset, uint16\+\_\+t block\+\_\+size) +\begin{DoxyCompactList}\small\item\em Requests meta data from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.\+1 \& 6.\+3.\+6) \end{DoxyCompactList}\item +bool \textbf{ FRS\+\_\+read\+\_\+data} (uint16\+\_\+t record\+\_\+\+ID, uint8\+\_\+t start\+\_\+location, uint8\+\_\+t words\+\_\+to\+\_\+read) +\begin{DoxyCompactList}\small\item\em Read meta data from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.\+1 \& 6.\+3.\+7) \end{DoxyCompactList}\end{DoxyCompactItemize} +\doxysubsubsection*{Static Public Attributes} +\begin{DoxyCompactItemize} +\item +\label{class_b_n_o08x_a72d8919cb432a53f57ff63aa29d5f984} +static const constexpr uint16\+\_\+t {\bfseries FRS\+\_\+\+RECORDID\+\_\+\+ACCELEROMETER} = 0x\+E302 +\item +\label{class_b_n_o08x_a6dbd6b8c9d1450c97db1e46861c55132} +static const constexpr uint16\+\_\+t {\bfseries FRS\+\_\+\+RECORDID\+\_\+\+GYROSCOPE\+\_\+\+CALIBRATED} = 0x\+E306 +\item +\label{class_b_n_o08x_ab9519ab682fedb7224e4c0489c7d5619} +static const constexpr uint16\+\_\+t {\bfseries FRS\+\_\+\+RECORDID\+\_\+\+MAGNETIC\+\_\+\+FIELD\+\_\+\+CALIBRATED} = 0x\+E309 +\item +\label{class_b_n_o08x_a58e7e3a7bf08fbdb4b75b3a0034ed33e} +static const constexpr uint16\+\_\+t {\bfseries FRS\+\_\+\+RECORDID\+\_\+\+ROTATION\+\_\+\+VECTOR} = 0x\+E30B +\end{DoxyCompactItemize} +\doxysubsubsection*{Private Member Functions} +\begin{DoxyCompactItemize} +\item +bool \textbf{ wait\+\_\+for\+\_\+device\+\_\+int} () +\begin{DoxyCompactList}\small\item\em Re-\/enables interrupts and waits for \doxyref{BNO08x}{p.}{class_b_n_o08x} to assert HINT pin. \end{DoxyCompactList}\item +bool \textbf{ receive\+\_\+packet} () +\begin{DoxyCompactList}\small\item\em Receives a SHTP packet via SPI. \end{DoxyCompactList}\item +void \textbf{ send\+\_\+packet} () +\begin{DoxyCompactList}\small\item\em Sends a queued SHTP packet via SPI. \end{DoxyCompactList}\item +void \textbf{ queue\+\_\+packet} (uint8\+\_\+t channel\+\_\+number, uint8\+\_\+t data\+\_\+length) +\begin{DoxyCompactList}\small\item\em Queues an SHTP packet to be sent via SPI. \end{DoxyCompactList}\item +void \textbf{ queue\+\_\+command} (uint8\+\_\+t command) +\begin{DoxyCompactList}\small\item\em Queues a packet containing a command. \end{DoxyCompactList}\item +void \textbf{ queue\+\_\+feature\+\_\+command} (uint8\+\_\+t report\+\_\+\+ID, uint16\+\_\+t time\+\_\+between\+\_\+reports) +\begin{DoxyCompactList}\small\item\em Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.\+5.\+4) \end{DoxyCompactList}\item +void \textbf{ queue\+\_\+feature\+\_\+command} (uint8\+\_\+t report\+\_\+\+ID, uint16\+\_\+t time\+\_\+between\+\_\+reports, uint32\+\_\+t specific\+\_\+config) +\begin{DoxyCompactList}\small\item\em Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.\+5.\+4) \end{DoxyCompactList}\item +void \textbf{ queue\+\_\+calibrate\+\_\+command} (uint8\+\_\+t \+\_\+to\+\_\+calibrate) +\begin{DoxyCompactList}\small\item\em Queues a packet containing a command to calibrate the specified sensor. \end{DoxyCompactList}\item +void \textbf{ queue\+\_\+tare\+\_\+command} (uint8\+\_\+t command, uint8\+\_\+t axis=\textbf{ TARE\+\_\+\+AXIS\+\_\+\+ALL}, uint8\+\_\+t rotation\+\_\+vector\+\_\+basis=\textbf{ TARE\+\_\+\+ROTATION\+\_\+\+VECTOR}) +\begin{DoxyCompactList}\small\item\em Queues a packet containing a command related to zeroing sensor\textquotesingle{}s axes. (See Ref. Manual 6.\+4.\+4.\+1) \end{DoxyCompactList}\item +void \textbf{ queue\+\_\+request\+\_\+product\+\_\+id\+\_\+command} () +\begin{DoxyCompactList}\small\item\em Queues a packet containing the request product ID command. \end{DoxyCompactList}\item +void \textbf{ spi\+\_\+task} () +\begin{DoxyCompactList}\small\item\em Task responsible for SPI transactions. Executed when HINT in is asserted by \doxyref{BNO08x}{p.}{class_b_n_o08x}. \end{DoxyCompactList}\end{DoxyCompactItemize} +\doxysubsubsection*{Static Private Member Functions} +\begin{DoxyCompactItemize} +\item +static void \textbf{ spi\+\_\+task\+\_\+trampoline} (void $\ast$arg) +\begin{DoxyCompactList}\small\item\em Static function used to launch spi task. \end{DoxyCompactList}\item +static void IRAM\+\_\+\+ATTR \textbf{ hint\+\_\+handler} (void $\ast$arg) +\begin{DoxyCompactList}\small\item\em HINT interrupt service routine, handles falling edge of \doxyref{BNO08x}{p.}{class_b_n_o08x} HINT pin. \end{DoxyCompactList}\end{DoxyCompactItemize} +\doxysubsubsection*{Private Attributes} +\begin{DoxyCompactItemize} +\item +\label{class_b_n_o08x_a5b1f13a3170f1c8fdcc886353efa0c08} +volatile uint8\+\_\+t {\bfseries tx\+\_\+packet\+\_\+queued} +\begin{DoxyCompactList}\small\item\em Whether or not a packet is currently waiting to be sent, a queued packet is sent on assertion of \doxyref{BNO08x}{p.}{class_b_n_o08x} HINT pin) \end{DoxyCompactList}\item +\label{class_b_n_o08x_aee2d0bcb8e9d7bacacccacbb04ded661} +Semaphore\+Handle\+\_\+t {\bfseries tx\+\_\+semaphore} +\begin{DoxyCompactList}\small\item\em Mutex semaphore used to prevent sending or receiving of packets if packet is currently being queued. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a7a85ccea09eadf865e8bbbf00d800e64} +uint8\+\_\+t {\bfseries rx\+\_\+buffer} [300] +\begin{DoxyCompactList}\small\item\em buffer used to receive packet with \doxyref{receive\+\_\+packet()}{p.}{class_b_n_o08x_ae540799865934fcff54caed0772df071} \end{DoxyCompactList}\item +\label{class_b_n_o08x_a74d936708ba924b6ba21004ff9a0b30b} +uint8\+\_\+t {\bfseries tx\+\_\+buffer} [50] +\begin{DoxyCompactList}\small\item\em buffer used for sending packet with \doxyref{send\+\_\+packet()}{p.}{class_b_n_o08x_a0ee58cedbc06d4a7db8821f40c0ee207} \end{DoxyCompactList}\item +\label{class_b_n_o08x_a908264b797fff9dc6679abde5e7584a5} +uint8\+\_\+t {\bfseries packet\+\_\+header\+\_\+rx} [4] +\begin{DoxyCompactList}\small\item\em SHTP header received with \doxyref{receive\+\_\+packet()}{p.}{class_b_n_o08x_ae540799865934fcff54caed0772df071} \end{DoxyCompactList}\item +\label{class_b_n_o08x_acbca88b37c8c5a590ca971b241dac64f} +uint8\+\_\+t {\bfseries commands} [20] +\begin{DoxyCompactList}\small\item\em Command to be sent with \doxyref{send\+\_\+packet()}{p.}{class_b_n_o08x_a0ee58cedbc06d4a7db8821f40c0ee207} \end{DoxyCompactList}\item +\label{class_b_n_o08x_aa722dbc6f6f07c63e9ea2a9271614af3} +uint8\+\_\+t {\bfseries sequence\+\_\+number} [6] +\begin{DoxyCompactList}\small\item\em Sequence num of each com channel, 6 in total. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a7bd032712a975e73e66bd72a3502baba} +uint32\+\_\+t {\bfseries meta\+\_\+data} [9] +\begin{DoxyCompactList}\small\item\em First 9 bytes of meta data returned from FRS read operation (we don\textquotesingle{}t really need the rest) (See Ref. Manual 5.\+1) \end{DoxyCompactList}\item +\label{class_b_n_o08x_ac1daa730e75d17e6afd1edaa288260ae} +uint8\+\_\+t {\bfseries command\+\_\+sequence\+\_\+number} = 0 +\begin{DoxyCompactList}\small\item\em Sequence num of command, sent within command packet. ~\newline + \end{DoxyCompactList}\item +\label{class_b_n_o08x_a6fbc6d086654b022a3ea53dfacd4fdf5} +uint16\+\_\+t {\bfseries packet\+\_\+length\+\_\+tx} = 0 +\begin{DoxyCompactList}\small\item\em Packet length to be sent with \doxyref{send\+\_\+packet()}{p.}{class_b_n_o08x_a0ee58cedbc06d4a7db8821f40c0ee207} \end{DoxyCompactList}\item +\label{class_b_n_o08x_af65e3fd0bfdb5b82dcf775e2c061c65a} +uint16\+\_\+t {\bfseries packet\+\_\+length\+\_\+rx} = 0 +\begin{DoxyCompactList}\small\item\em Packet length received (calculated from packet\+\_\+header\+\_\+rx) \end{DoxyCompactList}\item +\label{class_b_n_o08x_aeda443e9f608fccfec0e6770edc90c82} +\textbf{ bno08x\+\_\+config\+\_\+t} {\bfseries imu\+\_\+config} \{\} +\begin{DoxyCompactList}\small\item\em IMU configuration settings. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a982f065df42f00e53fd87c840efdb0f1} +spi\+\_\+bus\+\_\+config\+\_\+t {\bfseries bus\+\_\+config} \{\} +\begin{DoxyCompactList}\small\item\em SPI bus GPIO configuration settings. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a425a1f5a9f3232aadc685caaf4c2f82e} +spi\+\_\+device\+\_\+interface\+\_\+config\+\_\+t {\bfseries imu\+\_\+spi\+\_\+config} \{\} +\begin{DoxyCompactList}\small\item\em SPI slave device settings. \end{DoxyCompactList}\item +\label{class_b_n_o08x_acc0ea091465fc9a5736f5e0c6a0ce8ef} +spi\+\_\+device\+\_\+handle\+\_\+t {\bfseries spi\+\_\+hdl} \{\} +\begin{DoxyCompactList}\small\item\em SPI device handle. \end{DoxyCompactList}\item +\label{class_b_n_o08x_ac16adc5f00b0039c98a4921f13895026} +spi\+\_\+transaction\+\_\+t {\bfseries spi\+\_\+transaction} \{\} +\begin{DoxyCompactList}\small\item\em SPI transaction handle. \end{DoxyCompactList}\item +\label{class_b_n_o08x_abc972db20affbd0040b4e6c4892dd57b} +uint32\+\_\+t {\bfseries time\+\_\+stamp} +\begin{DoxyCompactList}\small\item\em Report timestamp (see datasheet 1.\+3.\+5.\+3) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a75fb2f06c5bbe26e3f3c794934ef954c} +uint16\+\_\+t {\bfseries raw\+\_\+accel\+\_\+X} +\item +\label{class_b_n_o08x_ab56e2ba505fa293d03e955137625c562} +uint16\+\_\+t {\bfseries raw\+\_\+accel\+\_\+Y} +\item +\label{class_b_n_o08x_af254d245b368027df6952b7d7522bd35} +uint16\+\_\+t {\bfseries raw\+\_\+accel\+\_\+Z} +\item +\label{class_b_n_o08x_a3365b7ebde01e284274e655c60343df9} +uint16\+\_\+t {\bfseries accel\+\_\+accuracy} +\begin{DoxyCompactList}\small\item\em Raw acceleration readings (See SH-\/2 Ref. Manual 6.\+5.\+8) \end{DoxyCompactList}\item +\label{class_b_n_o08x_ae1f71a432cb15e75f522fa18f29f4d50} +uint16\+\_\+t {\bfseries raw\+\_\+lin\+\_\+accel\+\_\+X} +\item +\label{class_b_n_o08x_aff3a5590471d1c9fc485a5610433915f} +uint16\+\_\+t {\bfseries raw\+\_\+lin\+\_\+accel\+\_\+Y} +\item +\label{class_b_n_o08x_abc8add47f1babc66c812a015614143d3} +uint16\+\_\+t {\bfseries raw\+\_\+lin\+\_\+accel\+\_\+Z} +\item +\label{class_b_n_o08x_a35e1635ef5edde8fc8640f978c6f2e3c} +uint16\+\_\+t {\bfseries accel\+\_\+lin\+\_\+accuracy} +\begin{DoxyCompactList}\small\item\em Raw linear acceleration (See SH-\/2 Ref. Manual 6.\+5.\+10) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a19696327a056a448ed5ba706e747bbe5} +uint16\+\_\+t {\bfseries raw\+\_\+gyro\+\_\+X} +\item +\label{class_b_n_o08x_a61df9f571555f5f682eb51f24a279489} +uint16\+\_\+t {\bfseries raw\+\_\+gyro\+\_\+Y} +\item +\label{class_b_n_o08x_a03f567cda2a3cc966301e96732fca9ad} +uint16\+\_\+t {\bfseries raw\+\_\+gyro\+\_\+Z} +\item +\label{class_b_n_o08x_a98ea35dd0fbd0c409d25fd8a6ed9f277} +uint16\+\_\+t {\bfseries gyro\+\_\+accuracy} +\begin{DoxyCompactList}\small\item\em Raw gyro reading (See SH-\/2 Ref. Manual 6.\+5.\+13) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a69dc7e97875060213085ba964b3bd987} +uint16\+\_\+t {\bfseries raw\+\_\+quat\+\_\+I} +\item +\label{class_b_n_o08x_a61ae05dc5572b326541bf8099f0c2a54} +uint16\+\_\+t {\bfseries raw\+\_\+quat\+\_\+J} +\item +\label{class_b_n_o08x_a7720c44ed1c0f1a0663d2adc5e1a1ea1} +uint16\+\_\+t {\bfseries raw\+\_\+quat\+\_\+K} +\item +\label{class_b_n_o08x_a867354267253ae828be4fae15c062db3} +uint16\+\_\+t {\bfseries raw\+\_\+quat\+\_\+real} +\item +\label{class_b_n_o08x_a033d6cb1aa137743b69cc3e401df67b7} +uint16\+\_\+t {\bfseries raw\+\_\+quat\+\_\+radian\+\_\+accuracy} +\item +\label{class_b_n_o08x_a36223f7124751fa71e860b2ef55dd2ac} +uint16\+\_\+t {\bfseries quat\+\_\+accuracy} +\begin{DoxyCompactList}\small\item\em Raw quaternion reading (See SH-\/2 Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item +\label{class_b_n_o08x_aa5bb03dbeabed729c012ec7164a3354f} +uint16\+\_\+t {\bfseries raw\+\_\+velocity\+\_\+gyro\+\_\+X} +\item +\label{class_b_n_o08x_a4f188bf76ba862f07606d1351d28548f} +uint16\+\_\+t {\bfseries raw\+\_\+velocity\+\_\+gyro\+\_\+Y} +\item +\label{class_b_n_o08x_ab49f9a6586d709bbd26280ef44a4bbf7} +uint16\+\_\+t {\bfseries raw\+\_\+velocity\+\_\+gyro\+\_\+Z} +\begin{DoxyCompactList}\small\item\em Raw gyro angular velocity reading (See SH-\/2 Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item +\label{class_b_n_o08x_af45016be9ea523d80be8467b2907b499} +uint16\+\_\+t {\bfseries gravity\+\_\+X} +\item +\label{class_b_n_o08x_af20dcd487a9fe8fa6243817d51e37be5} +uint16\+\_\+t {\bfseries gravity\+\_\+Y} +\item +\label{class_b_n_o08x_afa1cf5c3afbb258d97c55c5fb187f2d6} +uint16\+\_\+t {\bfseries gravity\+\_\+Z} +\item +\label{class_b_n_o08x_ae01698d287ea999179a11e2244902022} +uint16\+\_\+t {\bfseries gravity\+\_\+accuracy} +\begin{DoxyCompactList}\small\item\em Gravity reading in m/s$^\wedge$2 (See SH-\/2 Ref. Manual 6.\+5.\+11) \end{DoxyCompactList}\item +\label{class_b_n_o08x_afdc5cdb65bd0b36528b5b671b9d27053} +uint16\+\_\+t {\bfseries raw\+\_\+uncalib\+\_\+gyro\+\_\+X} +\item +\label{class_b_n_o08x_acc2c66e2985975266a286385ea855117} +uint16\+\_\+t {\bfseries raw\+\_\+uncalib\+\_\+gyro\+\_\+Y} +\item +\label{class_b_n_o08x_afac9dd4161f4c0051255293680c9082b} +uint16\+\_\+t {\bfseries raw\+\_\+uncalib\+\_\+gyro\+\_\+Z} +\item +\label{class_b_n_o08x_a8a2667f668317cee0a9fc4ef0accc3f5} +uint16\+\_\+t {\bfseries raw\+\_\+bias\+\_\+X} +\item +\label{class_b_n_o08x_ac38ff5eb93d3c3db0af2504ba02fd93c} +uint16\+\_\+t {\bfseries raw\+\_\+bias\+\_\+Y} +\item +\label{class_b_n_o08x_a0968eaed9b3d979a2caa1aba6e6b417a} +uint16\+\_\+t {\bfseries raw\+\_\+bias\+\_\+Z} +\item +\label{class_b_n_o08x_a081c666a3f24016d0ec5c5edc49f2903} +uint16\+\_\+t {\bfseries uncalib\+\_\+gyro\+\_\+accuracy} +\begin{DoxyCompactList}\small\item\em Uncalibrated gyro reading (See SH-\/2 Ref. Manual 6.\+5.\+14) \end{DoxyCompactList}\item +\label{class_b_n_o08x_aa5bdf740161b7c37adcac0154a410118} +uint16\+\_\+t {\bfseries raw\+\_\+magf\+\_\+X} +\item +\label{class_b_n_o08x_acd365418f24a6da61122c66d82086639} +uint16\+\_\+t {\bfseries raw\+\_\+magf\+\_\+Y} +\item +\label{class_b_n_o08x_ab4862de31d0874b44b6745678e1c905e} +uint16\+\_\+t {\bfseries raw\+\_\+magf\+\_\+Z} +\item +\label{class_b_n_o08x_ac5d4e151690774687efa951ca41c16ae} +uint16\+\_\+t {\bfseries magf\+\_\+accuracy} +\begin{DoxyCompactList}\small\item\em Calibrated magnetic field reading in u\+Tesla (See SH-\/2 Ref. Manual 6.\+5.\+16) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a1171a5738a4e6831ec7fa32a29f15554} +uint8\+\_\+t {\bfseries tap\+\_\+detector} +\begin{DoxyCompactList}\small\item\em Tap detector reading (See SH-\/2 Ref. Manual 6.\+5.\+27) \end{DoxyCompactList}\item +\label{class_b_n_o08x_ad80a77973371b12d722ea39063c648be} +uint16\+\_\+t {\bfseries step\+\_\+count} +\begin{DoxyCompactList}\small\item\em Step counter reading (See SH-\/2 Ref. Manual 6.\+5.\+29) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a1b12471e92536a79d0c425d77676f2e1} +uint8\+\_\+t {\bfseries stability\+\_\+classifier} +\begin{DoxyCompactList}\small\item\em Stability status reading (See SH-\/2 Ref. Manual 6.\+5.\+31) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a75cea49c1c08ca28d9fa7e5ed61c6e7b} +uint8\+\_\+t {\bfseries activity\+\_\+classifier} +\begin{DoxyCompactList}\small\item\em Activity status reading (See SH-\/2 Ref. Manual 6.\+5.\+36) \end{DoxyCompactList}\item +\label{class_b_n_o08x_af96e8cd070459f945ffbf01b98106e13} +uint8\+\_\+t $\ast$ {\bfseries activity\+\_\+confidences} +\begin{DoxyCompactList}\small\item\em Confidence of read activities (See SH-\/2 Ref. Manual 6.\+5.\+36) \end{DoxyCompactList}\item +\label{class_b_n_o08x_ad212b5028a31e857e76d251ced2724e1} +uint8\+\_\+t {\bfseries calibration\+\_\+status} +\begin{DoxyCompactList}\small\item\em Calibration status of device (See SH-\/2 Ref. Manual 6.\+4.\+7.\+1 \& 6.\+4.\+7.\+2) ~\newline + \end{DoxyCompactList}\item +\label{class_b_n_o08x_a937cbdc4edaac72c8cad041d79de5701} +uint16\+\_\+t {\bfseries mems\+\_\+raw\+\_\+accel\+\_\+X} +\item +\label{class_b_n_o08x_ad83cecb8a5d2be01db6792755b6057e9} +uint16\+\_\+t {\bfseries mems\+\_\+raw\+\_\+accel\+\_\+Y} +\item +\label{class_b_n_o08x_a59a4d75f1302ab693b1b26e9ccaa5341} +uint16\+\_\+t {\bfseries mems\+\_\+raw\+\_\+accel\+\_\+Z} +\begin{DoxyCompactList}\small\item\em Raw accelerometer readings from MEMS sensor (See SH2 Ref. Manual 6.\+5.\+8) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a3d6b6257462951ea023af7076c80f6dd} +uint16\+\_\+t {\bfseries mems\+\_\+raw\+\_\+gyro\+\_\+X} +\item +\label{class_b_n_o08x_ab6b142416912a096886dd63ad0beb865} +uint16\+\_\+t {\bfseries mems\+\_\+raw\+\_\+gyro\+\_\+Y} +\item +\label{class_b_n_o08x_ac35d5b12721ab876eaeb1f714a9b3b1d} +uint16\+\_\+t {\bfseries mems\+\_\+raw\+\_\+gyro\+\_\+Z} +\begin{DoxyCompactList}\small\item\em Raw gyro readings from MEMS sensor (See SH-\/2 Ref. Manual 6.\+5.\+12) \end{DoxyCompactList}\item +\label{class_b_n_o08x_ab587cdf991342b69b7fff3b33f537eb5} +uint16\+\_\+t {\bfseries mems\+\_\+raw\+\_\+magf\+\_\+X} +\item +\label{class_b_n_o08x_aad926054c81818fff611e10ed913706a} +uint16\+\_\+t {\bfseries mems\+\_\+raw\+\_\+magf\+\_\+Y} +\item +\label{class_b_n_o08x_a90f0cdf11decc276006f76a494d42ce3} +uint16\+\_\+t {\bfseries mems\+\_\+raw\+\_\+magf\+\_\+Z} +\begin{DoxyCompactList}\small\item\em Raw magnetometer (compass) readings from MEMS sensor (See SH-\/2 Ref. Manual 6.\+5.\+15) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a615090aae15f1b0410a7e5ecb94957b5} +Task\+Handle\+\_\+t {\bfseries spi\+\_\+task\+\_\+hdl} +\begin{DoxyCompactList}\small\item\em SPI task handle. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a496407fcd9c7c921bf5b3b062024b29d} +volatile bool {\bfseries int\+\_\+asserted} +\begin{DoxyCompactList}\small\item\em Interrupt asserted flag, sets true after hint\+\_\+handler ISR launches SPI task and it has run to completion. \end{DoxyCompactList}\end{DoxyCompactItemize} +\doxysubsubsection*{Static Private Attributes} +\begin{DoxyCompactItemize} +\item +\label{class_b_n_o08x_a6232920a05c0aba34e5560951a20ae87} +static \textbf{ bno08x\+\_\+config\+\_\+t} {\bfseries default\+\_\+imu\+\_\+config} +\begin{DoxyCompactList}\small\item\em default imu config settings \end{DoxyCompactList}\item +\label{class_b_n_o08x_a4882dbc698d7b730f57e2401037766a9} +static bool {\bfseries isr\+\_\+service\+\_\+installed} = \{false\} +\begin{DoxyCompactList}\small\item\em true of the isr service has been installed, only has to be done once regardless of how many devices are used \end{DoxyCompactList}\item +\label{class_b_n_o08x_a0b19c8f2de2b2bfe033da7f93cdd2608} +static const constexpr int16\+\_\+t {\bfseries ROTATION\+\_\+\+VECTOR\+\_\+\+Q1} = 14 +\begin{DoxyCompactList}\small\item\em Rotation vector Q point (See SH-\/2 Ref. Manual 6.\+5.\+18) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a923d65d8568cc31873ad56a3908e1939} +static const constexpr int16\+\_\+t {\bfseries ROTATION\+\_\+\+VECTOR\+\_\+\+ACCURACY\+\_\+\+Q1} = 12 +\begin{DoxyCompactList}\small\item\em Rotation vector accuracy estimate Q point (See SH-\/2 Ref. Manual 6.\+5.\+18) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a0564aaf5b20dc42b54db4fb3115ac1c7} +static const constexpr int16\+\_\+t {\bfseries ACCELEROMETER\+\_\+\+Q1} = 8 +\begin{DoxyCompactList}\small\item\em Acceleration Q point (See SH-\/2 Ref. Manual 6.\+5.\+9) \end{DoxyCompactList}\item +\label{class_b_n_o08x_ad0d37fe07ced24f2c9afc21145a74e7b} +static const constexpr int16\+\_\+t {\bfseries LINEAR\+\_\+\+ACCELEROMETER\+\_\+\+Q1} = 8 +\begin{DoxyCompactList}\small\item\em Linear acceleration Q point (See SH-\/2 Ref. Manual 6.\+5.\+10) \end{DoxyCompactList}\item +\label{class_b_n_o08x_aa3bec8effefa61cec6fa170e9d02c4dd} +static const constexpr int16\+\_\+t {\bfseries GYRO\+\_\+\+Q1} = 9 +\begin{DoxyCompactList}\small\item\em Gyro Q point (See SH-\/2 Ref. Manual 6.\+5.\+13) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a9fac9b811b7c2117675a784cb4df204c} +static const constexpr int16\+\_\+t {\bfseries MAGNETOMETER\+\_\+\+Q1} = 4 +\begin{DoxyCompactList}\small\item\em Magnetometer Q point (See SH-\/2 Ref. Manual 6.\+5.\+16) \end{DoxyCompactList}\item +\label{class_b_n_o08x_aafe117561fe9138800073a04a778b4ce} +static const constexpr int16\+\_\+t {\bfseries ANGULAR\+\_\+\+VELOCITY\+\_\+\+Q1} = 10 +\begin{DoxyCompactList}\small\item\em Angular velocity Q point (See SH-\/2 Ref. Manual 6.\+5.\+44) \end{DoxyCompactList}\item +\label{class_b_n_o08x_ae10722334dfce9635e76519598e165a2} +static const constexpr int16\+\_\+t {\bfseries GRAVITY\+\_\+\+Q1} = 8 +\begin{DoxyCompactList}\small\item\em Gravity Q point (See SH-\/2 Ref. Manual 6.\+5.\+11) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a53c4824accdff697948c10df30a15457} +static const constexpr uint64\+\_\+t {\bfseries HOST\+\_\+\+INT\+\_\+\+TIMEOUT\+\_\+\+US} = 150000\+ULL +\begin{DoxyCompactList}\small\item\em Max wait between HINT being asserted by \doxyref{BNO08x}{p.}{class_b_n_o08x} before transaction is considered failed. \end{DoxyCompactList}\item +\label{class_b_n_o08x_acd5b44d705af1f9aaa271a59a9d2d595} +static const constexpr uint8\+\_\+t {\bfseries CALIBRATE\+\_\+\+ACCEL} = 0 +\begin{DoxyCompactList}\small\item\em Calibrate accelerometer command used by queue\+\_\+calibrate\+\_\+command. \end{DoxyCompactList}\item +\label{class_b_n_o08x_aeac84719a1cc0f9c8d5a9a749391d4db} +static const constexpr uint8\+\_\+t {\bfseries CALIBRATE\+\_\+\+GYRO} = 1 +\begin{DoxyCompactList}\small\item\em Calibrate gyro command used by queue\+\_\+calibrate\+\_\+command. \end{DoxyCompactList}\item +\label{class_b_n_o08x_ac00e8b59ae8d710cf79956eaafa97ddb} +static const constexpr uint8\+\_\+t {\bfseries CALIBRATE\+\_\+\+MAG} = 2 +\begin{DoxyCompactList}\small\item\em Calibrate magnetometer command used by queue\+\_\+calibrate\+\_\+command. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a955dcb60da150490e17367a871b3a3d2} +static const constexpr uint8\+\_\+t {\bfseries CALIBRATE\+\_\+\+PLANAR\+\_\+\+ACCEL} = 3 +\begin{DoxyCompactList}\small\item\em Calibrate planar acceleration command used by queue\+\_\+calibrate\+\_\+command. \end{DoxyCompactList}\item +\label{class_b_n_o08x_af53d9e99f163d97ef92fe989b1dd25cc} +static const constexpr uint8\+\_\+t {\bfseries CALIBRATE\+\_\+\+ACCEL\+\_\+\+GYRO\+\_\+\+MAG} = 4 +\begin{DoxyCompactList}\small\item\em Calibrate accelerometer, gyro, \& magnetometer command used by queue\+\_\+calibrate\+\_\+command. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a584bfa04a39feb93279ee673c340db54} +static const constexpr uint8\+\_\+t {\bfseries CALIBRATE\+\_\+\+STOP} = 5 +\begin{DoxyCompactList}\small\item\em Stop calibration command used by queue\+\_\+calibrate\+\_\+command. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a384a1efc9857ad938be3bb44f871539b} +static const constexpr uint8\+\_\+t {\bfseries COMMAND\+\_\+\+ERRORS} = 1 +\item +\label{class_b_n_o08x_a93dd073c0cc1f3ccfde552649f6ebccc} +static const constexpr uint8\+\_\+t {\bfseries COMMAND\+\_\+\+COUNTER} = 2 +\item +\label{class_b_n_o08x_a0a1756bc16ba3eac45f4229b1e350107} +static const constexpr uint8\+\_\+t {\bfseries COMMAND\+\_\+\+TARE} = 3 +\begin{DoxyCompactList}\small\item\em Command and response to tare command (See Sh2 Ref. Manual 6.\+4.\+4) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a30eb6d305a187d4d36546841e12176b9} +static const constexpr uint8\+\_\+t {\bfseries COMMAND\+\_\+\+INITIALIZE} = 4 +\begin{DoxyCompactList}\small\item\em Reinitialize sensor hub components See (SH2 Ref. Manual 6.\+4.\+5) \end{DoxyCompactList}\item +\label{class_b_n_o08x_af124a6c1d8b871f3181b6c85f1099cb2} +static const constexpr uint8\+\_\+t {\bfseries COMMAND\+\_\+\+DCD} = 6 +\begin{DoxyCompactList}\small\item\em Save DCD command (See SH2 Ref. Manual 6.\+4.\+7) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a8381dfe403ddff522f172cb16780731a} +static const constexpr uint8\+\_\+t {\bfseries COMMAND\+\_\+\+ME\+\_\+\+CALIBRATE} = 7 +\begin{DoxyCompactList}\small\item\em Command and response to configure ME calibration (See SH2 Ref. Manual 6.\+4.\+7) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a7a246989c94cd87f68166b20b7ad4c8b} +static const constexpr uint8\+\_\+t {\bfseries COMMAND\+\_\+\+DCD\+\_\+\+PERIOD\+\_\+\+SAVE} = 9 +\begin{DoxyCompactList}\small\item\em Configure DCD periodic saving (See SH2 Ref. Manual 6.\+4) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a308c8b5307d93a67b5b9066d44494aa5} +static const constexpr uint8\+\_\+t {\bfseries COMMAND\+\_\+\+OSCILLATOR} = 10 +\begin{DoxyCompactList}\small\item\em Retrieve oscillator type command (See SH2 Ref. Manual 6.\+4) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a4f580b3cb232a762ea7019ee7b04d419} +static const constexpr uint8\+\_\+t {\bfseries COMMAND\+\_\+\+CLEAR\+\_\+\+DCD} = 11 +\begin{DoxyCompactList}\small\item\em Clear DCD \& Reset command (See SH2 Ref. Manual 6.\+4) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a1e5b64caa514b7e4fe64ab214758b875} +static const constexpr uint8\+\_\+t {\bfseries SHTP\+\_\+\+REPORT\+\_\+\+COMMAND\+\_\+\+RESPONSE} = 0x\+F1 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+3.\+9. \end{DoxyCompactList}\item +\label{class_b_n_o08x_ab04695dd189412092254e52bd6e5a75a} +static const constexpr uint8\+\_\+t {\bfseries SHTP\+\_\+\+REPORT\+\_\+\+COMMAND\+\_\+\+REQUEST} = 0x\+F2 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+3.\+8. \end{DoxyCompactList}\item +\label{class_b_n_o08x_aeb760b095dcf808a413ef696f2608e43} +static const constexpr uint8\+\_\+t {\bfseries SHTP\+\_\+\+REPORT\+\_\+\+FRS\+\_\+\+READ\+\_\+\+RESPONSE} = 0x\+F3 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+3.\+7. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a74af7eacc35cc825940b647c2de0d368} +static const constexpr uint8\+\_\+t {\bfseries SHTP\+\_\+\+REPORT\+\_\+\+FRS\+\_\+\+READ\+\_\+\+REQUEST} = 0x\+F4 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+3.\+6. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a0177134162e116501bc9483c6e4b76c3} +static const constexpr uint8\+\_\+t {\bfseries SHTP\+\_\+\+REPORT\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+RESPONSE} = 0x\+F8 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+3.\+2. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a542405639c28bd56bc4361b922763c95} +static const constexpr uint8\+\_\+t {\bfseries SHTP\+\_\+\+REPORT\+\_\+\+PRODUCT\+\_\+\+ID\+\_\+\+REQUEST} = 0x\+F9 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+3.\+1. \end{DoxyCompactList}\item +\label{class_b_n_o08x_ae37d6f8431c8c465bfb0c662772b5cb9} +static const constexpr uint8\+\_\+t {\bfseries SHTP\+\_\+\+REPORT\+\_\+\+BASE\+\_\+\+TIMESTAMP} = 0x\+FB +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 7.\+2.\+1. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a1d3bff4e20c2c3d47db322c9e34ef338} +static const constexpr uint8\+\_\+t {\bfseries SHTP\+\_\+\+REPORT\+\_\+\+SET\+\_\+\+FEATURE\+\_\+\+COMMAND} = 0x\+FD +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+4. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a476b35f11a2f096cdb70f7ee73cf2e90} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+ACCELEROMETER} = 0x01 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+9. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a29ab9f86763cce89e833392553f7abb4} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+GYROSCOPE} = 0x02 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+13. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a6f3bf6774ceb583c5c56f2ad80573834} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+MAGNETIC\+\_\+\+FIELD} = 0x03 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+16. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a53898b82dbac7ef27e1adb519dfcd686} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+LINEAR\+\_\+\+ACCELERATION} = 0x04 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+10. \end{DoxyCompactList}\item +\label{class_b_n_o08x_ab0279e8622ed188ee48411e074fb7e9d} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+ROTATION\+\_\+\+VECTOR} = 0x05 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+18. \end{DoxyCompactList}\item +\label{class_b_n_o08x_aeeb54b0b516917f3ff58cb655ae707a8} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+GRAVITY} = 0x06 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+11. \end{DoxyCompactList}\item +\label{class_b_n_o08x_ab94bfdbbffc0a7a255e752244b22322a} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+UNCALIBRATED\+\_\+\+GYRO} = 0x07 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+14. \end{DoxyCompactList}\item +\label{class_b_n_o08x_ab3dc8b362050d438d8a05b26e86af638} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR} = 0x08 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+19. \end{DoxyCompactList}\item +\label{class_b_n_o08x_aec618850b70a4e32a5148b05281aa8f0} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+GEOMAGNETIC\+\_\+\+ROTATION\+\_\+\+VECTOR} = 0x09 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+20. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a8b55a8131c251bb234d5391b0cd6aa48} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+GYRO\+\_\+\+INTEGRATED\+\_\+\+ROTATION\+\_\+\+VECTOR} = 0x2A +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+44. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a437fed4cb82edd32f839d88679ff8ed9} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+TAP\+\_\+\+DETECTOR} = 0x10 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+27. \end{DoxyCompactList}\item +\label{class_b_n_o08x_aaff9af63d5f35c05f0a1e485f3d97bc5} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+STEP\+\_\+\+COUNTER} = 0x11 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+29. \end{DoxyCompactList}\item +\label{class_b_n_o08x_afad93ba52698512205df714109cadcfc} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+STABILITY\+\_\+\+CLASSIFIER} = 0x13 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+31. \end{DoxyCompactList}\item +\label{class_b_n_o08x_aa8d2d5c66b72af3966dca751e7343a97} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+RAW\+\_\+\+ACCELEROMETER} = 0x14 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+8. \end{DoxyCompactList}\item +\label{class_b_n_o08x_aaed7faffc8f2bba8a2ae56933236f9f7} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+RAW\+\_\+\+GYROSCOPE} = 0x15 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+12. \end{DoxyCompactList}\item +\label{class_b_n_o08x_ac719a06278c239cc36f666b99a41b1c0} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+RAW\+\_\+\+MAGNETOMETER} = 0x16 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+15. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a001b45f56e347fb8e8149bcecbe2b40c} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+PERSONAL\+\_\+\+ACTIVITY\+\_\+\+CLASSIFIER} = 0x1E +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+36. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a263b8c25089c38f9ffa85493aef79606} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+AR\+\_\+\+VR\+\_\+\+STABILIZED\+\_\+\+ROTATION\+\_\+\+VECTOR} = 0x28 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+42. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a09dd6846e22801427b92b325385653e0} +static const constexpr uint8\+\_\+t {\bfseries SENSOR\+\_\+\+REPORTID\+\_\+\+AR\+\_\+\+VR\+\_\+\+STABILIZED\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR} = 0x29 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+5.\+43. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a27df630f3e52b35552d2c1f2cf3496b0} +static const constexpr uint8\+\_\+t {\bfseries TARE\+\_\+\+NOW} = 0 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+4.\+4.\+1. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a115aef7b38ec0dec2085f6917d832912} +static const constexpr uint8\+\_\+t {\bfseries TARE\+\_\+\+PERSIST} = 1 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+4.\+4.\+2. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a59cde7dd301c94a20b84735c5d49008e} +static const constexpr uint8\+\_\+t {\bfseries TARE\+\_\+\+SET\+\_\+\+REORIENTATION} = 2 +\begin{DoxyCompactList}\small\item\em See SH2 Ref. Manual 6.\+4.\+4.\+3. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a1ef13f6f330810934416ad5fe0ee55b2} +static const constexpr uint8\+\_\+t {\bfseries TARE\+\_\+\+AXIS\+\_\+\+ALL} = 0x07 +\begin{DoxyCompactList}\small\item\em Tare all axes (used with tare now command) \end{DoxyCompactList}\item +\label{class_b_n_o08x_aecb3e11c1ca5769fd60f42c17a105731} +static const constexpr uint8\+\_\+t {\bfseries TARE\+\_\+\+AXIS\+\_\+Z} = 0x04 +\begin{DoxyCompactList}\small\item\em Tar yaw axis only (used with tare now command) \end{DoxyCompactList}\item +\label{class_b_n_o08x_a8e2cfc25d0e34ae53a762b88cc3ac3c8} +static const constexpr uint8\+\_\+t {\bfseries TARE\+\_\+\+ROTATION\+\_\+\+VECTOR} = 0 +\begin{DoxyCompactList}\small\item\em Tare rotation vector. \end{DoxyCompactList}\item +\label{class_b_n_o08x_abaf1ec8bb197db1998a9ed3cec6180d5} +static const constexpr uint8\+\_\+t {\bfseries TARE\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR} = 1 +\begin{DoxyCompactList}\small\item\em Tare game rotation vector. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a225397a04d849e5647992ca80d68febb} +static const constexpr uint8\+\_\+t {\bfseries TARE\+\_\+\+GEOMAGNETIC\+\_\+\+ROTATION\+\_\+\+VECTOR} = 2 +\begin{DoxyCompactList}\small\item\em tare geomagnetic rotation vector \end{DoxyCompactList}\item +\label{class_b_n_o08x_a9ec354d75249f06f13599abf7bedfde0} +static const constexpr uint8\+\_\+t {\bfseries TARE\+\_\+\+GYRO\+\_\+\+INTEGRATED\+\_\+\+ROTATION\+\_\+\+VECTOR} = 3 +\begin{DoxyCompactList}\small\item\em Tare gyro integrated rotation vector. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a32204963cefc4ae64a80f43e71c8667a} +static const constexpr uint8\+\_\+t {\bfseries TARE\+\_\+\+AR\+\_\+\+VR\+\_\+\+STABILIZED\+\_\+\+ROTATION\+\_\+\+VECTOR} = 4 +\begin{DoxyCompactList}\small\item\em Tare ARVR stabilized rotation vector. \end{DoxyCompactList}\item +\label{class_b_n_o08x_aed8135fd5e7996ef06bf5968692ccd84} +static const constexpr uint8\+\_\+t {\bfseries TARE\+\_\+\+AR\+\_\+\+VR\+\_\+\+STABILIZED\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR} = 5 +\begin{DoxyCompactList}\small\item\em Tare ARVR stabilized game rotation vector. \end{DoxyCompactList}\item +\label{class_b_n_o08x_a2c98d5f2c406a3efd0b48c5666fa8c46} +static const constexpr char $\ast$ {\bfseries TAG} = \"{}BNO08x\"{} +\begin{DoxyCompactList}\small\item\em Class tag used for serial print statements. \end{DoxyCompactList}\end{DoxyCompactItemize} + + +\doxysubsection{Constructor \& Destructor Documentation} +\label{class_b_n_o08x_a40f7688e843d74b8bd526c6f5ff17845} +\index{BNO08x@{BNO08x}!BNO08x@{BNO08x}} +\index{BNO08x@{BNO08x}!BNO08x@{BNO08x}} +\doxysubsubsection{BNO08x()} +{\footnotesize\ttfamily BNO08x\+::\+BNO08x (\begin{DoxyParamCaption}\item[{\textbf{ bno08x\+\_\+config\+\_\+t}}]{imu\+\_\+config = {\ttfamily \textbf{ default\+\_\+imu\+\_\+config}} }\end{DoxyParamCaption})} + + + +\doxyref{BNO08x}{p.}{class_b_n_o08x} imu constructor. + +Construct a \doxyref{BNO08x}{p.}{class_b_n_o08x} object for managing a \doxyref{BNO08x}{p.}{class_b_n_o08x} sensor. Initializes required GPIO pins, interrupts, SPI peripheral, and local task for SPI transactions. + + +\begin{DoxyParams}{Parameters} +{\em imu\+\_\+config} & Configuration settings (optional), default settings can be seen in \doxyref{bno08x\+\_\+config\+\_\+t}{p.}{structbno08x__config__t} \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} + + +\doxysubsection{Member Function Documentation} +\label{class_b_n_o08x_aeffce374f558a167d5b5f19ad627e7cc} +\index{BNO08x@{BNO08x}!calibrate\_accelerometer@{calibrate\_accelerometer}} +\index{calibrate\_accelerometer@{calibrate\_accelerometer}!BNO08x@{BNO08x}} +\doxysubsubsection{calibrate\_accelerometer()} +{\footnotesize\ttfamily void BNO08x\+::calibrate\+\_\+accelerometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Sends command to calibrate accelerometer. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_afd0ca5f9b9741935543d143a5a43d128} +\index{BNO08x@{BNO08x}!calibrate\_all@{calibrate\_all}} +\index{calibrate\_all@{calibrate\_all}!BNO08x@{BNO08x}} +\doxysubsubsection{calibrate\_all()} +{\footnotesize\ttfamily void BNO08x\+::calibrate\+\_\+all (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Sends command to calibrate accelerometer, gyro, and magnetometer. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a9ada90f8ab6dd33fa2d7c168d9234af1} +\index{BNO08x@{BNO08x}!calibrate\_gyro@{calibrate\_gyro}} +\index{calibrate\_gyro@{calibrate\_gyro}!BNO08x@{BNO08x}} +\doxysubsubsection{calibrate\_gyro()} +{\footnotesize\ttfamily void BNO08x\+::calibrate\+\_\+gyro (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Sends command to calibrate gyro. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ac26350b55095a346d72598ab8aa74b4a} +\index{BNO08x@{BNO08x}!calibrate\_magnetometer@{calibrate\_magnetometer}} +\index{calibrate\_magnetometer@{calibrate\_magnetometer}!BNO08x@{BNO08x}} +\doxysubsubsection{calibrate\_magnetometer()} +{\footnotesize\ttfamily void BNO08x\+::calibrate\+\_\+magnetometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Sends command to calibrate magnetometer. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a1c6c49c97bc098db89db1aaa37e18f26} +\index{BNO08x@{BNO08x}!calibrate\_planar\_accelerometer@{calibrate\_planar\_accelerometer}} +\index{calibrate\_planar\_accelerometer@{calibrate\_planar\_accelerometer}!BNO08x@{BNO08x}} +\doxysubsubsection{calibrate\_planar\_accelerometer()} +{\footnotesize\ttfamily void BNO08x\+::calibrate\+\_\+planar\+\_\+accelerometer (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Sends command to calibrate planar accelerometer. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a71ca35f78b98d93d31eb0c187dc8543b} +\index{BNO08x@{BNO08x}!calibration\_complete@{calibration\_complete}} +\index{calibration\_complete@{calibration\_complete}!BNO08x@{BNO08x}} +\doxysubsubsection{calibration\_complete()} +{\footnotesize\ttfamily bool BNO08x\+::calibration\+\_\+complete (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Returns true if calibration has completed. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_afe39bfdede7b9a2b273983cb29a27d6e} +\index{BNO08x@{BNO08x}!clear\_tare@{clear\_tare}} +\index{clear\_tare@{clear\_tare}!BNO08x@{BNO08x}} +\doxysubsubsection{clear\_tare()} +{\footnotesize\ttfamily void BNO08x\+::clear\+\_\+tare (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Sends command to clear persistent tare settings in non-\/volatile memory of \doxyref{BNO08x}{p.}{class_b_n_o08x} (See Ref. Manual 6.\+4.\+4.\+3) + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a367d525d1c0ba119b3dca3067bb5bccc} +\index{BNO08x@{BNO08x}!data\_available@{data\_available}} +\index{data\_available@{data\_available}!BNO08x@{BNO08x}} +\doxysubsubsection{data\_available()} +{\footnotesize\ttfamily bool BNO08x\+::data\+\_\+available (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Checks if \doxyref{BNO08x}{p.}{class_b_n_o08x} has asserted interrupt and sent data. + +\begin{DoxyReturn}{Returns} +true if new data has been parsed and saved +\end{DoxyReturn} +\label{class_b_n_o08x_a1d68494d911f7efbbb620d349fb9da0d} +\index{BNO08x@{BNO08x}!enable\_accelerometer@{enable\_accelerometer}} +\index{enable\_accelerometer@{enable\_accelerometer}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_accelerometer()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+accelerometer (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable accelerometer reports (See Ref. Manual 6.\+5.\+9) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a0960ce957058af565dd4c43ad6c40225} +\index{BNO08x@{BNO08x}!enable\_activity\_classifier@{enable\_activity\_classifier}} +\index{enable\_activity\_classifier@{enable\_activity\_classifier}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_activity\_classifier()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+activity\+\_\+classifier (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports, }\item[{uint32\+\_\+t}]{activities\+\_\+to\+\_\+enable, }\item[{uint8\+\_\+t(\&)}]{activity\+\_\+confidence\+\_\+vals[9] }\end{DoxyParamCaption})} + + + +Sends command to enable activity classifier reports (See Ref. Manual 6.\+5.\+36) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +{\em activities\+\_\+to\+\_\+enable} & Desired activities to enable (0x1F enables all). \\ +\hline +{\em activity\+\_\+confidence\+\_\+vals} & Returned activity level confidences. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ad9e26658c53c728d7d10381db680765e} +\index{BNO08x@{BNO08x}!enable\_ARVR\_stabilized\_game\_rotation\_vector@{enable\_ARVR\_stabilized\_game\_rotation\_vector}} +\index{enable\_ARVR\_stabilized\_game\_rotation\_vector@{enable\_ARVR\_stabilized\_game\_rotation\_vector}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_ARVR\_stabilized\_game\_rotation\_vector()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+\+ARVR\+\_\+stabilized\+\_\+game\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable ARVR stabilized game rotation vector reports (See Ref. Manual 6.\+5.\+43) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a04290cb6ba09b93d5a9ef337c13d1abb} +\index{BNO08x@{BNO08x}!enable\_ARVR\_stabilized\_rotation\_vector@{enable\_ARVR\_stabilized\_rotation\_vector}} +\index{enable\_ARVR\_stabilized\_rotation\_vector@{enable\_ARVR\_stabilized\_rotation\_vector}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_ARVR\_stabilized\_rotation\_vector()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+\+ARVR\+\_\+stabilized\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable ARVR stabilized rotation vector reports (See Ref. Manual 6.\+5.\+42) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a639cb013ed17e0f33057742fac97f1a2} +\index{BNO08x@{BNO08x}!enable\_game\_rotation\_vector@{enable\_game\_rotation\_vector}} +\index{enable\_game\_rotation\_vector@{enable\_game\_rotation\_vector}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_game\_rotation\_vector()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+game\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable game rotation vector reports (See Ref. Manual 6.\+5.\+19) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a2dc0cd5bc04ca7eb3b4fffd2a3a6f27a} +\index{BNO08x@{BNO08x}!enable\_gravity@{enable\_gravity}} +\index{enable\_gravity@{enable\_gravity}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_gravity()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+gravity (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable gravity reading reports (See Ref. Manual 6.\+5.\+11) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a7619b598cc8e768c4df4805b2958a2c8} +\index{BNO08x@{BNO08x}!enable\_gyro@{enable\_gyro}} +\index{enable\_gyro@{enable\_gyro}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_gyro()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+gyro (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable gyro reports (See Ref. Manual 6.\+5.\+13) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a09a0306abec5895dd0450b2fe970347c} +\index{BNO08x@{BNO08x}!enable\_gyro\_integrated\_rotation\_vector@{enable\_gyro\_integrated\_rotation\_vector}} +\index{enable\_gyro\_integrated\_rotation\_vector@{enable\_gyro\_integrated\_rotation\_vector}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_gyro\_integrated\_rotation\_vector()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+gyro\+\_\+integrated\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable gyro integrated rotation vector reports (See Ref. Manual 6.\+5.\+44) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ad3724e7e602feb2b695d2d88a61d5328} +\index{BNO08x@{BNO08x}!enable\_linear\_accelerometer@{enable\_linear\_accelerometer}} +\index{enable\_linear\_accelerometer@{enable\_linear\_accelerometer}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_linear\_accelerometer()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+linear\+\_\+accelerometer (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable linear accelerometer reports (See Ref. Manual 6.\+5.\+10) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_acf4a83a44a221f6495263f00f1b8d849} +\index{BNO08x@{BNO08x}!enable\_magnetometer@{enable\_magnetometer}} +\index{enable\_magnetometer@{enable\_magnetometer}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_magnetometer()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+magnetometer (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable magnetometer reports (See Ref. Manual 6.\+5.\+16) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ad6adf3b24a8a559d3bb57e6abcef4ce8} +\index{BNO08x@{BNO08x}!enable\_raw\_accelerometer@{enable\_raw\_accelerometer}} +\index{enable\_raw\_accelerometer@{enable\_raw\_accelerometer}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_raw\_accelerometer()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+raw\+\_\+accelerometer (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable raw accelerometer reports (See Ref. Manual 6.\+5.\+8) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_af984deb77c92746fe4d193457312be63} +\index{BNO08x@{BNO08x}!enable\_raw\_gyro@{enable\_raw\_gyro}} +\index{enable\_raw\_gyro@{enable\_raw\_gyro}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_raw\_gyro()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+raw\+\_\+gyro (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable raw gyro reports (See Ref. Manual 6.\+5.\+12) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ad1ca07ee06ef98d4e11a74dde18e9623} +\index{BNO08x@{BNO08x}!enable\_raw\_magnetometer@{enable\_raw\_magnetometer}} +\index{enable\_raw\_magnetometer@{enable\_raw\_magnetometer}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_raw\_magnetometer()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+raw\+\_\+magnetometer (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable raw magnetometer reports (See Ref. Manual 6.\+5.\+15) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_abe9acd2eb1ce2f2e72b7a48c8d025cc4} +\index{BNO08x@{BNO08x}!enable\_rotation\_vector@{enable\_rotation\_vector}} +\index{enable\_rotation\_vector@{enable\_rotation\_vector}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_rotation\_vector()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+rotation\+\_\+vector (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable rotation vector reports (See Ref. Manual 6.\+5.\+18) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a5378a235e3114ccdc63b26bc3fae5dad} +\index{BNO08x@{BNO08x}!enable\_stability\_classifier@{enable\_stability\_classifier}} +\index{enable\_stability\_classifier@{enable\_stability\_classifier}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_stability\_classifier()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+stability\+\_\+classifier (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable activity stability classifier reports (See Ref. Manual 6.\+5.\+31) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ad550085fa1b51495ce3d8894538f33d5} +\index{BNO08x@{BNO08x}!enable\_step\_counter@{enable\_step\_counter}} +\index{enable\_step\_counter@{enable\_step\_counter}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_step\_counter()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+step\+\_\+counter (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable step counter reports (See Ref. Manual 6.\+5.\+29) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a919c7d94226f4c6adbb8edf6fd1613a9} +\index{BNO08x@{BNO08x}!enable\_tap\_detector@{enable\_tap\_detector}} +\index{enable\_tap\_detector@{enable\_tap\_detector}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_tap\_detector()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+tap\+\_\+detector (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable tap detector reports (See Ref. Manual 6.\+5.\+27) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ac7b5815c5ad8b83a34ad0855423601e8} +\index{BNO08x@{BNO08x}!enable\_uncalibrated\_gyro@{enable\_uncalibrated\_gyro}} +\index{enable\_uncalibrated\_gyro@{enable\_uncalibrated\_gyro}!BNO08x@{BNO08x}} +\doxysubsubsection{enable\_uncalibrated\_gyro()} +{\footnotesize\ttfamily void BNO08x\+::enable\+\_\+uncalibrated\+\_\+gyro (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})} + + + +Sends command to enable uncalibrated gyro reports (See Ref. Manual 6.\+5.\+14) + + +\begin{DoxyParams}{Parameters} +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ac9d9b6636745e8180807284da67c92a2} +\index{BNO08x@{BNO08x}!end\_calibration@{end\_calibration}} +\index{end\_calibration@{end\_calibration}!BNO08x@{BNO08x}} +\doxysubsubsection{end\_calibration()} +{\footnotesize\ttfamily void BNO08x\+::end\+\_\+calibration (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Sends command to end calibration procedure. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a40607e557eada666a5e1e416f42cd4a1} +\index{BNO08x@{BNO08x}!FRS\_read\_data@{FRS\_read\_data}} +\index{FRS\_read\_data@{FRS\_read\_data}!BNO08x@{BNO08x}} +\doxysubsubsection{FRS\_read\_data()} +{\footnotesize\ttfamily bool BNO08x\+::\+FRS\+\_\+read\+\_\+data (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID, }\item[{uint8\+\_\+t}]{start\+\_\+location, }\item[{uint8\+\_\+t}]{words\+\_\+to\+\_\+read }\end{DoxyParamCaption})} + + + +Read meta data from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.\+1 \& 6.\+3.\+7) + +Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. + + +\begin{DoxyParams}{Parameters} +{\em record\+\_\+\+ID} & Which record ID/ sensor to request meta data from. \\ +\hline +{\em start\+\_\+location} & Start byte location. \\ +\hline +{\em words\+\_\+to\+\_\+read} & Length of words to read.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +True if meta data read successfully. +\end{DoxyReturn} +\label{class_b_n_o08x_adf789e709ac1667656db757c8d559af9} +\index{BNO08x@{BNO08x}!FRS\_read\_request@{FRS\_read\_request}} +\index{FRS\_read\_request@{FRS\_read\_request}!BNO08x@{BNO08x}} +\doxysubsubsection{FRS\_read\_request()} +{\footnotesize\ttfamily bool BNO08x\+::\+FRS\+\_\+read\+\_\+request (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID, }\item[{uint16\+\_\+t}]{read\+\_\+offset, }\item[{uint16\+\_\+t}]{block\+\_\+size }\end{DoxyParamCaption})} + + + +Requests meta data from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system) given the record ID. Contains Q points and other info. (See Ref. Manual 5.\+1 \& 6.\+3.\+6) + +Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. + + +\begin{DoxyParams}{Parameters} +{\em record\+\_\+\+ID} & Which record ID/ sensor to request meta data from. \\ +\hline +{\em start\+\_\+location} & Start byte location. \\ +\hline +{\em words\+\_\+to\+\_\+read} & Length of words to read.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +True if read request acknowledged (HINT was asserted) +\end{DoxyReturn} +\label{class_b_n_o08x_a27f5dce5c994be18a587fb622574ad41} +\index{BNO08x@{BNO08x}!FRS\_read\_word@{FRS\_read\_word}} +\index{FRS\_read\_word@{FRS\_read\_word}!BNO08x@{BNO08x}} +\doxysubsubsection{FRS\_read\_word()} +{\footnotesize\ttfamily uint32\+\_\+t BNO08x\+::\+FRS\+\_\+read\+\_\+word (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID, }\item[{uint8\+\_\+t}]{word\+\_\+number }\end{DoxyParamCaption})} + + + +Reads meta data word from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system) given the record ID and word number. (See Ref. Manual 5.\+1 \& 6.\+3.\+7) + +Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. + + +\begin{DoxyParams}{Parameters} +{\em record\+\_\+\+ID} & Which record ID/ sensor to request meta data from. \\ +\hline +{\em word\+\_\+number} & Desired word to read.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +Requested meta data word, 0 if failed. +\end{DoxyReturn} +\label{class_b_n_o08x_a9329c6669282071622c3b3741b1b8142} +\index{BNO08x@{BNO08x}!get\_accel@{get\_accel}} +\index{get\_accel@{get\_accel}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_accel()} +{\footnotesize\ttfamily void BNO08x\+::get\+\_\+accel (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z, }\item[{uint8\+\_\+t \&}]{accuracy }\end{DoxyParamCaption})} + + + +Get full acceleration (total acceleration of device, units in m/s$^\wedge$2). + + +\begin{DoxyParams}{Parameters} +{\em x} & Reference variable to save X axis acceleration. \\ +\hline +{\em y} & Reference variable to save Y axis acceleration. \\ +\hline +{\em z} & Reference variable to save Z axis acceleration. \\ +\hline +{\em accuracy} & Reference variable to save reported acceleration accuracy.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a3fce726d5de821f97ed207036dae2900} +\index{BNO08x@{BNO08x}!get\_accel\_accuracy@{get\_accel\_accuracy}} +\index{get\_accel\_accuracy@{get\_accel\_accuracy}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_accel\_accuracy()} +{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::get\+\_\+accel\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get accuracy of linear acceleration. + +\begin{DoxyReturn}{Returns} +Accuracy of linear acceleration. +\end{DoxyReturn} +\label{class_b_n_o08x_abce574112a9079d2cbc58cfc352b8a69} +\index{BNO08x@{BNO08x}!get\_accel\_X@{get\_accel\_X}} +\index{get\_accel\_X@{get\_accel\_X}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_accel\_X()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+accel\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get x axis acceleration (total acceleration of device, units in m/s$^\wedge$2). + +\begin{DoxyReturn}{Returns} +The angular reported x axis acceleration. +\end{DoxyReturn} +\label{class_b_n_o08x_afdf24bb3d54518b23972f21f007817c1} +\index{BNO08x@{BNO08x}!get\_accel\_Y@{get\_accel\_Y}} +\index{get\_accel\_Y@{get\_accel\_Y}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_accel\_Y()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+accel\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get y axis acceleration (total acceleration of device, units in m/s$^\wedge$2). + +\begin{DoxyReturn}{Returns} +The angular reported y axis acceleration. +\end{DoxyReturn} +\label{class_b_n_o08x_a0a72477cb7a330fedbcb3e2126b882b1} +\index{BNO08x@{BNO08x}!get\_accel\_Z@{get\_accel\_Z}} +\index{get\_accel\_Z@{get\_accel\_Z}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_accel\_Z()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+accel\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get z axis acceleration (total acceleration of device, units in m/s$^\wedge$2). + +\begin{DoxyReturn}{Returns} +The angular reported z axis acceleration. +\end{DoxyReturn} +\label{class_b_n_o08x_a4f7060b2d3c15b359b70b6346730446a} +\index{BNO08x@{BNO08x}!get\_activity\_classifier@{get\_activity\_classifier}} +\index{get\_activity\_classifier@{get\_activity\_classifier}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_activity\_classifier()} +{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::get\+\_\+activity\+\_\+classifier (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the current activity classifier (Seee Ref. Manual 6.\+5.\+36) + +\begin{DoxyReturn}{Returns} +The current activity\+: 0 = unknown 1 = in vehicle 2 = on bicycle 3 = on foot 4 = still 5 = tilting 6 = walking 7 = runnning 8 = on stairs +\end{DoxyReturn} +\label{class_b_n_o08x_a386c46ac8965220ab7b9423df838dd4d} +\index{BNO08x@{BNO08x}!get\_gravity@{get\_gravity}} +\index{get\_gravity@{get\_gravity}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gravity()} +{\footnotesize\ttfamily void BNO08x\+::get\+\_\+gravity (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z, }\item[{uint8\+\_\+t \&}]{accuracy }\end{DoxyParamCaption})} + + + +Get full reported gravity vector, units in m/s$^\wedge$2. + + +\begin{DoxyParams}{Parameters} +{\em x} & Reference variable to save X axis gravity. \\ +\hline +{\em y} & Reference variable to save Y axis axis gravity. \\ +\hline +{\em z} & Reference variable to save Z axis axis gravity. \\ +\hline +{\em accuracy} & Reference variable to save reported gravity accuracy.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_accd39f48e9f8ab8267df7184b5b7cd76} +\index{BNO08x@{BNO08x}!get\_gravity\_accuracy@{get\_gravity\_accuracy}} +\index{get\_gravity\_accuracy@{get\_gravity\_accuracy}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gravity\_accuracy()} +{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::get\+\_\+gravity\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the reported gravity accuracy. + +\begin{DoxyReturn}{Returns} +Accuracy of reported gravity. ~\newline + +\end{DoxyReturn} +\label{class_b_n_o08x_a88679bccd9339b87ec35fc4fc4e745ae} +\index{BNO08x@{BNO08x}!get\_gravity\_X@{get\_gravity\_X}} +\index{get\_gravity\_X@{get\_gravity\_X}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gravity\_X()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+gravity\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the reported x axis gravity. + +\begin{DoxyReturn}{Returns} +x axis gravity in m/s$^\wedge$2 +\end{DoxyReturn} +\label{class_b_n_o08x_a8a36db7f1c932f33e05e494632059801} +\index{BNO08x@{BNO08x}!get\_gravity\_Y@{get\_gravity\_Y}} +\index{get\_gravity\_Y@{get\_gravity\_Y}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gravity\_Y()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+gravity\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the reported y axis gravity. + +\begin{DoxyReturn}{Returns} +y axis gravity in m/s$^\wedge$2 +\end{DoxyReturn} +\label{class_b_n_o08x_a5622b4d1754648ea7eb400c1adf9e807} +\index{BNO08x@{BNO08x}!get\_gravity\_Z@{get\_gravity\_Z}} +\index{get\_gravity\_Z@{get\_gravity\_Z}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gravity\_Z()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+gravity\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the reported z axis gravity. + +\begin{DoxyReturn}{Returns} +z axis gravity in m/s$^\wedge$2 +\end{DoxyReturn} +\label{class_b_n_o08x_a811999653110858311c97a779c388e5d} +\index{BNO08x@{BNO08x}!get\_gyro\_accuracy@{get\_gyro\_accuracy}} +\index{get\_gyro\_accuracy@{get\_gyro\_accuracy}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gyro\_accuracy()} +{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::get\+\_\+gyro\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get calibrated gyro accuracy. + +\begin{DoxyReturn}{Returns} +Accuracy of calibrated gyro. +\end{DoxyReturn} +\label{class_b_n_o08x_a4d3746a376a22acb7a2641bb750c4c89} +\index{BNO08x@{BNO08x}!get\_gyro\_calibrated\_velocity@{get\_gyro\_calibrated\_velocity}} +\index{get\_gyro\_calibrated\_velocity@{get\_gyro\_calibrated\_velocity}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gyro\_calibrated\_velocity()} +{\footnotesize\ttfamily void BNO08x\+::get\+\_\+gyro\+\_\+calibrated\+\_\+velocity (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z, }\item[{uint8\+\_\+t \&}]{accuracy }\end{DoxyParamCaption})} + + + +Get full rotational velocity with drift compensation (units in Rad/s). + + +\begin{DoxyParams}{Parameters} +{\em x} & Reference variable to save X axis angular velocity \\ +\hline +{\em y} & Reference variable to save Y axis angular velocity \\ +\hline +{\em z} & Reference variable to save Z axis angular velocity \\ +\hline +{\em accuracy} & Reference variable to save reported gyro accuracy.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ab7977391191067282e7f734b9ee45059} +\index{BNO08x@{BNO08x}!get\_gyro\_calibrated\_velocity\_X@{get\_gyro\_calibrated\_velocity\_X}} +\index{get\_gyro\_calibrated\_velocity\_X@{get\_gyro\_calibrated\_velocity\_X}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gyro\_calibrated\_velocity\_X()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+gyro\+\_\+calibrated\+\_\+velocity\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get calibrated gyro x axis angular velocity measurement. + +\begin{DoxyReturn}{Returns} +The angular reported x axis angular velocity from calibrated gyro (drift compensation applied). +\end{DoxyReturn} +\label{class_b_n_o08x_ad4fab6e636e239d4b9273f158983ed89} +\index{BNO08x@{BNO08x}!get\_gyro\_calibrated\_velocity\_Y@{get\_gyro\_calibrated\_velocity\_Y}} +\index{get\_gyro\_calibrated\_velocity\_Y@{get\_gyro\_calibrated\_velocity\_Y}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gyro\_calibrated\_velocity\_Y()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+gyro\+\_\+calibrated\+\_\+velocity\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get calibrated gyro y axis angular velocity measurement. + +\begin{DoxyReturn}{Returns} +The angular reported y axis angular velocity from calibrated gyro (drift compensation applied). +\end{DoxyReturn} +\label{class_b_n_o08x_a15a29c3bb476048b7229abcfb2b1d52a} +\index{BNO08x@{BNO08x}!get\_gyro\_calibrated\_velocity\_Z@{get\_gyro\_calibrated\_velocity\_Z}} +\index{get\_gyro\_calibrated\_velocity\_Z@{get\_gyro\_calibrated\_velocity\_Z}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gyro\_calibrated\_velocity\_Z()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+gyro\+\_\+calibrated\+\_\+velocity\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get calibrated gyro z axis angular velocity measurement. + +\begin{DoxyReturn}{Returns} +The angular reported z axis angular velocity from calibrated gyro (drift compensation applied). +\end{DoxyReturn} +\label{class_b_n_o08x_afe6392012669e7ebd1a9e817e2bd313f} +\index{BNO08x@{BNO08x}!get\_gyro\_velocity@{get\_gyro\_velocity}} +\index{get\_gyro\_velocity@{get\_gyro\_velocity}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gyro\_velocity()} +{\footnotesize\ttfamily void BNO08x\+::get\+\_\+gyro\+\_\+velocity (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z }\end{DoxyParamCaption})} + + + +Full rotational velocity from gyro-\/integrated rotation vector (See Ref. Manual 6.\+5.\+44) + + +\begin{DoxyParams}{Parameters} +{\em x} & Reference variable to save X axis angular velocity \\ +\hline +{\em y} & Reference variable to save Y axis angular velocity \\ +\hline +{\em z} & Reference variable to save Z axis angular velocity\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_acd376cd3e454a87198ec86accbf2ee00} +\index{BNO08x@{BNO08x}!get\_gyro\_velocity\_X@{get\_gyro\_velocity\_X}} +\index{get\_gyro\_velocity\_X@{get\_gyro\_velocity\_X}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gyro\_velocity\_X()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+gyro\+\_\+velocity\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get x axis angular velocity from gyro-\/integrated rotation vector. (See Ref. Manual 6.\+5.\+44) + +\begin{DoxyReturn}{Returns} +The reported x axis angular velocity. +\end{DoxyReturn} +\label{class_b_n_o08x_acd1819a81818f90dc105950b4a7d0b04} +\index{BNO08x@{BNO08x}!get\_gyro\_velocity\_Y@{get\_gyro\_velocity\_Y}} +\index{get\_gyro\_velocity\_Y@{get\_gyro\_velocity\_Y}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gyro\_velocity\_Y()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+gyro\+\_\+velocity\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get y axis angular velocity from gyro-\/integrated rotation vector. (See Ref. Manual 6.\+5.\+44) + +\begin{DoxyReturn}{Returns} +The reported y axis angular velocity. +\end{DoxyReturn} +\label{class_b_n_o08x_ae2add976af256ec981248371a2f58207} +\index{BNO08x@{BNO08x}!get\_gyro\_velocity\_Z@{get\_gyro\_velocity\_Z}} +\index{get\_gyro\_velocity\_Z@{get\_gyro\_velocity\_Z}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_gyro\_velocity\_Z()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+gyro\+\_\+velocity\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get z axis angular velocity from gyro-\/integrated rotation vector. (See Ref. Manual 6.\+5.\+44) + +\begin{DoxyReturn}{Returns} +The reported Z axis angular velocity. +\end{DoxyReturn} +\label{class_b_n_o08x_ad59b029d04341dbef72e059488951980} +\index{BNO08x@{BNO08x}!get\_linear\_accel@{get\_linear\_accel}} +\index{get\_linear\_accel@{get\_linear\_accel}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_linear\_accel()} +{\footnotesize\ttfamily void BNO08x\+::get\+\_\+linear\+\_\+accel (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z, }\item[{uint8\+\_\+t \&}]{accuracy }\end{DoxyParamCaption})} + + + +Get full linear acceleration (acceleration of the device minus gravity, units in m/s$^\wedge$2). + + +\begin{DoxyParams}{Parameters} +{\em x} & Reference variable to save X axis acceleration. \\ +\hline +{\em y} & Reference variable to save Y axis acceleration. \\ +\hline +{\em z} & Reference variable to save Z axis acceleration. \\ +\hline +{\em accuracy} & Reference variable to save reported linear acceleration accuracy.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a33fe3c2f47759cfae5f4b612ddd329ea} +\index{BNO08x@{BNO08x}!get\_linear\_accel\_accuracy@{get\_linear\_accel\_accuracy}} +\index{get\_linear\_accel\_accuracy@{get\_linear\_accel\_accuracy}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_linear\_accel\_accuracy()} +{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::get\+\_\+linear\+\_\+accel\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get accuracy of linear acceleration. + +\begin{DoxyReturn}{Returns} +Accuracy of linear acceleration. +\end{DoxyReturn} +\label{class_b_n_o08x_a763c3a9699a1081d430fd9b9b7bc49a3} +\index{BNO08x@{BNO08x}!get\_linear\_accel\_X@{get\_linear\_accel\_X}} +\index{get\_linear\_accel\_X@{get\_linear\_accel\_X}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_linear\_accel\_X()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+linear\+\_\+accel\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get x axis linear acceleration (acceleration of device minus gravity, units in m/s$^\wedge$2) + +\begin{DoxyReturn}{Returns} +The angular reported x axis linear acceleration. +\end{DoxyReturn} +\label{class_b_n_o08x_a1033bdd65b42b6706d1dfc67ece66191} +\index{BNO08x@{BNO08x}!get\_linear\_accel\_Y@{get\_linear\_accel\_Y}} +\index{get\_linear\_accel\_Y@{get\_linear\_accel\_Y}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_linear\_accel\_Y()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+linear\+\_\+accel\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get y axis linear acceleration (acceleration of device minus gravity, units in m/s$^\wedge$2) + +\begin{DoxyReturn}{Returns} +The angular reported y axis linear acceleration. +\end{DoxyReturn} +\label{class_b_n_o08x_afdfa7d50362702da689c5d18bf17fd84} +\index{BNO08x@{BNO08x}!get\_linear\_accel\_Z@{get\_linear\_accel\_Z}} +\index{get\_linear\_accel\_Z@{get\_linear\_accel\_Z}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_linear\_accel\_Z()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+linear\+\_\+accel\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get z axis linear acceleration (acceleration of device minus gravity, units in m/s$^\wedge$2) + +\begin{DoxyReturn}{Returns} +The angular reported z axis linear acceleration. +\end{DoxyReturn} +\label{class_b_n_o08x_a35a224d519a2a243d0d526a34ecde5a8} +\index{BNO08x@{BNO08x}!get\_magf@{get\_magf}} +\index{get\_magf@{get\_magf}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_magf()} +{\footnotesize\ttfamily void BNO08x\+::get\+\_\+magf (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z, }\item[{uint8\+\_\+t \&}]{accuracy }\end{DoxyParamCaption})} + + + +Get the full magnetic field vector. + + +\begin{DoxyParams}{Parameters} +{\em x} & Reference variable to save reported x magnitude. \\ +\hline +{\em y} & Reference variable to save reported y magnitude. \\ +\hline +{\em x} & Reference variable to save reported z magnitude. \\ +\hline +{\em accuracy} & Reference variable save reported accuracy.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a487391e6b2dd7f05084804d1fb94976f} +\index{BNO08x@{BNO08x}!get\_magf\_accuracy@{get\_magf\_accuracy}} +\index{get\_magf\_accuracy@{get\_magf\_accuracy}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_magf\_accuracy()} +{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::get\+\_\+magf\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get accuracy of reported magnetic field vector. + +\begin{DoxyReturn}{Returns} +The accuracy of reported magnetic field vector. +\end{DoxyReturn} +\label{class_b_n_o08x_a111601243b913751eb51c1f37cba4e7d} +\index{BNO08x@{BNO08x}!get\_magf\_X@{get\_magf\_X}} +\index{get\_magf\_X@{get\_magf\_X}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_magf\_X()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+magf\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get X component of magnetic field vector. + +\begin{DoxyReturn}{Returns} +The reported X component of magnetic field vector. +\end{DoxyReturn} +\label{class_b_n_o08x_a82ed8d7b9a5c25374839df75a3d220ea} +\index{BNO08x@{BNO08x}!get\_magf\_Y@{get\_magf\_Y}} +\index{get\_magf\_Y@{get\_magf\_Y}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_magf\_Y()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+magf\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get Y component of magnetic field vector. + +\begin{DoxyReturn}{Returns} +The reported Y component of magnetic field vector. +\end{DoxyReturn} +\label{class_b_n_o08x_ab4c48a91d2f8b29430abc17b7f015282} +\index{BNO08x@{BNO08x}!get\_magf\_Z@{get\_magf\_Z}} +\index{get\_magf\_Z@{get\_magf\_Z}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_magf\_Z()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+magf\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get Z component of magnetic field vector. + +\begin{DoxyReturn}{Returns} +The reported Z component of magnetic field vector. +\end{DoxyReturn} +\label{class_b_n_o08x_a1b91f234d81c45f1f5ca2f27c9f0f6a3} +\index{BNO08x@{BNO08x}!get\_pitch@{get\_pitch}} +\index{get\_pitch@{get\_pitch}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_pitch()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+pitch (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the reported rotation about y axis. + +\begin{DoxyReturn}{Returns} +Rotation about the y axis in radians. +\end{DoxyReturn} +\label{class_b_n_o08x_af50010400cbd1445e9ddfa259384b412} +\index{BNO08x@{BNO08x}!get\_pitch\_deg@{get\_pitch\_deg}} +\index{get\_pitch\_deg@{get\_pitch\_deg}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_pitch\_deg()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+pitch\+\_\+deg (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the reported rotation about y axis. + +\begin{DoxyReturn}{Returns} +Rotation about the y axis in degrees. +\end{DoxyReturn} +\label{class_b_n_o08x_a4421c43323945946ad605f8422958dcf} +\index{BNO08x@{BNO08x}!get\_Q1@{get\_Q1}} +\index{get\_Q1@{get\_Q1}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_Q1()} +{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+\+Q1 (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID }\end{DoxyParamCaption})} + + + +Gets Q1 point from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system). + +Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. + + +\begin{DoxyParams}{Parameters} +{\em record\+\_\+\+ID} & Which record ID/ sensor to get Q1 value for.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +Q1 value for requested sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_a954dccdcbe8a8c4f1787f13ebb8d932b} +\index{BNO08x@{BNO08x}!get\_Q2@{get\_Q2}} +\index{get\_Q2@{get\_Q2}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_Q2()} +{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+\+Q2 (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID }\end{DoxyParamCaption})} + + + +Gets Q2 point from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system). + +Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. + + +\begin{DoxyParams}{Parameters} +{\em record\+\_\+\+ID} & Which record ID/ sensor to get Q2 value for.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +Q2 value for requested sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_a1590ba793668f9cb1a32a1f4dd07cb9a} +\index{BNO08x@{BNO08x}!get\_Q3@{get\_Q3}} +\index{get\_Q3@{get\_Q3}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_Q3()} +{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+\+Q3 (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID }\end{DoxyParamCaption})} + + + +Gets Q3 point from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system). + +Note that Q points from the data sheet can be used as well, using the ones stored in flash is optional. + + +\begin{DoxyParams}{Parameters} +{\em record\+\_\+\+ID} & Which record ID/ sensor to get Q3 value for.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +Q3 value for requested sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_a51a6d594824de2292e70f788454f8a2d} +\index{BNO08x@{BNO08x}!get\_quat@{get\_quat}} +\index{get\_quat@{get\_quat}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_quat()} +{\footnotesize\ttfamily void BNO08x\+::get\+\_\+quat (\begin{DoxyParamCaption}\item[{float \&}]{i, }\item[{float \&}]{j, }\item[{float \&}]{k, }\item[{float \&}]{real, }\item[{float \&}]{rad\+\_\+accuracy, }\item[{uint8\+\_\+t \&}]{accuracy }\end{DoxyParamCaption})} + + + +Get the full quaternion reading. + + +\begin{DoxyParams}{Parameters} +{\em i} & Reference variable to save reported i component of quaternion. \\ +\hline +{\em j} & Reference variable to save reported j component of quaternion. \\ +\hline +{\em k} & Reference variable to save reported k component of quaternion. \\ +\hline +{\em real} & Reference variable to save reported real component of quaternion. \\ +\hline +{\em rad\+\_\+accuracy} & Reference variable to save reported raw quaternion radian accuracy. \\ +\hline +{\em accuracy} & Reference variable to save reported quaternion accuracy.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a24ba760d064a1dc45f972c79b9c8d98d} +\index{BNO08x@{BNO08x}!get\_quat\_accuracy@{get\_quat\_accuracy}} +\index{get\_quat\_accuracy@{get\_quat\_accuracy}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_quat\_accuracy()} +{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::get\+\_\+quat\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get accuracy of reported quaternion. + +\begin{DoxyReturn}{Returns} +The accuracy of reported quaternion. +\end{DoxyReturn} +\label{class_b_n_o08x_a12c12a8e078b28480fb8828d306656f5} +\index{BNO08x@{BNO08x}!get\_quat\_I@{get\_quat\_I}} +\index{get\_quat\_I@{get\_quat\_I}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_quat\_I()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+quat\+\_\+I (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get I component of reported quaternion. + +\begin{DoxyReturn}{Returns} +The I component of reported quaternion. +\end{DoxyReturn} +\label{class_b_n_o08x_a9f6bb642fa0297a7b9bcc94dd7374015} +\index{BNO08x@{BNO08x}!get\_quat\_J@{get\_quat\_J}} +\index{get\_quat\_J@{get\_quat\_J}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_quat\_J()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+quat\+\_\+J (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get J component of reported quaternion. + +\begin{DoxyReturn}{Returns} +The J component of reported quaternion. +\end{DoxyReturn} +\label{class_b_n_o08x_a9f42c70c2337a0d831064a40ecfe2dd8} +\index{BNO08x@{BNO08x}!get\_quat\_K@{get\_quat\_K}} +\index{get\_quat\_K@{get\_quat\_K}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_quat\_K()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+quat\+\_\+K (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get K component of reported quaternion. + +\begin{DoxyReturn}{Returns} +The K component of reported quaternion. +\end{DoxyReturn} +\label{class_b_n_o08x_a61b7d10a98afc6903fea6b2cede27630} +\index{BNO08x@{BNO08x}!get\_quat\_radian\_accuracy@{get\_quat\_radian\_accuracy}} +\index{get\_quat\_radian\_accuracy@{get\_quat\_radian\_accuracy}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_quat\_radian\_accuracy()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+quat\+\_\+radian\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get radian accuracy of reported quaternion. + +\begin{DoxyReturn}{Returns} +The radian accuracy of reported quaternion. +\end{DoxyReturn} +\label{class_b_n_o08x_a5a556c5ec1baaa7f1156779dbe47a7b7} +\index{BNO08x@{BNO08x}!get\_quat\_real@{get\_quat\_real}} +\index{get\_quat\_real@{get\_quat\_real}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_quat\_real()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+quat\+\_\+real (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get real component of reported quaternion. + +\begin{DoxyReturn}{Returns} +The real component of reported quaternion. +\end{DoxyReturn} +\label{class_b_n_o08x_a0fff04c42c9502615ad73cd1457cb9b0} +\index{BNO08x@{BNO08x}!get\_range@{get\_range}} +\index{get\_range@{get\_range}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_range()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+range (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID }\end{DoxyParamCaption})} + + + +Gets range from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system). + + +\begin{DoxyParams}{Parameters} +{\em record\+\_\+\+ID} & Which record ID/ sensor to get range value for.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +The range value for the requested sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_a1de356dd604c1dffcd1a32faeb4fafe2} +\index{BNO08x@{BNO08x}!get\_raw\_accel\_X@{get\_raw\_accel\_X}} +\index{get\_raw\_accel\_X@{get\_raw\_accel\_X}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_raw\_accel\_X()} +{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+accel\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get raw accelerometer x axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8) + +\begin{DoxyReturn}{Returns} +Reported raw accelerometer x axis reading from physical MEMs sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_a96563de0eb597a52d595d19da827b1ac} +\index{BNO08x@{BNO08x}!get\_raw\_accel\_Y@{get\_raw\_accel\_Y}} +\index{get\_raw\_accel\_Y@{get\_raw\_accel\_Y}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_raw\_accel\_Y()} +{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+accel\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get raw accelerometer y axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8) + +\begin{DoxyReturn}{Returns} +Reported raw accelerometer y axis reading from physical MEMs sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_a718cdd910e5e7e03fd0a1ad04ee6f0ce} +\index{BNO08x@{BNO08x}!get\_raw\_accel\_Z@{get\_raw\_accel\_Z}} +\index{get\_raw\_accel\_Z@{get\_raw\_accel\_Z}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_raw\_accel\_Z()} +{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+accel\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get raw accelerometer z axis reading from physical accelerometer MEMs sensor (See Ref. Manual 6.\+5.\+8) + +\begin{DoxyReturn}{Returns} +Reported raw accelerometer z axis reading from physical MEMs sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_af1b2c3a383a84fc6dfaddae1052b44d4} +\index{BNO08x@{BNO08x}!get\_raw\_gyro\_X@{get\_raw\_gyro\_X}} +\index{get\_raw\_gyro\_X@{get\_raw\_gyro\_X}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_raw\_gyro\_X()} +{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+gyro\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get raw gyroscope x axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) + +\begin{DoxyReturn}{Returns} +Reported raw gyroscope x axis reading from physical MEMs sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_aff7714441d242b3b9b0c03f94e0a9374} +\index{BNO08x@{BNO08x}!get\_raw\_gyro\_Y@{get\_raw\_gyro\_Y}} +\index{get\_raw\_gyro\_Y@{get\_raw\_gyro\_Y}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_raw\_gyro\_Y()} +{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+gyro\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get raw gyroscope y axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) + +\begin{DoxyReturn}{Returns} +Reported raw gyroscope y axis reading from physical MEMs sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_a2e28b5a79c442a6baa2fa5165b9ce37d} +\index{BNO08x@{BNO08x}!get\_raw\_gyro\_Z@{get\_raw\_gyro\_Z}} +\index{get\_raw\_gyro\_Z@{get\_raw\_gyro\_Z}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_raw\_gyro\_Z()} +{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+gyro\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get raw gyroscope z axis reading from physical gyroscope MEMs sensor (See Ref. Manual 6.\+5.\+12) + +\begin{DoxyReturn}{Returns} +Reported raw gyroscope z axis reading from physical MEMs sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_adf12600b39de41d258439a343fcc1ad8} +\index{BNO08x@{BNO08x}!get\_raw\_magf\_X@{get\_raw\_magf\_X}} +\index{get\_raw\_magf\_X@{get\_raw\_magf\_X}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_raw\_magf\_X()} +{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+magf\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get raw magnetometer x axis reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) + +\begin{DoxyReturn}{Returns} +Reported raw magnetometer x axis reading from physical magnetometer sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_a2c842e43ceae19149f6525bcbc48f1cf} +\index{BNO08x@{BNO08x}!get\_raw\_magf\_Y@{get\_raw\_magf\_Y}} +\index{get\_raw\_magf\_Y@{get\_raw\_magf\_Y}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_raw\_magf\_Y()} +{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+magf\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get raw magnetometer y axis reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) + +\begin{DoxyReturn}{Returns} +Reported raw magnetometer y axis reading from physical magnetometer sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_a99c1bcc2ec3ca3d8feafd6dd61f9d269} +\index{BNO08x@{BNO08x}!get\_raw\_magf\_Z@{get\_raw\_magf\_Z}} +\index{get\_raw\_magf\_Z@{get\_raw\_magf\_Z}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_raw\_magf\_Z()} +{\footnotesize\ttfamily int16\+\_\+t BNO08x\+::get\+\_\+raw\+\_\+magf\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get raw magnetometer z axis reading from physical magnetometer sensor (See Ref. Manual 6.\+5.\+15) + +\begin{DoxyReturn}{Returns} +Reported raw magnetometer z axis reading from physical magnetometer sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_a9cc47f0e5b7d679c80992c993a910ccf} +\index{BNO08x@{BNO08x}!get\_readings@{get\_readings}} +\index{get\_readings@{get\_readings}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_readings()} +{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::get\+\_\+readings (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Waits for \doxyref{BNO08x}{p.}{class_b_n_o08x} HINT pin to assert, and parses the received data. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a11bb1b3fa44ad8f28c1492b5c07af886} +\index{BNO08x@{BNO08x}!get\_reset\_reason@{get\_reset\_reason}} +\index{get\_reset\_reason@{get\_reset\_reason}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_reset\_reason()} +{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::get\+\_\+reset\+\_\+reason (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the reason for the most recent reset. + +\begin{DoxyReturn}{Returns} +The reason for the most recent recent reset ( 1 = POR (power on reset), 2 = internal reset, 3 = watchdog timer, 4 = external reset 5 = other) +\end{DoxyReturn} +\label{class_b_n_o08x_a1d6ea02d0d4b23ff6a15e9d5c6c92372} +\index{BNO08x@{BNO08x}!get\_resolution@{get\_resolution}} +\index{get\_resolution@{get\_resolution}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_resolution()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+resolution (\begin{DoxyParamCaption}\item[{uint16\+\_\+t}]{record\+\_\+\+ID }\end{DoxyParamCaption})} + + + +Gets resolution from \doxyref{BNO08x}{p.}{class_b_n_o08x} FRS (flash record system). + + +\begin{DoxyParams}{Parameters} +{\em record\+\_\+\+ID} & Which record ID/ sensor to get resolution value for.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +The resolution value for the requested sensor. +\end{DoxyReturn} +\label{class_b_n_o08x_a89618eba08186ee8e679e7313907ddef} +\index{BNO08x@{BNO08x}!get\_roll@{get\_roll}} +\index{get\_roll@{get\_roll}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_roll()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+roll (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the reported rotation about x axis. + +\begin{DoxyReturn}{Returns} +Rotation about the x axis in radians. +\end{DoxyReturn} +\label{class_b_n_o08x_a7077b9a130f1dcf0192454e387968dd6} +\index{BNO08x@{BNO08x}!get\_roll\_deg@{get\_roll\_deg}} +\index{get\_roll\_deg@{get\_roll\_deg}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_roll\_deg()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+roll\+\_\+deg (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the reported rotation about x axis. + +\begin{DoxyReturn}{Returns} +Rotation about the x axis in degrees. +\end{DoxyReturn} +\label{class_b_n_o08x_a0d148e00abcfeec48c689e3084a7e786} +\index{BNO08x@{BNO08x}!get\_stability\_classifier@{get\_stability\_classifier}} +\index{get\_stability\_classifier@{get\_stability\_classifier}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_stability\_classifier()} +{\footnotesize\ttfamily int8\+\_\+t BNO08x\+::get\+\_\+stability\+\_\+classifier (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the current stability classifier (Seee Ref. Manual 6.\+5.\+31) + +\begin{DoxyReturn}{Returns} +The current stability (0 = unknown, 1 = on table, 2 = stationary) +\end{DoxyReturn} +\label{class_b_n_o08x_adaff49f3d80fdd19fd4210f0c56d41ef} +\index{BNO08x@{BNO08x}!get\_step\_count@{get\_step\_count}} +\index{get\_step\_count@{get\_step\_count}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_step\_count()} +{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::get\+\_\+step\+\_\+count (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the counted amount of steps. + +\begin{DoxyReturn}{Returns} +The current amount of counted steps. +\end{DoxyReturn} +\label{class_b_n_o08x_a4797ec731de4c158716da1a7af9d1602} +\index{BNO08x@{BNO08x}!get\_tap\_detector@{get\_tap\_detector}} +\index{get\_tap\_detector@{get\_tap\_detector}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_tap\_detector()} +{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::get\+\_\+tap\+\_\+detector (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get if tap has occured. + +\begin{DoxyReturn}{Returns} +7 bit tap code indicated which axis taps have occurred. (See Ref. Manual 6.\+5.\+27) +\end{DoxyReturn} +\label{class_b_n_o08x_ad9137777271421a58159f3fe5e05ed20} +\index{BNO08x@{BNO08x}!get\_time\_stamp@{get\_time\_stamp}} +\index{get\_time\_stamp@{get\_time\_stamp}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_time\_stamp()} +{\footnotesize\ttfamily uint32\+\_\+t BNO08x\+::get\+\_\+time\+\_\+stamp (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Return timestamp of most recent report. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a1bd3c33e70354bd35a78b83b6786b531} +\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro@{get\_uncalibrated\_gyro}} +\index{get\_uncalibrated\_gyro@{get\_uncalibrated\_gyro}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_uncalibrated\_gyro()} +{\footnotesize\ttfamily void BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro (\begin{DoxyParamCaption}\item[{float \&}]{x, }\item[{float \&}]{y, }\item[{float \&}]{z, }\item[{float \&}]{b\+\_\+x, }\item[{float \&}]{b\+\_\+y, }\item[{float \&}]{b\+\_\+z, }\item[{uint8\+\_\+t \&}]{accuracy }\end{DoxyParamCaption})} + + + +Get full rotational velocity without drift compensation (units in Rad/s). An estimate of drift is given but not applied. + + +\begin{DoxyParams}{Parameters} +{\em x} & Reference variable to save X axis angular velocity \\ +\hline +{\em y} & Reference variable to save Y axis angular velocity \\ +\hline +{\em z} & Reference variable to save Z axis angular velocity \\ +\hline +{\em b\+\_\+x} & Reference variable to save X axis drift estimate \\ +\hline +{\em b\+\_\+y} & Reference variable to save Y axis drift estimate \\ +\hline +{\em b\+\_\+z} & Reference variable to save Z axis drift estimate \\ +\hline +{\em accuracy} & Reference variable to save reported gyro accuracy.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a3285613f18b2f2f4c3f9e6d5c971af10} +\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_accuracy@{get\_uncalibrated\_gyro\_accuracy}} +\index{get\_uncalibrated\_gyro\_accuracy@{get\_uncalibrated\_gyro\_accuracy}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_uncalibrated\_gyro\_accuracy()} +{\footnotesize\ttfamily uint8\+\_\+t BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+accuracy (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get uncalibrated gyro accuracy. + +\begin{DoxyReturn}{Returns} +Accuracy of uncalibrated gyro. +\end{DoxyReturn} +\label{class_b_n_o08x_ad228cdf352b7ea95e484da993045a47b} +\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_bias\_X@{get\_uncalibrated\_gyro\_bias\_X}} +\index{get\_uncalibrated\_gyro\_bias\_X@{get\_uncalibrated\_gyro\_bias\_X}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_uncalibrated\_gyro\_bias\_X()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+bias\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get uncalibrated gyro x axis drift estimate. + +\begin{DoxyReturn}{Returns} +The angular reported x axis drift estimate. +\end{DoxyReturn} +\label{class_b_n_o08x_a74725517129dd548c7a3de705d5861bd} +\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_bias\_Y@{get\_uncalibrated\_gyro\_bias\_Y}} +\index{get\_uncalibrated\_gyro\_bias\_Y@{get\_uncalibrated\_gyro\_bias\_Y}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_uncalibrated\_gyro\_bias\_Y()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+bias\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get uncalibrated gyro Y axis drift estimate. + +\begin{DoxyReturn}{Returns} +The angular reported Y axis drift estimate. +\end{DoxyReturn} +\label{class_b_n_o08x_a5050359272abd146ab3c7a6101effbd7} +\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_bias\_Z@{get\_uncalibrated\_gyro\_bias\_Z}} +\index{get\_uncalibrated\_gyro\_bias\_Z@{get\_uncalibrated\_gyro\_bias\_Z}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_uncalibrated\_gyro\_bias\_Z()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+bias\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get uncalibrated gyro Z axis drift estimate. + +\begin{DoxyReturn}{Returns} +The angular reported Z axis drift estimate. +\end{DoxyReturn} +\label{class_b_n_o08x_a289ff66f51c94be62c4a556f3a5997bf} +\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_X@{get\_uncalibrated\_gyro\_X}} +\index{get\_uncalibrated\_gyro\_X@{get\_uncalibrated\_gyro\_X}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_uncalibrated\_gyro\_X()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+X (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get uncalibrated gyro x axis angular velocity measurement. + +\begin{DoxyReturn}{Returns} +The angular reported x axis angular velocity from uncalibrated gyro. +\end{DoxyReturn} +\label{class_b_n_o08x_a1874e4bd457bb5b6ecc2c64039b88ba4} +\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_Y@{get\_uncalibrated\_gyro\_Y}} +\index{get\_uncalibrated\_gyro\_Y@{get\_uncalibrated\_gyro\_Y}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_uncalibrated\_gyro\_Y()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+Y (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get uncalibrated gyro Y axis angular velocity measurement. + +\begin{DoxyReturn}{Returns} +The angular reported Y axis angular velocity from uncalibrated gyro. +\end{DoxyReturn} +\label{class_b_n_o08x_a0a73633d8929ce4058b14cefc8cad717} +\index{BNO08x@{BNO08x}!get\_uncalibrated\_gyro\_Z@{get\_uncalibrated\_gyro\_Z}} +\index{get\_uncalibrated\_gyro\_Z@{get\_uncalibrated\_gyro\_Z}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_uncalibrated\_gyro\_Z()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+uncalibrated\+\_\+gyro\+\_\+Z (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get uncalibrated gyro Z axis angular velocity measurement. + +\begin{DoxyReturn}{Returns} +The angular reported Z axis angular velocity from uncalibrated gyro. +\end{DoxyReturn} +\label{class_b_n_o08x_a64d3e41750c6de9413d6982511f78f17} +\index{BNO08x@{BNO08x}!get\_yaw@{get\_yaw}} +\index{get\_yaw@{get\_yaw}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_yaw()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+yaw (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the reported rotation about z axis. + +\begin{DoxyReturn}{Returns} +Rotation about the z axis in radians. +\end{DoxyReturn} +\label{class_b_n_o08x_af80f7795656e695e036d3b1557aed94c} +\index{BNO08x@{BNO08x}!get\_yaw\_deg@{get\_yaw\_deg}} +\index{get\_yaw\_deg@{get\_yaw\_deg}!BNO08x@{BNO08x}} +\doxysubsubsection{get\_yaw\_deg()} +{\footnotesize\ttfamily float BNO08x\+::get\+\_\+yaw\+\_\+deg (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Get the reported rotation about z axis. + +\begin{DoxyReturn}{Returns} +Rotation about the z axis in degrees. +\end{DoxyReturn} +\label{class_b_n_o08x_a28cd1c0b3477571d87133234e6358503} +\index{BNO08x@{BNO08x}!hard\_reset@{hard\_reset}} +\index{hard\_reset@{hard\_reset}!BNO08x@{BNO08x}} +\doxysubsubsection{hard\_reset()} +{\footnotesize\ttfamily bool BNO08x\+::hard\+\_\+reset (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Hard resets \doxyref{BNO08x}{p.}{class_b_n_o08x} sensor. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a804b95c58c30d36933fd251626b85bf7} +\index{BNO08x@{BNO08x}!hint\_handler@{hint\_handler}} +\index{hint\_handler@{hint\_handler}!BNO08x@{BNO08x}} +\doxysubsubsection{hint\_handler()} +{\footnotesize\ttfamily void IRAM\+\_\+\+ATTR BNO08x\+::hint\+\_\+handler (\begin{DoxyParamCaption}\item[{void $\ast$}]{arg }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [private]}} + + + +HINT interrupt service routine, handles falling edge of \doxyref{BNO08x}{p.}{class_b_n_o08x} HINT pin. + +ISR that launches SPI task to perform transaction upon assertion of \doxyref{BNO08x}{p.}{class_b_n_o08x} interrupt pin. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_aea8e2c6dd7a2c9899479a7f39fe94798} +\index{BNO08x@{BNO08x}!initialize@{initialize}} +\index{initialize@{initialize}!BNO08x@{BNO08x}} +\doxysubsubsection{initialize()} +{\footnotesize\ttfamily bool BNO08x\+::initialize (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Initializes \doxyref{BNO08x}{p.}{class_b_n_o08x} sensor. + +Resets sensor and goes through initializing process outlined in \doxyref{BNO08x}{p.}{class_b_n_o08x} datasheet. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ac1b3de9b552c611ee9c455d7f19be698} +\index{BNO08x@{BNO08x}!mode\_on@{mode\_on}} +\index{mode\_on@{mode\_on}!BNO08x@{BNO08x}} +\doxysubsubsection{mode\_on()} +{\footnotesize\ttfamily bool BNO08x\+::mode\+\_\+on (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Turns on/ brings \doxyref{BNO08x}{p.}{class_b_n_o08x} sensor out of sleep mode using executable channel. + +\begin{DoxyReturn}{Returns} +True if exiting sleep mode was success. +\end{DoxyReturn} +\label{class_b_n_o08x_a176ae0112325c05105eacb4566bbfa0b} +\index{BNO08x@{BNO08x}!mode\_sleep@{mode\_sleep}} +\index{mode\_sleep@{mode\_sleep}!BNO08x@{BNO08x}} +\doxysubsubsection{mode\_sleep()} +{\footnotesize\ttfamily bool BNO08x\+::mode\+\_\+sleep (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Puts \doxyref{BNO08x}{p.}{class_b_n_o08x} sensor into sleep/low power mode using executable channel. + +\begin{DoxyReturn}{Returns} +True if entering sleep mode was success. +\end{DoxyReturn} +\label{class_b_n_o08x_a3762125be0025a335f0d918415f4ce18} +\index{BNO08x@{BNO08x}!parse\_command\_report@{parse\_command\_report}} +\index{parse\_command\_report@{parse\_command\_report}!BNO08x@{BNO08x}} +\doxysubsubsection{parse\_command\_report()} +{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::parse\+\_\+command\+\_\+report (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Parses received command report sent by \doxyref{BNO08x}{p.}{class_b_n_o08x} (See Ref. Manual 6.\+3.\+9) + +\begin{DoxyReturn}{Returns} +The command report ID, 0 if invalid. +\end{DoxyReturn} +\label{class_b_n_o08x_a7ba1d779ed68edf30090dd0f938a5709} +\index{BNO08x@{BNO08x}!parse\_input\_report@{parse\_input\_report}} +\index{parse\_input\_report@{parse\_input\_report}!BNO08x@{BNO08x}} +\doxysubsubsection{parse\_input\_report()} +{\footnotesize\ttfamily uint16\+\_\+t BNO08x\+::parse\+\_\+input\+\_\+report (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Parses received input report sent by \doxyref{BNO08x}{p.}{class_b_n_o08x}. + +Unit responds with packet that contains the following\+: + +packet\+\_\+header\+\_\+rx[0\+:3]\+: First, a 4 byte header rx\+\_\+buffer[0\+:4]\+: Then a 5 byte timestamp of microsecond ticks since reading was taken rx\+\_\+buffer[5 + 0]\+: Then a feature report ID (0x01 for Accel, 0x05 for Rotation Vector, etc...) rx\+\_\+buffer[5 + 1]\+: Sequence number (See Ref.\+Manual 6.\+5.\+8.\+2) rx\+\_\+buffer[5 + 2]\+: Status rx\+\_\+buffer[3]\+: Delay rx\+\_\+buffer[4\+:5]\+: i/accel x/gyro x/etc rx\+\_\+buffer[6\+:7]\+: j/accel y/gyro y/etc rx\+\_\+buffer[8\+:9]\+: k/accel z/gyro z/etc rx\+\_\+buffer[10\+:11]\+: real/gyro temp/etc rx\+\_\+buffer[12\+:13]\+: Accuracy estimate + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a08f037df7b3c7e2fc3f0e968f4a5f68c} +\index{BNO08x@{BNO08x}!print\_header@{print\_header}} +\index{print\_header@{print\_header}!BNO08x@{BNO08x}} +\doxysubsubsection{print\_header()} +{\footnotesize\ttfamily void BNO08x\+::print\+\_\+header (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Prints the most recently received SHTP header to serial console with ESP\+\_\+\+LOG statement. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a27fb24e894f794ec6228ef142b6ff8d9} +\index{BNO08x@{BNO08x}!q\_to\_float@{q\_to\_float}} +\index{q\_to\_float@{q\_to\_float}!BNO08x@{BNO08x}} +\doxysubsubsection{q\_to\_float()} +{\footnotesize\ttfamily float BNO08x\+::q\+\_\+to\+\_\+float (\begin{DoxyParamCaption}\item[{int16\+\_\+t}]{fixed\+\_\+point\+\_\+value, }\item[{uint8\+\_\+t}]{q\+\_\+point }\end{DoxyParamCaption})} + + + +Converts a register value to a float using its associated Q point. (See {\texttt{ https\+://en.\+wikipedia.\+org/wiki/\+Q\+\_\+(number\+\_\+format)}}) + + +\begin{DoxyParams}{Parameters} +{\em q\+\_\+point} & Q point value associated with register. \\ +\hline +{\em fixed\+\_\+point\+\_\+value} & The fixed point value to convert.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ad097849616c5caab1fd3eb3632ee2b91} +\index{BNO08x@{BNO08x}!queue\_calibrate\_command@{queue\_calibrate\_command}} +\index{queue\_calibrate\_command@{queue\_calibrate\_command}!BNO08x@{BNO08x}} +\doxysubsubsection{queue\_calibrate\_command()} +{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+calibrate\+\_\+command (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{sensor\+\_\+to\+\_\+calibrate }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} + + + +Queues a packet containing a command to calibrate the specified sensor. + + +\begin{DoxyParams}{Parameters} +{\em sensor\+\_\+to\+\_\+calibrate} & The sensor to calibrate. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a1742d6445ffb6e9297b8bf84dec24f22} +\index{BNO08x@{BNO08x}!queue\_command@{queue\_command}} +\index{queue\_command@{queue\_command}!BNO08x@{BNO08x}} +\doxysubsubsection{queue\_command()} +{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+command (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{command }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} + + + +Queues a packet containing a command. + + +\begin{DoxyParams}{Parameters} +{\em command} & The command to be sent. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a6c004a16b146527aa9eeeb6ff37db281} +\index{BNO08x@{BNO08x}!queue\_feature\_command@{queue\_feature\_command}} +\index{queue\_feature\_command@{queue\_feature\_command}!BNO08x@{BNO08x}} +\doxysubsubsection{queue\_feature\_command()\hspace{0.1cm}{\footnotesize\ttfamily [1/2]}} +{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+feature\+\_\+command (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{report\+\_\+\+ID, }\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} + + + +Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.\+5.\+4) + + +\begin{DoxyParams}{Parameters} +{\em report\+\_\+\+ID} & ID of sensor report being requested. \\ +\hline +{\em time\+\_\+between\+\_\+reports} & Desired time between reports.\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_af0a0686a78c929aad43af2eaeba12878} +\index{BNO08x@{BNO08x}!queue\_feature\_command@{queue\_feature\_command}} +\index{queue\_feature\_command@{queue\_feature\_command}!BNO08x@{BNO08x}} +\doxysubsubsection{queue\_feature\_command()\hspace{0.1cm}{\footnotesize\ttfamily [2/2]}} +{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+feature\+\_\+command (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{report\+\_\+\+ID, }\item[{uint16\+\_\+t}]{time\+\_\+between\+\_\+reports, }\item[{uint32\+\_\+t}]{specific\+\_\+config }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} + + + +Queues a packet containing a command with a request for sensor reports, reported periodically. (See Ref. Manual 6.\+5.\+4) + + +\begin{DoxyParams}{Parameters} +{\em report\+\_\+\+ID} & ID of sensor report to be enabled. \\ +\hline +{\em time\+\_\+between\+\_\+reports} & Desired time between reports in miliseconds. \\ +\hline +{\em specific\+\_\+config} & Specific config word (used with personal activity classifier)\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a67d0b5302a60083cef1b31936e2b65d8} +\index{BNO08x@{BNO08x}!queue\_packet@{queue\_packet}} +\index{queue\_packet@{queue\_packet}!BNO08x@{BNO08x}} +\doxysubsubsection{queue\_packet()} +{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+packet (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{channel\+\_\+number, }\item[{uint8\+\_\+t}]{data\+\_\+length }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} + + + +Queues an SHTP packet to be sent via SPI. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ab5f200069a2f8cb74cb79c6f162da5a1} +\index{BNO08x@{BNO08x}!queue\_request\_product\_id\_command@{queue\_request\_product\_id\_command}} +\index{queue\_request\_product\_id\_command@{queue\_request\_product\_id\_command}!BNO08x@{BNO08x}} +\doxysubsubsection{queue\_request\_product\_id\_command()} +{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+request\+\_\+product\+\_\+id\+\_\+command (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} + + + +Queues a packet containing the request product ID command. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a4c6353e795f734ed28613f9a3d161ea2} +\index{BNO08x@{BNO08x}!queue\_tare\_command@{queue\_tare\_command}} +\index{queue\_tare\_command@{queue\_tare\_command}!BNO08x@{BNO08x}} +\doxysubsubsection{queue\_tare\_command()} +{\footnotesize\ttfamily void BNO08x\+::queue\+\_\+tare\+\_\+command (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{command, }\item[{uint8\+\_\+t}]{axis = {\ttfamily \textbf{ TARE\+\_\+\+AXIS\+\_\+\+ALL}}, }\item[{uint8\+\_\+t}]{rotation\+\_\+vector\+\_\+basis = {\ttfamily \textbf{ TARE\+\_\+\+ROTATION\+\_\+\+VECTOR}} }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} + + + +Queues a packet containing a command related to zeroing sensor\textquotesingle{}s axes. (See Ref. Manual 6.\+4.\+4.\+1) + + +\begin{DoxyParams}{Parameters} +{\em command} & Tare command to be sent. ~\newline + \\ +\hline +{\em axis} & Specified axis (can be z or all at once) \\ +\hline +{\em rotation\+\_\+vector\+\_\+basis} & Which rotation vector type to zero axes of, \doxyref{BNO08x}{p.}{class_b_n_o08x} saves seperate data for Rotation Vector, Gaming Rotation Vector, etc..)\\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ae540799865934fcff54caed0772df071} +\index{BNO08x@{BNO08x}!receive\_packet@{receive\_packet}} +\index{receive\_packet@{receive\_packet}!BNO08x@{BNO08x}} +\doxysubsubsection{receive\_packet()} +{\footnotesize\ttfamily bool BNO08x\+::receive\+\_\+packet (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} + + + +Receives a SHTP packet via SPI. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_affaaa35abbb872da5299ebab6e2c9b11} +\index{BNO08x@{BNO08x}!request\_calibration\_status@{request\_calibration\_status}} +\index{request\_calibration\_status@{request\_calibration\_status}!BNO08x@{BNO08x}} +\doxysubsubsection{request\_calibration\_status()} +{\footnotesize\ttfamily void BNO08x\+::request\+\_\+calibration\+\_\+status (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Requests ME calibration status from \doxyref{BNO08x}{p.}{class_b_n_o08x} (see Ref. Manual 6.\+4.\+7.\+2) + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_ae6e875a27ae74ebed806ee1a4576845a} +\index{BNO08x@{BNO08x}!run\_full\_calibration\_routine@{run\_full\_calibration\_routine}} +\index{run\_full\_calibration\_routine@{run\_full\_calibration\_routine}!BNO08x@{BNO08x}} +\doxysubsubsection{run\_full\_calibration\_routine()} +{\footnotesize\ttfamily bool BNO08x\+::run\+\_\+full\+\_\+calibration\+\_\+routine (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Runs full calibration routine. + +Enables game rotation vector and magnetometer, starts ME calibration process. Waits for accuracy of returned quaternions and magnetic field vectors to be high, then saves calibration data and returns. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_aa16609de88bfb7b389348859aa0cee54} +\index{BNO08x@{BNO08x}!save\_calibration@{save\_calibration}} +\index{save\_calibration@{save\_calibration}!BNO08x@{BNO08x}} +\doxysubsubsection{save\_calibration()} +{\footnotesize\ttfamily void BNO08x\+::save\+\_\+calibration (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Sends command to save internal calibration data (See Ref. Manual 6.\+4.\+7). + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_afb2ffc4e7ff0498917bc14a83af306e2} +\index{BNO08x@{BNO08x}!save\_tare@{save\_tare}} +\index{save\_tare@{save\_tare}!BNO08x@{BNO08x}} +\doxysubsubsection{save\_tare()} +{\footnotesize\ttfamily void BNO08x\+::save\+\_\+tare (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Sends command to save tare into non-\/volatile memory of \doxyref{BNO08x}{p.}{class_b_n_o08x} (See Ref. Manual 6.\+4.\+4.\+2) + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a0ee58cedbc06d4a7db8821f40c0ee207} +\index{BNO08x@{BNO08x}!send\_packet@{send\_packet}} +\index{send\_packet@{send\_packet}!BNO08x@{BNO08x}} +\doxysubsubsection{send\_packet()} +{\footnotesize\ttfamily void BNO08x\+::send\+\_\+packet (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} + + + +Sends a queued SHTP packet via SPI. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a973a1b1785f3302ee1b2702c6a27646e} +\index{BNO08x@{BNO08x}!soft\_reset@{soft\_reset}} +\index{soft\_reset@{soft\_reset}!BNO08x@{BNO08x}} +\doxysubsubsection{soft\_reset()} +{\footnotesize\ttfamily bool BNO08x\+::soft\+\_\+reset (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})} + + + +Soft resets \doxyref{BNO08x}{p.}{class_b_n_o08x} sensor using executable channel. + +\begin{DoxyReturn}{Returns} +True if reset was success. +\end{DoxyReturn} +\label{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf} +\index{BNO08x@{BNO08x}!spi\_task@{spi\_task}} +\index{spi\_task@{spi\_task}!BNO08x@{BNO08x}} +\doxysubsubsection{spi\_task()} +{\footnotesize\ttfamily void BNO08x\+::spi\+\_\+task (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} + + + +Task responsible for SPI transactions. Executed when HINT in is asserted by \doxyref{BNO08x}{p.}{class_b_n_o08x}. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a0ce6d9db873555f1ebe7e095251eab74} +\index{BNO08x@{BNO08x}!spi\_task\_trampoline@{spi\_task\_trampoline}} +\index{spi\_task\_trampoline@{spi\_task\_trampoline}!BNO08x@{BNO08x}} +\doxysubsubsection{spi\_task\_trampoline()} +{\footnotesize\ttfamily void BNO08x\+::spi\+\_\+task\+\_\+trampoline (\begin{DoxyParamCaption}\item[{void $\ast$}]{arg }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [static]}, {\ttfamily [private]}} + + + +Static function used to launch spi task. + +Used such that \doxyref{spi\+\_\+task()}{p.}{class_b_n_o08x_a2ecd4ed60f82730ae230c61687ec92bf} can be non-\/static class member. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a4549bbef48208bd9c745fc755b93012f} +\index{BNO08x@{BNO08x}!tare\_now@{tare\_now}} +\index{tare\_now@{tare\_now}!BNO08x@{BNO08x}} +\doxysubsubsection{tare\_now()} +{\footnotesize\ttfamily void BNO08x\+::tare\+\_\+now (\begin{DoxyParamCaption}\item[{uint8\+\_\+t}]{axis\+\_\+sel = {\ttfamily \textbf{ TARE\+\_\+\+AXIS\+\_\+\+ALL}}, }\item[{uint8\+\_\+t}]{rotation\+\_\+vector\+\_\+basis = {\ttfamily \textbf{ TARE\+\_\+\+ROTATION\+\_\+\+VECTOR}} }\end{DoxyParamCaption})} + + + +Sends command to tare an axis (See Ref. Manual 6.\+4.\+4.\+1) + + +\begin{DoxyParams}{Parameters} +{\em axis\+\_\+sel} & Which axes to zero, can be TARE\+\_\+\+AXIS\+\_\+\+ALL (all axes) or TARE\+\_\+\+AXIS\+\_\+Z (only yaw) \\ +\hline +{\em rotation\+\_\+vector\+\_\+basis} & Which rotation vector type to zero axes can be TARE\+\_\+\+ROTATION\+\_\+\+VECTOR, TARE\+\_\+\+GAME\+\_\+\+ROTATION\+\_\+\+VECTOR, TARE\+\_\+\+GEOMAGNETIC\+\_\+\+ROTATION\+\_\+\+VECTOR, etc.. \\ +\hline +\end{DoxyParams} +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} +\label{class_b_n_o08x_a988c45b4afa4dcd6a24610ff308c1faa} +\index{BNO08x@{BNO08x}!wait\_for\_device\_int@{wait\_for\_device\_int}} +\index{wait\_for\_device\_int@{wait\_for\_device\_int}!BNO08x@{BNO08x}} +\doxysubsubsection{wait\_for\_device\_int()} +{\footnotesize\ttfamily bool BNO08x\+::wait\+\_\+for\+\_\+device\+\_\+int (\begin{DoxyParamCaption}{ }\end{DoxyParamCaption})\hspace{0.3cm}{\ttfamily [private]}} + + + +Re-\/enables interrupts and waits for \doxyref{BNO08x}{p.}{class_b_n_o08x} to assert HINT pin. + +\begin{DoxyReturn}{Returns} +void, nothing to return +\end{DoxyReturn} + + +The documentation for this class was generated from the following files\+:\begin{DoxyCompactItemize} +\item +D\+:/development/git/esp32\+\_\+\+BNO08x/BNO08x.\+hpp\item +D\+:/development/git/esp32\+\_\+\+BNO08x/BNO08x.\+cpp\end{DoxyCompactItemize} diff --git a/documentation/latex/doxygen.sty b/documentation/latex/doxygen.sty new file mode 100644 index 0000000..4bfc17f --- /dev/null +++ b/documentation/latex/doxygen.sty @@ -0,0 +1,694 @@ +\NeedsTeXFormat{LaTeX2e} +\ProvidesPackage{doxygen} + +% Packages used by this style file +\RequirePackage{alltt} +%%\RequirePackage{array} %% moved to refman.tex due to workaround for LaTex 2019 version and unmaintained tabu package +\RequirePackage{calc} +\RequirePackage{float} +%%\RequirePackage{ifthen} %% moved to refman.tex due to workaround for LaTex 2019 version and unmaintained tabu package +\RequirePackage{verbatim} +\RequirePackage[table]{xcolor} +\RequirePackage{longtable_doxygen} +\RequirePackage{tabu_doxygen} +\RequirePackage{fancyvrb} +\RequirePackage{tabularx} +\RequirePackage{multicol} +\RequirePackage{multirow} +\RequirePackage{hanging} +\RequirePackage{ifpdf} +\RequirePackage{adjustbox} +\RequirePackage{amssymb} +\RequirePackage{stackengine} +\RequirePackage{enumitem} +\RequirePackage{alphalph} +\RequirePackage[normalem]{ulem} % for strikeout, but don't modify emphasis + +%---------- Internal commands used in this style file ---------------- + +\newcommand{\ensurespace}[1]{% + \begingroup% + \setlength{\dimen@}{#1}% + \vskip\z@\@plus\dimen@% + \penalty -100\vskip\z@\@plus -\dimen@% + \vskip\dimen@% + \penalty 9999% + \vskip -\dimen@% + \vskip\z@skip% hide the previous |\vskip| from |\addvspace| + \endgroup% +} + +\newcommand{\DoxyHorRuler}[1]{% + \setlength{\parskip}{0ex plus 0ex minus 0ex}% + \ifthenelse{#1=0}% + {% + \hrule% + }% + {% + \hrulefilll% + }% +} +\newcommand{\DoxyLabelFont}{} +\newcommand{\entrylabel}[1]{% + {% + \parbox[b]{\labelwidth-4pt}{% + \makebox[0pt][l]{\DoxyLabelFont#1}% + \vspace{1.5\baselineskip}% + }% + }% +} + +\newenvironment{DoxyDesc}[1]{% + \ensurespace{4\baselineskip}% + \begin{list}{}{% + \settowidth{\labelwidth}{20pt}% + %\setlength{\parsep}{0pt}% + \setlength{\itemsep}{0pt}% + \setlength{\leftmargin}{\labelwidth+\labelsep}% + \renewcommand{\makelabel}{\entrylabel}% + }% + \item[#1]% +}{% + \end{list}% +} + +\newsavebox{\xrefbox} +\newlength{\xreflength} +\newcommand{\xreflabel}[1]{% + \sbox{\xrefbox}{#1}% + \setlength{\xreflength}{\wd\xrefbox}% + \ifthenelse{\xreflength>\labelwidth}{% + \begin{minipage}{\textwidth}% + \setlength{\parindent}{0pt}% + \hangindent=15pt\bfseries #1\vspace{1.2\itemsep}% + \end{minipage}% + }{% + \parbox[b]{\labelwidth}{\makebox[0pt][l]{\textbf{#1}}}% + }% +} + +%---------- Commands used by doxygen LaTeX output generator ---------- + +% Used by
     ... 
    +\newenvironment{DoxyPre}{% + \small% + \begin{alltt}% +}{% + \end{alltt}% + \normalsize% +} +% Necessary for redefining not defined characters, i.e. "Replacement Character" in tex output. +\newlength{\CodeWidthChar} +\newlength{\CodeHeightChar} +\settowidth{\CodeWidthChar}{?} +\settoheight{\CodeHeightChar}{?} +% Necessary for hanging indent +\newlength{\DoxyCodeWidth} + +\newcommand\DoxyCodeLine[1]{ + \ifthenelse{\equal{\detokenize{#1}}{}} + { + \vspace*{\baselineskip} + } + { + \hangpara{\DoxyCodeWidth}{1}{#1}\par + } +} + +\newcommand\NiceSpace{% + \discretionary{}{\kern\fontdimen2\font}{\kern\fontdimen2\font}% +} + +% Used by @code ... @endcode +\newenvironment{DoxyCode}[1]{% + \par% + \scriptsize% + \normalfont\ttfamily% + \rightskip0pt plus 1fil% + \settowidth{\DoxyCodeWidth}{000000}% + \settowidth{\CodeWidthChar}{?}% + \settoheight{\CodeHeightChar}{?}% + \setlength{\parskip}{0ex plus 0ex minus 0ex}% + \ifthenelse{\equal{#1}{0}} + { + {\lccode`~32 \lowercase{\global\let~}\NiceSpace}\obeyspaces% + } + { + {\lccode`~32 \lowercase{\global\let~}}\obeyspaces% + } + +}{% + \normalfont% + \normalsize% + \settowidth{\CodeWidthChar}{?}% + \settoheight{\CodeHeightChar}{?}% +} + +% Redefining not defined characters, i.e. "Replacement Character" in tex output. +\def\ucr{\adjustbox{width=\CodeWidthChar,height=\CodeHeightChar}{\stackinset{c}{}{c}{-.2pt}{% + \textcolor{white}{\sffamily\bfseries\small ?}}{% + \rotatebox{45}{$\blacksquare$}}}} + +% Used by @example, @include, @includelineno and @dontinclude +\newenvironment{DoxyCodeInclude}[1]{% + \DoxyCode{#1}% +}{% + \endDoxyCode% +} + +% Used by @verbatim ... @endverbatim +\newenvironment{DoxyVerb}{% + \par% + \footnotesize% + \verbatim% +}{% + \endverbatim% + \normalsize% +} + +% Used by @verbinclude +\newenvironment{DoxyVerbInclude}{% + \DoxyVerb% +}{% + \endDoxyVerb% +} + +% Used by numbered lists (using '-#' or
      ...
    ) +\setlistdepth{12} +\newlist{DoxyEnumerate}{enumerate}{12} +\setlist[DoxyEnumerate,1]{label=\arabic*.} +\setlist[DoxyEnumerate,2]{label=(\enumalphalphcnt*)} +\setlist[DoxyEnumerate,3]{label=\roman*.} +\setlist[DoxyEnumerate,4]{label=\enumAlphAlphcnt*.} +\setlist[DoxyEnumerate,5]{label=\arabic*.} +\setlist[DoxyEnumerate,6]{label=(\enumalphalphcnt*)} +\setlist[DoxyEnumerate,7]{label=\roman*.} +\setlist[DoxyEnumerate,8]{label=\enumAlphAlphcnt*.} +\setlist[DoxyEnumerate,9]{label=\arabic*.} +\setlist[DoxyEnumerate,10]{label=(\enumalphalphcnt*)} +\setlist[DoxyEnumerate,11]{label=\roman*.} +\setlist[DoxyEnumerate,12]{label=\enumAlphAlphcnt*.} + +% Used by bullet lists (using '-', @li, @arg, or
      ...
    ) +\setlistdepth{12} +\newlist{DoxyItemize}{itemize}{12} +\setlist[DoxyItemize]{label=\textperiodcentered} + +\setlist[DoxyItemize,1]{label=\textbullet} +\setlist[DoxyItemize,2]{label=\normalfont\bfseries \textendash} +\setlist[DoxyItemize,3]{label=\textasteriskcentered} +\setlist[DoxyItemize,4]{label=\textperiodcentered} + +% Used by description lists (using
    ...
    ) +\newenvironment{DoxyDescription}{% + \description% +}{% + \enddescription% +} + +% Used by @image, @dotfile, @dot ... @enddot, and @msc ... @endmsc +% (only if caption is specified) +\newenvironment{DoxyImage}{% + \begin{figure}[H]% + \centering% +}{% + \end{figure}% +} + +% Used by @image, @dotfile, @dot ... @enddot, and @msc ... @endmsc +% (only if no caption is specified) +\newenvironment{DoxyImageNoCaption}{% + \begin{center}% +}{% + \end{center}% +} + +% Used by @image +% (only if inline is specified) +\newenvironment{DoxyInlineImage}{% +}{% +} + +% Used by @attention +\newenvironment{DoxyAttention}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @author and @authors +\newenvironment{DoxyAuthor}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @date +\newenvironment{DoxyDate}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @invariant +\newenvironment{DoxyInvariant}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @note +\newenvironment{DoxyNote}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @post +\newenvironment{DoxyPostcond}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @pre +\newenvironment{DoxyPrecond}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @copyright +\newenvironment{DoxyCopyright}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @remark +\newenvironment{DoxyRemark}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @return and @returns +\newenvironment{DoxyReturn}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @since +\newenvironment{DoxySince}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @see +\newenvironment{DoxySeeAlso}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @version +\newenvironment{DoxyVersion}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @warning +\newenvironment{DoxyWarning}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by @par and @paragraph +\newenvironment{DoxyParagraph}[1]{% + \begin{DoxyDesc}{#1}% +}{% + \end{DoxyDesc}% +} + +% Used by parameter lists +\newenvironment{DoxyParams}[2][]{% + \tabulinesep=1mm% + \par% + \ifthenelse{\equal{#1}{}}% + {\begin{longtabu*}spread 0pt [l]{|X[-1,l]|X[-1,l]|}}% name + description + {\ifthenelse{\equal{#1}{1}}% + {\begin{longtabu*}spread 0pt [l]{|X[-1,l]|X[-1,l]|X[-1,l]|}}% in/out + name + desc + {\begin{longtabu*}spread 0pt [l]{|X[-1,l]|X[-1,l]|X[-1,l]|X[-1,l]|}}% in/out + type + name + desc + } + \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #2}\\[1ex]% + \hline% + \endfirsthead% + \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #2}\\[1ex]% + \hline% + \endhead% +}{% + \end{longtabu*}% + \vspace{6pt}% +} + +% Used for fields of simple structs +\newenvironment{DoxyFields}[1]{% + \tabulinesep=1mm% + \par% + \begin{longtabu*}spread 0pt [l]{|X[-1,r]|X[-1,l]|X[-1,l]|}% + \multicolumn{3}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% + \hline% + \endfirsthead% + \multicolumn{3}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% + \hline% + \endhead% +}{% + \end{longtabu*}% + \vspace{6pt}% +} + +% Used for fields simple class style enums +\newenvironment{DoxyEnumFields}[1]{% + \tabulinesep=1mm% + \par% + \begin{longtabu*}spread 0pt [l]{|X[-1,r]|X[-1,l]|}% + \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% + \hline% + \endfirsthead% + \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% + \hline% + \endhead% +}{% + \end{longtabu*}% + \vspace{6pt}% +} + +% Used for parameters within a detailed function description +\newenvironment{DoxyParamCaption}{% + \renewcommand{\item}[2][]{\\ \hspace*{2.0cm} ##1 {\em ##2}}% +}{% +} + +% Used by return value lists +\newenvironment{DoxyRetVals}[1]{% + \tabulinesep=1mm% + \par% + \begin{longtabu*}spread 0pt [l]{|X[-1,r]|X[-1,l]|}% + \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% + \hline% + \endfirsthead% + \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% + \hline% + \endhead% +}{% + \end{longtabu*}% + \vspace{6pt}% +} + +% Used by exception lists +\newenvironment{DoxyExceptions}[1]{% + \tabulinesep=1mm% + \par% + \begin{longtabu*}spread 0pt [l]{|X[-1,r]|X[-1,l]|}% + \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% + \hline% + \endfirsthead% + \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% + \hline% + \endhead% +}{% + \end{longtabu*}% + \vspace{6pt}% +} + +% Used by template parameter lists +\newenvironment{DoxyTemplParams}[1]{% + \tabulinesep=1mm% + \par% + \begin{longtabu*}spread 0pt [l]{|X[-1,r]|X[-1,l]|}% + \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% + \hline% + \endfirsthead% + \multicolumn{2}{l}{\hspace{-6pt}\bfseries\fontseries{bc}\selectfont\color{darkgray} #1}\\[1ex]% + \hline% + \endhead% +}{% + \end{longtabu*}% + \vspace{6pt}% +} + +% Used for member lists +\newenvironment{DoxyCompactItemize}{% + \begin{itemize}% + \setlength{\itemsep}{-3pt}% + \setlength{\parsep}{0pt}% + \setlength{\topsep}{0pt}% + \setlength{\partopsep}{0pt}% +}{% + \end{itemize}% +} + +% Used for member descriptions +\newenvironment{DoxyCompactList}{% + \begin{list}{}{% + \setlength{\leftmargin}{0.5cm}% + \setlength{\itemsep}{0pt}% + \setlength{\parsep}{0pt}% + \setlength{\topsep}{0pt}% + \renewcommand{\makelabel}{\hfill}% + }% +}{% + \end{list}% +} + +% Used for reference lists (@bug, @deprecated, @todo, etc.) +\newenvironment{DoxyRefList}{% + \begin{list}{}{% + \setlength{\labelwidth}{10pt}% + \setlength{\leftmargin}{\labelwidth}% + \addtolength{\leftmargin}{\labelsep}% + \renewcommand{\makelabel}{\xreflabel}% + }% +}{% + \end{list}% +} + +% Used by @bug, @deprecated, @todo, etc. +\newenvironment{DoxyRefDesc}[1]{% + \begin{list}{}{% + \renewcommand\makelabel[1]{\textbf{##1}}% + \settowidth\labelwidth{\makelabel{#1}}% + \setlength\leftmargin{\labelwidth+\labelsep}% + }% +}{% + \end{list}% +} + +% Used by parameter lists and simple sections +\newenvironment{Desc} +{\begin{list}{}{% + \settowidth{\labelwidth}{20pt}% + \setlength{\parsep}{0pt}% + \setlength{\itemsep}{0pt}% + \setlength{\leftmargin}{\labelwidth+\labelsep}% + \renewcommand{\makelabel}{\entrylabel}% + } +}{% + \end{list}% +} + +% Used by tables +\newcommand{\PBS}[1]{\let\temp=\\#1\let\\=\temp}% +\newenvironment{TabularC}[1]% +{\tabulinesep=1mm +\begin{longtabu*}spread 0pt [c]{*#1{|X[-1]}|}}% +{\end{longtabu*}\par}% + +\newenvironment{TabularNC}[1]% +{\begin{tabu}spread 0pt [l]{*#1{|X[-1]}|}}% +{\end{tabu}\par}% + +% Used for member group headers +\newenvironment{Indent}{% + \begin{list}{}{% + \setlength{\leftmargin}{0.5cm}% + }% + \item[]\ignorespaces% +}{% + \unskip% + \end{list}% +} + +% Used when hyperlinks are turned on +\newcommand{\doxylink}[2]{% + \mbox{\hyperlink{#1}{#2}}% +} + +% Used when hyperlinks are turned on +% Third argument is the SectionType, see the doxygen internal +% documentation for the values (relevant: Page ... Subsubsection). +\newcommand{\doxysectlink}[3]{% + \mbox{\hyperlink{#1}{#2}}% +} +% Used when hyperlinks are turned off +\newcommand{\doxyref}[3]{% + \textbf{#1} (\textnormal{#2}\,\pageref{#3})% +} + +% Used when hyperlinks are turned off +% Fourth argument is the SectionType, see the doxygen internal +% documentation for the values (relevant: Page ... Subsubsection). +\newcommand{\doxysectref}[4]{% + \textbf{#1} (\textnormal{#2}\,\pageref{#3})% +} + +% Used to link to a table when hyperlinks are turned on +\newcommand{\doxytablelink}[2]{% + \ref{#1}% +} + +% Used to link to a table when hyperlinks are turned off +\newcommand{\doxytableref}[3]{% + \ref{#3}% +} + +% Used by @addindex +\newcommand{\lcurly}{\{} +\newcommand{\rcurly}{\}} + +% Colors used for syntax highlighting +\definecolor{comment}{rgb}{0.5,0.0,0.0} +\definecolor{keyword}{rgb}{0.0,0.5,0.0} +\definecolor{keywordtype}{rgb}{0.38,0.25,0.125} +\definecolor{keywordflow}{rgb}{0.88,0.5,0.0} +\definecolor{preprocessor}{rgb}{0.5,0.38,0.125} +\definecolor{stringliteral}{rgb}{0.0,0.125,0.25} +\definecolor{charliteral}{rgb}{0.0,0.5,0.5} +\definecolor{xmlcdata}{rgb}{0.0,0.0,0.0} +\definecolor{vhdldigit}{rgb}{1.0,0.0,1.0} +\definecolor{vhdlkeyword}{rgb}{0.43,0.0,0.43} +\definecolor{vhdllogic}{rgb}{1.0,0.0,0.0} +\definecolor{vhdlchar}{rgb}{0.0,0.0,0.0} + +% Color used for table heading +\newcommand{\tableheadbgcolor}{lightgray}% + +% Version of hypertarget with correct landing location +\newcommand{\Hypertarget}[1]{\Hy@raisedlink{\hypertarget{#1}{}}} + +% possibility to have sections etc. be within the margins +% unfortunately had to copy part of book.cls and add \raggedright +\makeatletter +\newcounter{subsubsubsection}[subsubsection] +\newcounter{subsubsubsubsection}[subsubsubsection] +\newcounter{subsubsubsubsubsection}[subsubsubsubsection] +\newcounter{subsubsubsubsubsubsection}[subsubsubsubsubsection] +\renewcommand{\thesubsubsubsection}{\thesubsubsection.\arabic{subsubsubsection}} +\renewcommand{\thesubsubsubsubsection}{\thesubsubsubsection.\arabic{subsubsubsubsection}} +\renewcommand{\thesubsubsubsubsubsection}{\thesubsubsubsubsection.\arabic{subsubsubsubsubsection}} +\renewcommand{\thesubsubsubsubsubsubsection}{\thesubsubsubsubsubsection.\arabic{subsubsubsubsubsubsection}} +\newcommand{\subsubsubsectionmark}[1]{} +\newcommand{\subsubsubsubsectionmark}[1]{} +\newcommand{\subsubsubsubsubsectionmark}[1]{} +\newcommand{\subsubsubsubsubsubsectionmark}[1]{} +\def\toclevel@subsubsubsection{4} +\def\toclevel@subsubsubsubsection{5} +\def\toclevel@subsubsubsubsubsection{6} +\def\toclevel@subsubsubsubsubsubsection{7} +\def\toclevel@paragraph{8} +\def\toclevel@subparagraph{9} + +\newcommand\doxysection{\@startsection {section}{1}{\z@}% + {-3.5ex \@plus -1ex \@minus -.2ex}% + {2.3ex \@plus.2ex}% + {\raggedright\normalfont\Large\bfseries}} +\newcommand\doxysubsection{\@startsection{subsection}{2}{\z@}% + {-3.25ex\@plus -1ex \@minus -.2ex}% + {1.5ex \@plus .2ex}% + {\raggedright\normalfont\large\bfseries}} +\newcommand\doxysubsubsection{\@startsection{subsubsection}{3}{\z@}% + {-3.25ex\@plus -1ex \@minus -.2ex}% + {1.5ex \@plus .2ex}% + {\raggedright\normalfont\normalsize\bfseries}} +\newcommand\doxysubsubsubsection{\@startsection{subsubsubsection}{4}{\z@}% + {-3.25ex\@plus -1ex \@minus -.2ex}% + {1.5ex \@plus .2ex}% + {\raggedright\normalfont\normalsize\bfseries}} +\newcommand\doxysubsubsubsubsection{\@startsection{subsubsubsubsection}{5}{\z@}% + {-3.25ex\@plus -1ex \@minus -.2ex}% + {1.5ex \@plus .2ex}% + {\raggedright\normalfont\normalsize\bfseries}} +\newcommand\doxysubsubsubsubsubsection{\@startsection{subsubsubsubsubsection}{6}{\z@}% + {-3.25ex\@plus -1ex \@minus -.2ex}% + {1.5ex \@plus .2ex}% + {\raggedright\normalfont\normalsize\bfseries}} +\newcommand\doxysubsubsubsubsubsubsection{\@startsection{subsubsubsubsubsubsection}{7}{\z@}% + {-3.25ex\@plus -1ex \@minus -.2ex}% + {1.5ex \@plus .2ex}% + {\raggedright\normalfont\normalsize\bfseries}} +\newcommand\doxyparagraph{\@startsection{paragraph}{8}{\z@}% + {-3.25ex\@plus -1ex \@minus -.2ex}% + {1.5ex \@plus .2ex}% + {\raggedright\normalfont\normalsize\bfseries}} +\newcommand\doxysubparagraph{\@startsection{subparagraph}{9}{\parindent}% + {-3.25ex\@plus -1ex \@minus -.2ex}% + {1.5ex \@plus .2ex}% + {\raggedright\normalfont\normalsize\bfseries}} + +\newcommand\l@subsubsubsection{\@dottedtocline{4}{6.1em}{7.8em}} +\newcommand\l@subsubsubsubsection{\@dottedtocline{5}{6.1em}{9.4em}} +\newcommand\l@subsubsubsubsubsection{\@dottedtocline{6}{6.1em}{11em}} +\newcommand\l@subsubsubsubsubsubsection{\@dottedtocline{7}{6.1em}{12.6em}} +\renewcommand\l@paragraph{\@dottedtocline{8}{6.1em}{14.2em}} +\renewcommand\l@subparagraph{\@dottedtocline{9}{6.1em}{15.8em}} +\makeatother +% the sectsty doesn't look to be maintained but gives, in our case, some warning like: +% LaTeX Warning: Command \underline has changed. +% Check if current package is valid. +% unfortunately had to copy the relevant part +\newcommand*{\doxypartfont} [1] + {\gdef\SS@partnumberfont{\SS@sectid{0}\SS@nopart\SS@makeulinepartchap#1} + \gdef\SS@parttitlefont{\SS@sectid{0}\SS@titlepart\SS@makeulinepartchap#1}} +\newcommand*{\doxychapterfont} [1] + {\gdef\SS@chapnumfont{\SS@sectid{1}\SS@nopart\SS@makeulinepartchap#1} + \gdef\SS@chaptitlefont{\SS@sectid{1}\SS@titlepart\SS@makeulinepartchap#1}} +\newcommand*{\doxysectionfont} [1] + {\gdef\SS@sectfont{\SS@sectid{2}\SS@rr\SS@makeulinesect#1}} +\newcommand*{\doxysubsectionfont} [1] + {\gdef\SS@subsectfont{\SS@sectid{3}\SS@rr\SS@makeulinesect#1}} +\newcommand*{\doxysubsubsectionfont} [1] + {\gdef\SS@subsubsectfont{\SS@sectid{4}\SS@rr\SS@makeulinesect#1}} +\newcommand*{\doxyparagraphfont} [1] + {\gdef\SS@parafont{\SS@sectid{5}\SS@rr\SS@makeulinesect#1}} +\newcommand*{\doxysubparagraphfont} [1] + {\gdef\SS@subparafont{\SS@sectid{6}\SS@rr\SS@makeulinesect#1}} +\newcommand*{\doxyminisecfont} [1] + {\gdef\SS@minisecfont{\SS@sectid{7}\SS@rr\SS@makeulinepartchap#1}} +\newcommand*{\doxyallsectionsfont} [1] {\doxypartfont{#1}% + \doxychapterfont{#1}% + \doxysectionfont{#1}% + \doxysubsectionfont{#1}% + \doxysubsubsectionfont{#1}% + \doxyparagraphfont{#1}% + \doxysubparagraphfont{#1}% + \doxyminisecfont{#1}}% +% Define caption that is also suitable in a table +\makeatletter +\def\doxyfigcaption{% +\H@refstepcounter{figure}% +\@dblarg{\@caption{figure}}} +\makeatother + +% Define alpha enumarative names for counters > 26 +\makeatletter +\def\enumalphalphcnt#1{\expandafter\@enumalphalphcnt\csname c@#1\endcsname} +\def\@enumalphalphcnt#1{\alphalph{#1}} +\def\enumAlphAlphcnt#1{\expandafter\@enumAlphAlphcnt\csname c@#1\endcsname} +\def\@enumAlphAlphcnt#1{\AlphAlph{#1}} +\makeatother +\AddEnumerateCounter{\enumalphalphcnt}{\@enumalphalphcnt}{aa} +\AddEnumerateCounter{\enumAlphAlphcnt}{\@enumAlphAlphcnt}{AA} diff --git a/documentation/latex/etoc_doxygen.sty b/documentation/latex/etoc_doxygen.sty new file mode 100644 index 0000000..8663b1b --- /dev/null +++ b/documentation/latex/etoc_doxygen.sty @@ -0,0 +1,2182 @@ +%% +%% This is file etoc_doxygen.sty +%% +%% Apart from this header notice and the renaming from etoc to +%% etoc_doxygen (also in \ProvidesPackage) it is an identical +%% copy of +%% +%% etoc.sty +%% +%% at version 1.2a of 2023/05/01. +%% +%% This file has been provided to Doxygen team courtesy of the +%% author for benefit of users having a LaTeX installation not +%% yet providing version 1.2a or later of etoc, whose +%% deeplevels feature is required. +%% +%% The original source etoc.dtx (only of the latest version at +%% any given time) is available at +%% +%% https://ctan.org/pkg/etoc +%% +%% and contains the terms for copying and modification as well +%% as author contact information. +%% +%% In brief any modified versions of this file must be renamed +%% with new filenames distinct from etoc.sty. +%% +%% Package: etoc +%% Version: 1.2a +%% License: LPPL 1.3c +%% Copyright (C) 2012-2023 Jean-Francois B. +\NeedsTeXFormat{LaTeX2e}[2003/12/01] +\ProvidesPackage{etoc_doxygen}[2023/05/01 v1.2a Completely customisable TOCs (JFB)] +\newif\ifEtoc@oldLaTeX +\@ifl@t@r\fmtversion{2020/10/01} + {} + {\Etoc@oldLaTeXtrue + \PackageInfo{etoc}{Old LaTeX (\fmtversion) detected!\MessageBreak + Since 1.1a (2023/01/14), etoc prefers LaTeX at least\MessageBreak + as recent as 2020-10-01, for reasons of the .toc file,\MessageBreak + and used to require it (from 1.1a to 1.2).\MessageBreak + This etoc (1.2a) does not *require* it, but has not been\MessageBreak + tested thoroughly on old LaTeX (especially if document\MessageBreak + does not use hyperref) and retrofitting was done only\MessageBreak + on basis of author partial remembrances of old context.\MessageBreak + Reported}} +\RequirePackage{kvoptions} +\SetupKeyvalOptions{prefix=Etoc@} +\newif\ifEtoc@lof +\DeclareVoidOption{lof}{\Etoc@loftrue + \PackageInfo{etoc}{Experimental support for \string\locallistoffigures.\MessageBreak + Barely tested, use at own risk}% +} +\newif\ifEtoc@lot +\DeclareVoidOption{lot}{\Etoc@lottrue + \PackageInfo{etoc}{Experimental support for \string\locallistoftables.\MessageBreak + Barely tested, use at own risk}% +} +\@ifclassloaded{memoir}{ +\PackageInfo{etoc} + {As this is with memoir class, all `...totoc' options\MessageBreak + are set true by default. Reported} +\DeclareBoolOption[true]{maintoctotoc} +\DeclareBoolOption[true]{localtoctotoc} +\DeclareBoolOption[true]{localloftotoc} +\DeclareBoolOption[true]{locallottotoc} +}{ +\DeclareBoolOption[false]{maintoctotoc} +\DeclareBoolOption[false]{localtoctotoc} +\DeclareBoolOption[false]{localloftotoc} +\DeclareBoolOption[false]{locallottotoc} +} +\DeclareBoolOption[true]{ouroboros} +\DeclareBoolOption[false]{deeplevels} +\DeclareDefaultOption{\PackageWarning{etoc}{Option `\CurrentOption' is unknown.}} +\ProcessKeyvalOptions* +\DisableKeyvalOption[action=error,package=etoc]{etoc}{lof} +\DisableKeyvalOption[action=error,package=etoc]{etoc}{lot} +\DisableKeyvalOption[action=error,package=etoc]{etoc}{deeplevels} +\def\etocsetup#1{\setkeys{etoc}{#1}} +\def\etocifmaintoctotoc{\ifEtoc@maintoctotoc + \expandafter\@firstoftwo + \else + \expandafter\@secondoftwo + \fi} +\def\etociflocaltoctotoc{\ifEtoc@localtoctotoc + \expandafter\@firstoftwo + \else + \expandafter\@secondoftwo + \fi} +\def\etociflocalloftotoc{\ifEtoc@localloftotoc + \expandafter\@firstoftwo + \else + \expandafter\@secondoftwo + \fi} +\def\etociflocallottotoc{\ifEtoc@locallottotoc + \expandafter\@firstoftwo + \else + \expandafter\@secondoftwo + \fi} +\RequirePackage{multicol} +\def\etoc@{\etoc@} +\long\def\Etoc@gobtoetoc@ #1\etoc@{} +\newtoks\Etoc@toctoks +\def\Etoc@par{\par} +\def\etocinline{\def\Etoc@par{}} +\let\etocnopar\etocinline +\def\etocdisplay{\def\Etoc@par{\par}} +\let\Etoc@global\@empty +\def\etocglobaldefs{\let\Etoc@global\global\let\tof@global\global} +\def\etoclocaldefs {\let\Etoc@global\@empty\let\tof@global\@empty} +\newif\ifEtoc@numbered +\newif\ifEtoc@hyperref +\newif\ifEtoc@parskip +\newif\ifEtoc@tocwithid +\newif\ifEtoc@standardlines +\newif\ifEtoc@etocstyle +\newif\ifEtoc@classstyle +\newif\ifEtoc@keeporiginaltoc +\newif\ifEtoc@skipprefix +\newif\ifEtoc@isfirst +\newif\ifEtoc@localtoc +\newif\ifEtoc@skipthisone +\newif\ifEtoc@stoptoc +\newif\ifEtoc@notactive +\newif\ifEtoc@mustclosegroup +\newif\ifEtoc@isemptytoc +\newif\ifEtoc@checksemptiness +\def\etocchecksemptiness {\Etoc@checksemptinesstrue } +\def\etocdoesnotcheckemptiness {\Etoc@checksemptinessfalse } +\newif\ifEtoc@notocifnotoc +\def\etocnotocifnotoc {\Etoc@checksemptinesstrue\Etoc@notocifnotoctrue } +\newcounter{etoc@tocid} +\def\Etoc@tocext{toc} +\def\Etoc@lofext{lof} +\def\Etoc@lotext{lot} +\let\Etoc@currext\Etoc@tocext +\def\etocifislocal{\ifEtoc@localtoc\expandafter\@firstoftwo\else + \expandafter\@secondoftwo\fi + } +\def\etocifislocaltoc{\etocifislocal{\ifx\Etoc@currext\Etoc@tocext + \expandafter\@firstoftwo\else + \expandafter\@secondoftwo\fi}% + {\@secondoftwo}% + } +\def\etocifislocallof{\etocifislocal{\ifx\Etoc@currext\Etoc@lofext + \expandafter\@firstoftwo\else + \expandafter\@secondoftwo\fi}% + {\@secondoftwo}% + } +\def\etocifislocallot{\etocifislocal{\ifx\Etoc@currext\Etoc@lotext + \expandafter\@firstoftwo\else + \expandafter\@secondoftwo\fi}% + {\@secondoftwo}% + } +\expandafter\def\csname Etoc@-3@@\endcsname {-\thr@@} +\expandafter\def\csname Etoc@-2@@\endcsname {-\tw@} +\expandafter\let\csname Etoc@-1@@\endcsname \m@ne +\expandafter\let\csname Etoc@0@@\endcsname \z@ +\expandafter\let\csname Etoc@1@@\endcsname \@ne +\expandafter\let\csname Etoc@2@@\endcsname \tw@ +\expandafter\let\csname Etoc@3@@\endcsname \thr@@ +\expandafter\chardef\csname Etoc@4@@\endcsname 4 +\expandafter\chardef\csname Etoc@5@@\endcsname 5 +\expandafter\chardef\csname Etoc@6@@\endcsname 6 +\ifEtoc@deeplevels + \expandafter\chardef\csname Etoc@7@@\endcsname 7 + \expandafter\chardef\csname Etoc@8@@\endcsname 8 + \expandafter\chardef\csname Etoc@9@@\endcsname 9 + \expandafter\chardef\csname Etoc@10@@\endcsname 10 + \expandafter\chardef\csname Etoc@11@@\endcsname 11 + \expandafter\chardef\csname Etoc@12@@\endcsname 12 +\fi +\expandafter\let\expandafter\Etoc@maxlevel + \csname Etoc@\ifEtoc@deeplevels12\else6\fi @@\endcsname +\edef\etocthemaxlevel{\number\Etoc@maxlevel} +\@ifclassloaded{memoir}{\def\Etoc@minf{-\thr@@}}{\def\Etoc@minf{-\tw@}} +\let\Etoc@none@@ \Etoc@minf +\expandafter\let\expandafter\Etoc@all@@ + \csname Etoc@\ifEtoc@deeplevels11\else5\fi @@\endcsname +\let\Etoc@dolevels\@empty +\def\Etoc@newlevel #1{\expandafter\def\expandafter\Etoc@dolevels\expandafter + {\Etoc@dolevels\Etoc@do{#1}}} +\ifdefined\expanded + \def\etocsetlevel#1#2{\expanded{\noexpand\etoc@setlevel{#1}{#2}}}% +\else + \def\etocsetlevel#1#2{{\edef\Etoc@tmp{\noexpand\etoc@setlevel{#1}{#2}}\expandafter}\Etoc@tmp}% +\fi +\def\etoc@setlevel#1#2{% + \edef\Etoc@tmp{\the\numexpr#2}% + \if1\ifnum\Etoc@tmp>\Etoc@maxlevel0\fi\unless\ifnum\Etoc@minf<\Etoc@tmp;\fi1% + \ifEtoc@deeplevels + \in@{.#1,}{.none,.all,.figure,.table,.-3,.-2,.-1,.0,.1,.2,.3,.4,.5,.6,% + .7,.8,.9,.10,.11,.12,}% + \else + \in@{.#1,}{.none,.all,.figure,.table,.-3,.-2,.-1,.0,.1,.2,.3,.4,.5,.6,}% + \fi + \ifin@\else\if\@car#1\@nil @\in@true\fi\fi + \ifin@ + \PackageWarning{etoc} + {Sorry, but `#1' is forbidden as level name.\MessageBreak + \if\@car#1\@nil @% + (because of the @ as first character)\MessageBreak\fi + Reported}% + \else + \etocifunknownlevelTF{#1}{\Etoc@newlevel{#1}}{}% + \expandafter\let\csname Etoc@#1@@\expandafter\endcsname + \csname Etoc@\Etoc@tmp @@\endcsname + \expandafter\edef\csname Etoc@@#1@@\endcsname + {\expandafter\noexpand\csname Etoc@#1@@\endcsname}% + \expandafter\edef\csname toclevel@@#1\endcsname + {\expandafter\noexpand\csname toclevel@#1\endcsname}% + \fi + \else + \PackageWarning{etoc} + {Argument `\detokenize{#2}' of \string\etocsetlevel\space should + represent one of\MessageBreak + \ifnum\Etoc@minf=-\thr@@-2, \fi-1, 0, 1, 2, \ifEtoc@deeplevels ...\else3, 4\fi, + \the\numexpr\Etoc@maxlevel-1, or \number\Etoc@maxlevel\space + but evaluates to \Etoc@tmp.\MessageBreak + The level of `#1' will be set to \number\Etoc@maxlevel.\MessageBreak + Tables of contents will ignore `#1' as long\MessageBreak + as its level is \number\Etoc@maxlevel\space (=\string\etocthemaxlevel).% + \MessageBreak + Reported}% + \etocifunknownlevelTF{#1}{\Etoc@newlevel{#1}}{}% + \expandafter\let\csname Etoc@#1@@\endcsname\Etoc@maxlevel + \fi +} +\def\etoclevel#1{\csname Etoc@#1@@\endcsname} +\def\etocthelevel#1{\number\csname Etoc@#1@@\endcsname} +\def\etocifunknownlevelTF#1{\@ifundefined{Etoc@#1@@}} +\@ifclassloaded{memoir}{\etocsetlevel{book}{-2}}{} +\etocsetlevel{part}{-1} +\etocsetlevel{chapter}{0} +\etocsetlevel{section}{1} +\etocsetlevel{subsection}{2} +\etocsetlevel{subsubsection}{3} +\etocsetlevel{paragraph}{4} +\etocsetlevel{subparagraph}{5} +\ifdefined\c@chapter + \etocsetlevel{appendix}{0} +\else + \etocsetlevel{appendix}{1} +\fi +\def\Etoc@do#1{\@namedef{l@@#1}{\csname l@#1\endcsname}} +\Etoc@dolevels +\let\Etoc@figure@@\Etoc@maxlevel +\let\Etoc@table@@ \Etoc@maxlevel +\let\Etoc@gobblethreeorfour\@gobblefour +\ifdefined\@gobblethree + \let\Etoc@gobblethree\@gobblethree +\else + \long\def\Etoc@gobblethree#1#2#3{}% +\fi +\AtBeginDocument{% +\@ifpackageloaded{parskip}{\Etoc@parskiptrue}{}% +\@ifpackageloaded{hyperref} + {\Etoc@hyperreftrue} + {\ifEtoc@oldLaTeX + \let\Etoc@gobblethreeorfour\Etoc@gobblethree + \let\Etoc@etoccontentsline@fourargs\Etoc@etoccontentsline@ + \long\def\Etoc@etoccontentsline@#1#2#3{% + \Etoc@etoccontentsline@fourargs{#1}{#2}{#3}{}% + }% + \fi + }% +} +\def\etocskipfirstprefix {\global\Etoc@skipprefixtrue } +\def\Etoc@updatestackofends#1\etoc@{\gdef\Etoc@stackofends{#1}} +\def\Etoc@stackofends{{-3}{}} +\def\Etoc@doendsandbegin{% + \expandafter\Etoc@traversestackofends\Etoc@stackofends\etoc@ +} +\def\Etoc@traversestackofends#1{% + \ifnum#1>\Etoc@level + \csname Etoc@end@#1\endcsname + \expandafter\Etoc@traversestackofends + \else + \Etoc@traversestackofends@done{#1}% + \fi +} +\def\Etoc@traversestackofends@done#1#2{#2% + \ifnum#1<\Etoc@level + \csname Etoc@begin@\the\numexpr\Etoc@level\endcsname + \Etoc@global\Etoc@isfirsttrue + \edef\Etoc@tmp{{\the\numexpr\Etoc@level}}% + \else + \Etoc@global\Etoc@isfirstfalse + \let\Etoc@tmp\@empty + \fi + \expandafter\Etoc@updatestackofends\Etoc@tmp{#1}% +} +\def\Etoc@etoccontentsline #1{% + \let\Etoc@next\Etoc@gobblethreeorfour + \ifnum\csname Etoc@#1@@\endcsname=\Etoc@maxlevel + \else + \Etoc@skipthisonefalse + \global\expandafter\let\expandafter\Etoc@level\csname Etoc@#1@@\endcsname + \if @\@car#1\@nil\else\global\let\Etoc@virtualtop\Etoc@level\fi + \ifEtoc@localtoc + \ifEtoc@stoptoc + \Etoc@skipthisonetrue + \else + \ifEtoc@notactive + \Etoc@skipthisonetrue + \else + \unless\ifnum\Etoc@level>\etoclocaltop + \Etoc@skipthisonetrue + \global\Etoc@stoptoctrue + \fi + \fi + \fi + \fi + \ifEtoc@skipthisone + \else + \unless\ifnum\Etoc@level>\c@tocdepth + \ifEtoc@standardlines + \let\Etoc@next\Etoc@savedcontentsline + \else + \let\Etoc@next\Etoc@etoccontentsline@ + \fi + \fi + \fi + \fi + \Etoc@next{#1}% +} +\def\Etoc@etoccontentsline@ #1#2#3#4{% + \Etoc@doendsandbegin + \Etoc@global\edef\Etoc@prefix {\expandafter\noexpand + \csname Etoc@prefix@\the\numexpr\Etoc@level\endcsname }% + \Etoc@global\edef\Etoc@contents{\expandafter\noexpand + \csname Etoc@contents@\the\numexpr\Etoc@level\endcsname }% + \ifEtoc@skipprefix \Etoc@global\def\Etoc@prefix{\@empty}\fi + \global\Etoc@skipprefixfalse + \Etoc@lxyz{#2}{#3}{#4}% + \Etoc@prefix + \Etoc@contents +} +\def\Etoc@lxyz #1#2#3{% + \ifEtoc@hyperref + \Etoc@global\def\etocthelink##1{\hyperlink{#3}{##1}}% + \else + \Etoc@global\let\etocthelink\@firstofone + \fi + \Etoc@global\def\etocthepage {#2}% + \ifEtoc@hyperref + \ifx\etocthepage\@empty + \Etoc@global\let\etocthelinkedpage\@empty + \else + \Etoc@global\def\etocthelinkedpage{\hyperlink {#3}{#2}}% + \fi + \else + \Etoc@global\let\etocthelinkedpage\etocthepage + \fi + \Etoc@global\def\etocthename{#1}% + \futurelet\Etoc@getnb@token\Etoc@@getnb #1\hspace\etoc@ + \ifEtoc@hyperref + \def\Etoc@tmp##1##2{\Etoc@global\def##2{\hyperlink{#3}{##1}}}% + \expandafter\Etoc@tmp\expandafter{\etocthename}\etocthelinkedname + \ifEtoc@numbered + \expandafter\Etoc@tmp\expandafter{\etocthenumber}\etocthelinkednumber + \else + \Etoc@global\let\etocthelinkednumber\@empty + \fi + \else + \Etoc@global\let\etocthelinkedname \etocthename + \Etoc@global\let\etocthelinkednumber\etocthenumber + \fi + \Etoc@global\expandafter\let\csname etoclink \endcsname \etocthelink + \Etoc@global\expandafter\let\csname etocname \endcsname \etocthename + \Etoc@global\expandafter\let\csname etocnumber \endcsname\etocthenumber + \Etoc@global\expandafter\let\csname etocpage \endcsname \etocthepage + \ifEtoc@hyperref + \Etoc@lxyz@linktoc + \fi +} +\def\Etoc@lxyz@linktoc{% + \ifcase\Hy@linktoc + % none: nothing to do + \or % section (aka name for etoc): link name and number + \Etoc@global\expandafter\let\csname etocname \endcsname\etocthelinkedname + \Etoc@global\expandafter\let\csname etocnumber \endcsname\etocthelinkednumber + \or % page + \Etoc@global\expandafter\let\csname etocpage \endcsname\etocthelinkedpage + \else % all + \Etoc@global\expandafter\let\csname etocname \endcsname\etocthelinkedname + \Etoc@global\expandafter\let\csname etocnumber \endcsname\etocthelinkednumber + \Etoc@global\expandafter\let\csname etocpage \endcsname\etocthelinkedpage + \fi +} +\def\Etoc@@getnb {% + \let\Etoc@next\Etoc@getnb + \ifx\Etoc@getnb@token\@sptoken\let\Etoc@next\Etoc@getnb@nonbr\fi + \ifx\Etoc@getnb@token\bgroup \let\Etoc@next\Etoc@getnb@nonbr\fi + \Etoc@next +} +\def\Etoc@getnb #1{% + \in@{#1}{\numberline\chapternumberline\partnumberline\booknumberline}% + \ifin@ + \let\Etoc@next\Etoc@getnb@nmbrd + \else + \ifnum\Etoc@level=\m@ne + \let\Etoc@next\Etoc@@getit + \else + \let\Etoc@next\Etoc@getnb@nonbr + \fi + \in@{#1}{\nonumberline}% + \ifin@ + \let\Etoc@next\Etoc@getnb@nonumberline + \fi + \fi + \Etoc@next #1% +} +\def\Etoc@getnb@nmbrd #1#2{% + \Etoc@global\Etoc@numberedtrue + \Etoc@global\def\etocthenumber {#2}% + \Etoc@getnb@nmbrd@getname\@empty +}% +\def\Etoc@getnb@nmbrd@getname #1\hspace\etoc@ {% + \Etoc@global\expandafter\def\expandafter\etocthename\expandafter{#1}% +} +\def\Etoc@getnb@nonbr #1\etoc@ {% + \Etoc@global\Etoc@numberedfalse + \Etoc@global\let\etocthenumber \@empty +} +\def\Etoc@getnb@nonumberline #1\hspace\etoc@ {% + \Etoc@global\Etoc@numberedfalse + \Etoc@global\let\etocthenumber \@empty + \Etoc@global\expandafter\def\expandafter\etocthename\expandafter{\@gobble#1}% +} +\def\Etoc@@getit #1\hspace#2{% + \ifx\etoc@#2% + \Etoc@global\Etoc@numberedfalse + \Etoc@global\let\etocthenumber \@empty + \else + \Etoc@global\Etoc@numberedtrue + \Etoc@global\def\etocthenumber {#1}% + \expandafter\Etoc@getit@getname \expandafter\@empty + \fi +} +\def\Etoc@getit@getname #1\hspace\etoc@ {% + \Etoc@global\expandafter\def\expandafter\etocthename\expandafter{#1}% +} +\let\etocthename \@empty +\let\etocthenumber \@empty +\let\etocthepage \@empty +\let\etocthelinkedname \@empty +\let\etocthelinkednumber \@empty +\let\etocthelinkedpage \@empty +\let\etocthelink \@firstofone +\DeclareRobustCommand*{\etocname} {} +\DeclareRobustCommand*{\etocnumber}{} +\DeclareRobustCommand*{\etocpage} {} +\DeclareRobustCommand*{\etoclink} {\@firstofone} +\DeclareRobustCommand*{\etocifnumbered} + {\ifEtoc@numbered\expandafter\@firstoftwo\else\expandafter\@secondoftwo\fi} +\expandafter\let\expandafter\etocxifnumbered\csname etocifnumbered \endcsname +\DeclareRobustCommand*{\etociffirst} + {\ifEtoc@isfirst\expandafter\@firstoftwo\else\expandafter\@secondoftwo\fi} +\expandafter\let\expandafter\etocxiffirst\csname etociffirst \endcsname +\def\Etoc@readtoc {% + \ifeof \Etoc@tf + \else + \read \Etoc@tf to \Etoc@buffer + \Etoc@toctoks=\expandafter\expandafter\expandafter + {\expandafter\the\expandafter\Etoc@toctoks\Etoc@buffer}% + \expandafter\Etoc@readtoc + \fi +} +\Etoc@toctoks {}% (superfluous, but for clarity) +\AtBeginDocument{\IfFileExists{\jobname.toc} + {{\endlinechar=\m@ne + \makeatletter + \newread\Etoc@tf + \openin\Etoc@tf\@filef@und + \Etoc@readtoc + \global\Etoc@toctoks=\expandafter{\the\Etoc@toctoks}% + \closein\Etoc@tf}} + {\typeout{No file \jobname.toc.}}} +\def\Etoc@openouttoc{% + \ifEtoc@hyperref + \ifx\hyper@last\@undefined + \IfFileExists{\jobname .toc} + {\Hy@WarningNoLine + {old toc file detected; run LaTeX again (cheers from `etoc')}% + \global\Etoc@toctoks={}% + } + {}% + \fi + \fi + \if@filesw + \newwrite \tf@toc + \immediate \openout \tf@toc \jobname .toc\relax + \fi + \global\let\Etoc@openouttoc\empty +} +\def\Etoc@toctoc{% + \gdef\Etoc@stackofends{{-3}{}}% + \global\let\Etoc@level\Etoc@minf + \global\let\Etoc@virtualtop\Etoc@minf + \the\Etoc@toctoks + \ifEtoc@notactive + \else + \gdef\Etoc@level{-\thr@@}% + \Etoc@doendsandbegin + \fi +} +\def\Etoc@@startlocaltoc#1#2{% + \ifEtoc@localtoc + \ifnum #1=#2\relax + \global\let\etoclocaltop\Etoc@virtualtop + \Etoc@@startlocaltochook + \etoclocaltableofcontentshook + \ifEtoc@etocstyle + \etocetoclocaltocmaketitle + \fi + \ifx\Etoc@aftertitlehook\@empty + \else + \ifEtoc@localtoctotoc + \ifEtoc@ouroboros + \else + \let\Etoc@tmp\contentsline + \def\contentsline{\let\contentsline\Etoc@tmp\Etoc@gobblethreeorfour}% + \fi + \fi + \fi + \global\Etoc@notactivefalse + \fi + \fi +} +\let\etoc@startlocaltoc\@gobble +\let\Etoc@@startlocaltoc@toc\Etoc@@startlocaltoc +\let\Etoc@@startlocaltochook\@empty +\unless\ifEtoc@deeplevels + \def\etocdivisionnameatlevel#1{% + \ifcase\numexpr#1\relax + \ifdefined\c@chapter chapter\else section\fi% + \or section% + \or subsection% + \or subsubsection% + \or paragraph% + \or subparagraph% + \or empty% + \else\ifnum\numexpr#1<\m@ne + book% + \else + part% + \fi + \fi + } +\else + \def\etocdivisionnameatlevel#1{% + \ifcase\numexpr#1\relax + \ifdefined\c@chapter chapter\else section\fi% + \or section% + \or subsection% + \or subsubsection% + \or subsubsubsection% + \or subsubsubsubsection% + \or subsubsubsubsubsection% + \or subsubsubsubsubsubsection% + \or paragraph% + \or subparagraph% + \else\ifnum\numexpr#1>\z@ + empty% + \else\ifnum\numexpr#1=\m@ne + part% + \else + book% + \fi\fi + \fi + } +\fi +\def\etoclocalheadtotoc#1#2{\addcontentsline{toc}{@#1}{#2}} +\def\etocglobalheadtotoc{\addcontentsline{toc}} +\providecommand*\UseName{\@nameuse} +\def\etocetoclocaltocmaketitle{% + \UseName{\etocdivisionnameatlevel{\etoclocaltop+1}}*{\localcontentsname}% + \if@noskipsec\leavevmode\par\fi + \etociflocaltoctotoc + {\etocifisstarred + {}% star variant, do not add to toc + {\etoclocalheadtotoc + {\etocdivisionnameatlevel{\etoclocaltop+1}}% + {\localcontentsname}% + }% + }% + {}% +}% +\def\localcontentsname {\contentsname}% +\let\etoclocaltableofcontentshook\@empty +\if1\ifEtoc@lof0\fi\ifEtoc@lot0\fi1% +\else +\AtBeginDocument{% + \let\Etoc@originaladdcontentsline\addcontentsline + \def\addcontentsline{\Etoc@hackedaddcontentsline}% +}% +\fi +\ifEtoc@lof + \ifEtoc@lot + \def\Etoc@hackedaddcontentsline#1{% + \expanded{\noexpand\in@{.#1,}}{.lof,.lot,}% + \ifin@\expandafter\Etoc@hackedaddcontentsline@i + \else\expandafter\Etoc@originaladdcontentsline + \fi {#1}} + \else + \def\Etoc@hackedaddcontentsline#1{% + \expanded{\noexpand\in@{.#1,}}{.lof,}% + \ifin@\expandafter\Etoc@hackedaddcontentsline@i + \else\expandafter\Etoc@originaladdcontentsline + \fi {#1}} + \fi +\else + \def\Etoc@hackedaddcontentsline#1{% + \expanded{\noexpand\in@{.#1,}}{.lot,}% + \ifin@\expandafter\Etoc@hackedaddcontentsline@i + \else\expandafter\Etoc@originaladdcontentsline + \fi {#1}} +\fi +\def\Etoc@hackedaddcontentsline@i#1#2#3{% + \expanded{\noexpand\in@{.#1;#2,}}{.lof;figure,.lot;table,}% + \ifin@ + \addtocontents {toc}{% + \protect\contentsline{#2}{#3}{\thepage}{\ifEtoc@hyperref\@currentHref\fi}% + \ifdefined\protected@file@percent\protected@file@percent\fi + }% + \fi + \Etoc@originaladdcontentsline{#1}{#2}{#3}% +} +\unless\ifdefined\expanded + \def\Etoc@hackedaddcontentsline#1{% + {\edef\Etoc@tmp{\noexpand\in@{.#1,}{\ifEtoc@lof.lof,\fi\ifEtoc@lot.lot,\fi}}\expandafter}% + \Etoc@tmp + \ifin@\expandafter\Etoc@hackedaddcontentsline@i + \else\expandafter\Etoc@originaladdcontentsline + \fi {#1}% + } + \def\Etoc@hackedaddcontentsline@i#1#2#3{% + {\edef\Etoc@tmp{\noexpand\in@{.#1;#2,}}\expandafter}% + \Etoc@tmp{.lof;figure,.lot;table,}% + \ifin@ + \addtocontents {toc}{% + \protect\contentsline{#2}{#3}{\thepage}{\ifEtoc@hyperref\@currentHref\fi}% + \ifdefined\protected@file@percent\protected@file@percent\fi + }% + \fi + \Etoc@originaladdcontentsline{#1}{#2}{#3}% + } +\fi +\def\Etoc@@startlocallistof#1#2#3{% + \ifEtoc@localtoc + \ifnum #2=#3\relax + \global\let\etoclocaltop\Etoc@virtualtop + \global\Etoc@notactivefalse + \Etoc@@startlocaltochook + \csname etoclocallistof#1shook\endcsname + \ifEtoc@etocstyle + \csname etocetoclistof#1smaketitle\endcsname + \fi + \fi + \fi +} +\def\Etoc@@startlocallistof@setlevels#1{% + \ifnum\etoclocaltop<\z@ + \expandafter\let\csname Etoc@#1@@\endcsname\@ne + \else + \expandafter\let\csname Etoc@#1@@\expandafter\endcsname + \csname Etoc@\the\numexpr\etoclocaltop+\@ne @@\endcsname + \fi + \def\Etoc@do##1{% + \ifnum\etoclevel{##1}>\etoclocaltop + \expandafter\let\csname Etoc@##1@@\endcsname\Etoc@maxlevel + \fi}% + \Etoc@dolevels +} +\def\etoclocallistoffigureshook{\etocstandardlines} +\def\etoclocallistoftableshook {\etocstandardlines} +\def\locallistfigurename{\listfigurename} +\def\locallisttablename {\listtablename} +\def\etocetoclistoffiguresmaketitle{% + \UseName{\etocdivisionnameatlevel{\etoclocaltop+1}}*{\locallistfigurename}% + \ifnum\etoclocaltop>\tw@\mbox{}\par\fi + \etociflocalloftotoc + {\etocifisstarred + {}% star variant, do not add to toc + {\etoclocalheadtotoc + {\etocdivisionnameatlevel{\etoclocaltop+1}}% + {\locallistfigurename}% + }% + }% + {}% +}% +\def\etocetoclistoftablesmaketitle{% + \UseName{\etocdivisionnameatlevel{\etoclocaltop+1}}*{\locallisttablename}% + \ifnum\etoclocaltop>\tw@\mbox{}\par\fi + \etociflocallottotoc + {\etocifisstarred + {}% star variant, do not add to toc + {\etoclocalheadtotoc + {\etocdivisionnameatlevel{\etoclocaltop+1}}% + {\locallisttablename}% + }% + }% + {}% +}% +\let\Etoc@listofreset\@empty +\ifEtoc@lof + \def\locallistoffigures{% + \def\Etoc@listofreset{% + \let\Etoc@currext\Etoc@tocext + \let\Etoc@@startlocaltoc\Etoc@@startlocaltoc@toc + \let\Etoc@@startlocaltochook\@empty + \let\Etoc@listofreset\@empty + \let\Etoc@listofhook\@empty + }% + \let\Etoc@currext\Etoc@lofext + \def\Etoc@@startlocaltoc{\Etoc@@startlocallistof{figure}}% + \def\Etoc@@startlocaltochook{\Etoc@@startlocallistof@setlevels{figure}}% + \def\Etoc@listofhook{% + \def\Etoc@do####1{% + \expandafter\let\csname Etoc@@####1@@\endcsname\Etoc@maxlevel + }% + \Etoc@dolevels + }% + \localtableofcontents + } +\else + \def\locallistoffigures{% + \PackageError{etoc}{% + \string\locallistoffigures \on@line\space but\MessageBreak + package was loaded without `lof' option}% + {Try again with \string\usepackage[lof]{etoc}}% + } +\fi +\ifEtoc@lot + \def\locallistoftables{% + \def\Etoc@listofreset{% + \let\Etoc@currext\Etoc@tocext + \let\Etoc@@startlocaltoc\Etoc@@startlocaltoc@toc + \let\Etoc@@startlocaltochook\@empty + \let\Etoc@listofreset\@empty + \let\Etoc@listofhook\@empty + }% + \let\Etoc@currext\Etoc@lotext + \def\Etoc@@startlocaltoc{\Etoc@@startlocallistof{table}}% + \def\Etoc@@startlocaltochook{\Etoc@@startlocallistof@setlevels{table}}% + \def\Etoc@listofhook{% + \def\Etoc@do####1{% + \expandafter\let\csname Etoc@@####1@@\endcsname\Etoc@maxlevel + }% + \Etoc@dolevels + }% + \localtableofcontents + } +\else + \def\locallistoftables{% + \PackageError{etoc}{% + \string\locallistoftable \on@line\space but\MessageBreak + package was loaded without `lot' option}% + {Try again with \string\usepackage[lot]{etoc}}% + } +\fi +\def\Etoc@checkifempty {% + \global\Etoc@isemptytoctrue + \global\Etoc@stoptocfalse + \global\let\Etoc@level\Etoc@minf + \global\let\Etoc@virtualtop\Etoc@minf + \gdef\Etoc@stackofends{{-3}{}}% + \begingroup + \ifEtoc@localtoc + \def\etoc@startlocaltoc##1{% + \ifnum##1=\Etoc@tocid\relax + \global\let\etoclocaltop\Etoc@virtualtop + \Etoc@@startlocaltochook + \global\Etoc@notactivefalse + \fi + }% + \let\contentsline\Etoc@testingcontentslinelocal + \else + \let\contentsline\Etoc@testingcontentsline + \fi + \Etoc@storetocdepth + \let\Etoc@setlocaltop@doendsandbegin\@empty + \the\Etoc@toctoks + \Etoc@restoretocdepth + \endgroup +} +\DeclareRobustCommand*\etocifwasempty + {\ifEtoc@isemptytoc\expandafter\@firstoftwo\else\expandafter\@secondoftwo\fi } +\expandafter\let\expandafter\etocxifwasempty\csname etocifwasempty \endcsname +\def\Etoc@testingcontentslinelocal #1{% + \ifEtoc@stoptoc + \else + \ifnum\csname Etoc@#1@@\endcsname=\Etoc@maxlevel + \else + \global\expandafter\let\expandafter\Etoc@level\csname Etoc@#1@@\endcsname + \if @\@car#1\@nil\else\global\let\Etoc@virtualtop\Etoc@level\fi + \ifEtoc@notactive + \else + \ifnum\Etoc@level>\etoclocaltop + \unless\ifnum\Etoc@level>\c@tocdepth + \global\Etoc@isemptytocfalse + \global\Etoc@stoptoctrue + \fi + \else + \global\Etoc@stoptoctrue + \fi + \fi + \fi + \fi + \Etoc@gobblethreeorfour{}% +} +\def\Etoc@testingcontentsline #1{% + \ifEtoc@stoptoc + \else + \ifnum\csname Etoc@#1@@\endcsname=\Etoc@maxlevel + \else + \unless\ifnum\csname Etoc@#1@@\endcsname>\c@tocdepth + \global\Etoc@isemptytocfalse + \global\Etoc@stoptoctrue + \fi + \fi + \fi + \Etoc@gobblethreeorfour{}% +} +\def\Etoc@localtableofcontents#1{% + \gdef\etoclocaltop{-\@m}% + \Etoc@localtoctrue + \global\Etoc@isemptytocfalse + \edef\Etoc@tocid{#1}% + \ifnum\Etoc@tocid<\@ne + \setbox0\hbox{\ref{Unknown toc ref \@secondoftwo#1. \space Rerun LaTeX}}% + \global\Etoc@stoptoctrue + \gdef\etoclocaltop{-\thr@@}% + \Etoc@tableofcontents + \expandafter\Etoc@gobtoetoc@ + \fi + \global\Etoc@notactivetrue + \ifEtoc@checksemptiness + \Etoc@checkifempty + \fi + \ifEtoc@isemptytoc + \ifEtoc@notactive + \setbox0\hbox{\ref{Unknown toc ID \number\Etoc@tocid. \space Rerun LaTeX}}% + \global\Etoc@isemptytocfalse + \global\Etoc@stoptoctrue + \gdef\etoclocaltop{-\thr@@}% + \Etoc@tableofcontents + \expandafter\expandafter\expandafter\Etoc@gobtoetoc@ + \fi + \else + \global\Etoc@stoptocfalse + \global\Etoc@notactivetrue + \edef\etoc@startlocaltoc##1% + {\noexpand\Etoc@@startlocaltoc{##1}{\Etoc@tocid}}% + \Etoc@tableofcontents + \fi + \@gobble\etoc@ + \endgroup\ifEtoc@mustclosegroup\endgroup\fi + \Etoc@tocdepthreset + \Etoc@listofreset + \etocaftertochook +}% \Etoc@localtableofcontents +\def\Etoc@getref #1{% + \@ifundefined{r@#1} + {0} + {\expandafter\Etoc@getref@i\romannumeral-`0% + \expandafter\expandafter\expandafter + \@car\csname r@#1\endcsname0\@nil\@etoc + }% +} +\def\Etoc@getref@i#1#2\@etoc{\ifnum9<1\string#1 #1#2\else 0\fi} +\def\Etoc@ref#1{\Etoc@localtableofcontents{\Etoc@getref{#1}}} +\def\Etoc@label#1{\label{#1}\futurelet\Etoc@nexttoken\Etoc@t@bleofcontents} +\@firstofone{\def\Etoc@again} {\futurelet\Etoc@nexttoken\Etoc@t@bleofcontents} +\def\Etoc@dothis #1#2\etoc@ {\fi #1} +\def\Etoc@t@bleofcontents{% + \gdef\etoclocaltop{-\@M}% + \ifx\Etoc@nexttoken\label\Etoc@dothis{\expandafter\Etoc@label\@gobble}\fi + \ifx\Etoc@nexttoken\@sptoken\Etoc@dothis{\Etoc@again}\fi + \ifx\Etoc@nexttoken\ref\Etoc@dothis{\expandafter\Etoc@ref\@gobble}\fi + \ifEtoc@tocwithid\Etoc@dothis{\Etoc@localtableofcontents{\c@etoc@tocid}}\fi + \global\Etoc@isemptytocfalse + \ifEtoc@checksemptiness\Etoc@checkifempty\fi + \ifEtoc@isemptytoc + \ifEtoc@notocifnotoc + \expandafter\expandafter\expandafter\@gobble + \fi + \fi + \Etoc@tableofcontents + \endgroup + \ifEtoc@mustclosegroup\endgroup\fi + \Etoc@tocdepthreset + \Etoc@listofreset + \etocaftertochook + \@gobble\etoc@ + }% \Etoc@t@bleofcontents +\def\Etoc@table@fcontents{% + \refstepcounter{etoc@tocid}% + \Etoc@tocwithidfalse + \futurelet\Etoc@nexttoken\Etoc@t@bleofcontents +} +\def\Etoc@localtable@fcontents{% + \refstepcounter{etoc@tocid}% + \addtocontents{toc}{\string\etoc@startlocaltoc{\the\c@etoc@tocid}}% + \Etoc@tocwithidtrue + \futurelet\Etoc@nexttoken\Etoc@t@bleofcontents +} +\def\etoctableofcontents{% + \Etoc@openouttoc + \Etoc@tocdepthset + \begingroup + \@ifstar + {\let\Etoc@aftertitlehook\@empty\Etoc@table@fcontents} + {\def\Etoc@aftertitlehook{\etocaftertitlehook}\Etoc@table@fcontents}% +}% \etoctableofcontents +\def\etocifisstarred{\ifx\Etoc@aftertitlehook\@empty + \expandafter\@firstoftwo\else + \expandafter\@secondoftwo + \fi} +\let\etocoriginaltableofcontents\tableofcontents +\let\tableofcontents\etoctableofcontents +\let\Etoc@listofhook\@empty +\newcommand*\localtableofcontents{% + \Etoc@openouttoc + \Etoc@tocdepthset + \begingroup + \Etoc@listofhook + \@ifstar + {\let\Etoc@aftertitlehook\@empty\Etoc@localtable@fcontents} + {\def\Etoc@aftertitlehook{\etocaftertitlehook}\Etoc@localtable@fcontents}% +}% \localtableofcontents +\newcommand*\localtableofcontentswithrelativedepth[1]{% + \def\Etoc@@startlocaltochook{% + \global\c@tocdepth\numexpr\etoclocaltop+#1\relax + }% + \def\Etoc@listofreset{\let\Etoc@@startlocaltochook\@empty + \let\Etoc@listofreset\@empty}% + \localtableofcontents +}% \localtableofcontentswithrelativedepth +\newcommand\etocsettocstyle[2]{% + \Etoc@etocstylefalse + \Etoc@classstylefalse + \def\Etoc@tableofcontents@user@before{#1}% + \def\Etoc@tableofcontents@user@after {#2}% +}% +\def\etocstoretocstyleinto#1{% +%% \@ifdefinable#1{% + \edef#1{\noexpand\Etoc@etocstylefalse\noexpand\Etoc@classstylefalse + \def\noexpand\Etoc@tableofcontents@user@before{% + \unexpanded\expandafter{\Etoc@tableofcontents@user@before}% + }% + \def\noexpand\Etoc@tableofcontents@user@after{% + \unexpanded\expandafter{\Etoc@tableofcontents@user@after}% + }% + }% +%% }% +}% +\def\Etoc@tableofcontents {% + \Etoc@tableofcontents@etoc@before + \ifEtoc@localtoc\ifEtoc@etocstyle\expandafter\expandafter\expandafter\@gobble\fi\fi + \Etoc@tableofcontents@user@before + \Etoc@tableofcontents@contents + \ifEtoc@localtoc\ifEtoc@etocstyle\expandafter\expandafter\expandafter\@gobble\fi\fi + \Etoc@tableofcontents@user@after + \Etoc@tableofcontents@etoc@after + \@gobble\etoc@ +} +\def\Etoc@tableofcontents@etoc@before{% + \ifnum\c@tocdepth>\Etoc@minf + \else + \expandafter\Etoc@gobtoetoc@ + \fi + \Etoc@par + \Etoc@beforetitlehook + \etocbeforetitlehook + \Etoc@storetocdepth + \let\Etoc@savedcontentsline\contentsline + \let\contentsline\Etoc@etoccontentsline + \ifEtoc@standardlines + \else + \def\Etoc@do##1{% + \expandafter\def\csname etocsaved##1tocline\endcsname + {\PackageError{etoc}{% + \expandafter\string\csname etocsaved##1tocline\endcsname\space + has been deprecated\MessageBreak + at 1.1a and is removed at 1.2.\MessageBreak + Use \expandafter\string\csname l@##1\endcsname\space directly.\MessageBreak + Reported \on@line}% + {I will use \expandafter\string + \csname l@##1\endcsname\space myself for this time.% + }% + \csname l@##1\endcsname + }% + }% + \Etoc@dolevels + \fi +}% +\def\Etoc@tableofcontents@contents{% + \Etoc@tocdepthset + \ifEtoc@parskip\parskip\z@skip\fi + \Etoc@aftertitlehook + \gdef\etoclocaltop{-\thr@@}% + \Etoc@toctoc + \etocaftercontentshook +}% +\def\Etoc@tableofcontents@etoc@after{% + \@nobreakfalse + \Etoc@restoretocdepth + \ifx\Etoc@global\global + \@ifundefined{tof@finish} + {} + {\ifx\tof@finish\@empty + \else + \global\let\contentsline\Etoc@savedcontentsline + \fi + }% + \fi +} +\def\etocsetstyle#1{\ifcsname Etoc@#1@@\endcsname + \expandafter\Etoc@setstyle@a + \else + \expandafter\Etoc@setstyle@error + \fi {#1}% +} +\def\Etoc@setstyle@error #1{% + \PackageWarning{etoc}{`#1' is unknown to etoc. \space Did you\MessageBreak + forget some \string\etocsetlevel{#1}{}?\MessageBreak + Reported}% + \@gobblefour +} +\def\Etoc@setstyle@a #1{% + \edef\Etoc@tmp{\the\numexpr\csname Etoc@#1@@\endcsname}% + \if1\unless\ifnum\Etoc@tmp<\Etoc@maxlevel 0\fi + \unless\ifnum\Etoc@tmp>\Etoc@minf 0\fi1% + \Etoc@standardlinesfalse + \expandafter\Etoc@setstyle@b\expandafter\Etoc@tmp + \else + \ifnum\Etoc@tmp=\Etoc@maxlevel + \in@{.#1,}{.figure,.table,}% + \ifin@ + \PackageWarning{etoc} + {You can not use \string\etocsetstyle\space with `#1'.\MessageBreak + Check the package documentation (in particular about\MessageBreak + \string\etoclocallistoffigureshook/\string\etoclocallistoftableshook)% + \MessageBreak on how to customize + figure and table entries in local\MessageBreak lists. Reported}% + \else + \PackageInfo{etoc} + {Attempt to set the style of `#1',\MessageBreak + whose level is currently the maximal one \etocthemaxlevel,\MessageBreak + which is never displayed. \space This will be ignored\MessageBreak + but note that we do quit compatibility mode.\MessageBreak + Reported}% + \Etoc@standardlinesfalse + \fi + \else + \PackageWarning{etoc}{This should not happen. Reported}% + \fi + \expandafter\@gobblefour + \fi +} +\long\def\Etoc@setstyle@b#1#2#3#4#5{% + \expandafter\def\csname Etoc@begin@#1\endcsname {#2}% + \expandafter\def\csname Etoc@prefix@#1\endcsname {#3}% + \expandafter\def\csname Etoc@contents@#1\endcsname {#4}% + \expandafter\def\csname Etoc@end@#1\endcsname {#5}% +} +\def\Etoc@setstyle@e#1{% + \expandafter\let\csname Etoc@begin@#1\endcsname \@empty + \expandafter\let\csname Etoc@prefix@#1\endcsname \@empty + \expandafter\let\csname Etoc@contents@#1\endcsname \@empty + \expandafter\let\csname Etoc@end@#1\endcsname \@empty +} +\def\Etoc@storelines@a#1{% + \noexpand\Etoc@setstyle@b{#1}% + {\expandafter\Etoc@expandonce\csname Etoc@begin@#1\endcsname}% + {\expandafter\Etoc@expandonce\csname Etoc@prefix@#1\endcsname}% + {\expandafter\Etoc@expandonce\csname Etoc@contents@#1\endcsname}% + {\expandafter\Etoc@expandonce\csname Etoc@end@#1\endcsname}% +} +\def\Etoc@expandonce#1{\unexpanded\expandafter{#1}} +\def\etocstorelinestylesinto#1{% + \edef#1{\Etoc@storelines@a{-2}\Etoc@storelines@a{-1}\Etoc@storelines@a{0}% + \Etoc@storelines@a {1}\Etoc@storelines@a {2}\Etoc@storelines@a{3}% + \Etoc@storelines@a {4}\Etoc@storelines@a {5}% + \ifEtoc@deeplevels + \Etoc@storelines@a{6}\Etoc@storelines@a{7}\Etoc@storelines@a{8}% + \Etoc@storelines@a{9}\Etoc@storelines@a{10}\Etoc@storelines@a{11}% + \fi + }% +} +\def\etocstorethislinestyleinto#1#2{% + \edef#2{\expandafter\Etoc@storelines@a\expandafter{\number\etoclevel{#1}}}% +}% +\def\etocfontminustwo {\normalfont \LARGE \bfseries} +\def\etocfontminusone {\normalfont \large \bfseries} +\def\etocfontzero {\normalfont \large \bfseries} +\def\etocfontone {\normalfont \normalsize \bfseries} +\def\etocfonttwo {\normalfont \normalsize} +\def\etocfontthree {\normalfont \footnotesize} +\def\etocsepminustwo {4ex \@plus .5ex \@minus .5ex} +\def\etocsepminusone {4ex \@plus .5ex \@minus .5ex} +\def\etocsepzero {2.5ex \@plus .4ex \@minus .4ex} +\def\etocsepone {1.5ex \@plus .3ex \@minus .3ex} +\def\etocseptwo {.5ex \@plus .1ex \@minus .1ex} +\def\etocsepthree {.25ex \@plus .05ex \@minus .05ex} +\def\etocbaselinespreadminustwo {1} +\def\etocbaselinespreadminusone {1} +\def\etocbaselinespreadzero {1} +\def\etocbaselinespreadone {1} +\def\etocbaselinespreadtwo {1} +\def\etocbaselinespreadthree {.9} +\def\etocminustwoleftmargin {1.5em plus 0.5fil} +\def\etocminustworightmargin {1.5em plus -0.5fil} +\def\etocminusoneleftmargin {1em} +\def\etocminusonerightmargin {1em} +\def\etoctoclineleaders + {\hbox{\normalfont\normalsize\hb@xt@2ex {\hss.\hss}}} +\def\etocabbrevpagename {p.~} +\def\etocpartname {Part} +\def\etocbookname {Book} +\def\etocdefaultlines{% + \Etoc@standardlinesfalse + \etocdefaultlines@setbook + \etocdefaultlines@setpart + \etocdefaultlines@setchapter + \etocdefaultlines@setsection + \etocdefaultlines@setsubsection + \etocdefaultlines@setsubsubsection + \etocdefaultlines@setdeeperones +} +\@ifclassloaded{memoir}{% + \def\etocdefaultlines@setbook{% + \Etoc@setstyle@b + {-2}% + {\addpenalty\@M\etocskipfirstprefix} + {\addpenalty\@secpenalty} + {\begingroup + \etocfontminustwo + \addvspace{\etocsepminustwo}% + \parindent \z@ + \leftskip \etocminustwoleftmargin + \rightskip \etocminustworightmargin + \parfillskip \@flushglue + \vbox{\etocifnumbered{\etoclink{\etocbookname\enspace\etocthenumber:\quad}}{}% + \etocname + \baselineskip\etocbaselinespreadminustwo\baselineskip + \par}% + \addpenalty\@M\addvspace{\etocsepminusone}% + \endgroup} + {}% + } + }{\let\etocdefaultlines@setbook\@empty} +\def\etocdefaultlines@setpart{% +\Etoc@setstyle@b + {-1}% + {\addpenalty\@M\etocskipfirstprefix} + {\addpenalty\@secpenalty} + {\begingroup + \etocfontminusone + \addvspace{\etocsepminusone}% + \parindent \z@ + \leftskip \etocminusoneleftmargin + \rightskip \etocminusonerightmargin + \parfillskip \@flushglue + \vbox{\etocifnumbered{\etoclink{\etocpartname\enspace\etocthenumber.\quad}}{}% + \etocname + \baselineskip\etocbaselinespreadminusone\baselineskip + \par}% + \addpenalty\@M\addvspace{\etocsepzero}% + \endgroup} + {}% +} +\def\etocdefaultlines@setchapter{% +\Etoc@setstyle@b + {0}% + {\addpenalty\@M\etocskipfirstprefix} + {\addpenalty\@itempenalty} + {\begingroup + \etocfontzero + \addvspace{\etocsepzero}% + \parindent \z@ \parfillskip \@flushglue + \vbox{\etocifnumbered{\etocnumber.\enspace}{}\etocname + \baselineskip\etocbaselinespreadzero\baselineskip + \par}% + \endgroup} + {\addpenalty{-\@highpenalty}\addvspace{\etocsepminusone}}% +} +\def\etocdefaultlines@setsection{% +\Etoc@setstyle@b + {1}% + {\addpenalty\@M\etocskipfirstprefix} + {\addpenalty\@itempenalty} + {\begingroup + \etocfontone + \addvspace{\etocsepone}% + \parindent \z@ \parfillskip \z@ + \setbox\z@\vbox{\parfillskip\@flushglue + \etocname\par + \setbox\tw@\lastbox + \global\setbox\@ne\hbox{\unhbox\tw@\ }}% + \dimen\z@=\wd\@ne + \setbox\z@=\etoctoclineleaders + \advance\dimen\z@\wd\z@ + \etocifnumbered + {\setbox\tw@\hbox{\etocnumber, \etocabbrevpagename\etocpage}} + {\setbox\tw@\hbox{\etocabbrevpagename\etocpage}}% + \advance\dimen\z@\wd\tw@ + \ifdim\dimen\z@ < \linewidth + \vbox{\etocname~% + \leaders\box\z@\hfil\box\tw@ + \baselineskip\etocbaselinespreadone\baselineskip + \par}% + \else + \vbox{\etocname~% + \leaders\copy\z@\hfil\break + \hbox{}\leaders\box\z@\hfil\box\tw@ + \baselineskip\etocbaselinespreadone\baselineskip + \par}% + \fi + \endgroup} + {\addpenalty\@secpenalty\addvspace{\etocsepzero}}% +} +\def\etocdefaultlines@setsubsection{% +\Etoc@setstyle@b + {2}% + {\addpenalty\@medpenalty\etocskipfirstprefix} + {\addpenalty\@itempenalty} + {\begingroup + \etocfonttwo + \addvspace{\etocseptwo}% + \parindent \z@ \parfillskip \z@ + \setbox\z@\vbox{\parfillskip\@flushglue + \etocname\par\setbox\tw@\lastbox + \global\setbox\@ne\hbox{\unhbox\tw@}}% + \dimen\z@=\wd\@ne + \setbox\z@=\etoctoclineleaders + \advance\dimen\z@\wd\z@ + \etocifnumbered + {\setbox\tw@\hbox{\etocnumber, \etocabbrevpagename\etocpage}} + {\setbox\tw@\hbox{\etocabbrevpagename\etocpage}}% + \advance\dimen\z@\wd\tw@ + \ifdim\dimen\z@ < \linewidth + \vbox{\etocname~% + \leaders\box\z@\hfil\box\tw@ + \baselineskip\etocbaselinespreadtwo\baselineskip + \par}% + \else + \vbox{\etocname~% + \leaders\copy\z@\hfil\break + \hbox{}\leaders\box\z@\hfil\box\tw@ + \baselineskip\etocbaselinespreadtwo\baselineskip + \par}% + \fi + \endgroup} + {\addpenalty\@secpenalty\addvspace{\etocsepone}}% +} +\def\etocdefaultlines@setsubsubsection{% +\Etoc@setstyle@b + {3}% + {\addpenalty\@M + \etocfontthree + \vspace{\etocsepthree}% + \noindent + \etocskipfirstprefix} + {\allowbreak\,--\,} + {\etocname} + {.\hfil + \begingroup + \baselineskip\etocbaselinespreadthree\baselineskip + \par + \endgroup + \addpenalty{-\@highpenalty}} +} +\def\etocdefaultlines@setdeeperones{% +\Etoc@setstyle@e{4}% +\Etoc@setstyle@e{5}% +\ifEtoc@deeplevels + \Etoc@setstyle@e{6}% + \Etoc@setstyle@e{7}% + \Etoc@setstyle@e{8}% + \Etoc@setstyle@e{9}% + \Etoc@setstyle@e{10}% + \Etoc@setstyle@e{11}% +\fi +} +\def\etocabovetocskip{3.5ex \@plus 1ex \@minus .2ex} +\def\etocbelowtocskip{3.5ex \@plus 1ex \@minus .2ex} +\def\etoccolumnsep{2em} +\def\etocmulticolsep{0ex} +\def\etocmulticolpretolerance{-1} +\def\etocmulticoltolerance{200} +\def\etocdefaultnbcol{2} +\def\etocinnertopsep{2ex} +\newcommand\etocmulticolstyle[2][\etocdefaultnbcol]{% +\etocsettocstyle + {\let\etocoldpar\par + \addvspace{\etocabovetocskip}% + \ifnum #1>\@ne + \expandafter\@firstoftwo + \else \expandafter\@secondoftwo + \fi + {\multicolpretolerance\etocmulticolpretolerance + \multicoltolerance\etocmulticoltolerance + \setlength{\columnsep}{\etoccolumnsep}% + \setlength{\multicolsep}{\etocmulticolsep}% + \begin{multicols}{#1}[#2\etocoldpar\addvspace{\etocinnertopsep}]} + {#2\ifvmode\else\begingroup\interlinepenalty\@M\parskip\z@skip + \@@par\endgroup + \fi + \nobreak\addvspace{\etocinnertopsep}% + \pretolerance\etocmulticolpretolerance + \tolerance\etocmulticoltolerance}% + }% + {\ifnum #1>\@ne + \expandafter\@firstofone + \else \expandafter\@gobble + \fi + {\end{multicols}}% + \addvspace{\etocbelowtocskip}}% +} +\def\etocinnerbottomsep{3.5ex} +\def\etocinnerleftsep{2em} +\def\etocinnerrightsep{2em} +\def\etoctoprule{\hrule} +\def\etocleftrule{\vrule} +\def\etocrightrule{\vrule} +\def\etocbottomrule{\hrule} +\def\etoctoprulecolorcmd{\relax} +\def\etocbottomrulecolorcmd{\relax} +\def\etocleftrulecolorcmd{\relax} +\def\etocrightrulecolorcmd{\relax} +\def\etoc@ruledheading #1{% + \hb@xt@\linewidth{\color@begingroup + \hss #1\hss\hskip-\linewidth + \etoctoprulecolorcmd\leaders\etoctoprule\hss + \phantom{#1}% + \leaders\etoctoprule\hss\color@endgroup}% + \nointerlineskip\nobreak\vskip\etocinnertopsep} +\newcommand*\etocruledstyle[2][\etocdefaultnbcol]{% +\etocsettocstyle + {\addvspace{\etocabovetocskip}% + \ifnum #1>\@ne + \expandafter\@firstoftwo + \else \expandafter\@secondoftwo + \fi + {\multicolpretolerance\etocmulticolpretolerance + \multicoltolerance\etocmulticoltolerance + \setlength{\columnsep}{\etoccolumnsep}% + \setlength{\multicolsep}{\etocmulticolsep}% + \begin{multicols}{#1}[\etoc@ruledheading{#2}]} + {\etoc@ruledheading{#2}% + \pretolerance\etocmulticolpretolerance + \tolerance\etocmulticoltolerance}} + {\ifnum #1>\@ne\expandafter\@firstofone + \else \expandafter\@gobble + \fi + {\end{multicols}}% + \addvspace{\etocbelowtocskip}}} +\def\etocframedmphook{\relax} +\long\def\etocbkgcolorcmd{\relax} +\long\def\Etoc@relax{\relax} +\newbox\etoc@framed@titlebox +\newbox\etoc@framed@contentsbox +\newcommand*\etocframedstyle[2][\etocdefaultnbcol]{% +\etocsettocstyle{% + \addvspace{\etocabovetocskip}% + \sbox\z@{#2}% + \dimen\z@\dp\z@ + \ifdim\wd\z@<\linewidth \dp\z@\z@ \else \dimen\z@\z@ \fi + \setbox\etoc@framed@titlebox=\hb@xt@\linewidth{\color@begingroup + \hss + \ifx\etocbkgcolorcmd\Etoc@relax + \else + \sbox\tw@{\color{white}% + \vrule\@width\wd\z@\@height\ht\z@\@depth\dimen\z@}% + \ifdim\wd\z@<\linewidth \dp\tw@\z@\fi + \box\tw@ + \hskip-\wd\z@ + \fi + \copy\z@ + \hss + \hskip-\linewidth + \etoctoprulecolorcmd\leaders\etoctoprule\hss + \hskip\wd\z@ + \etoctoprulecolorcmd\leaders\etoctoprule\hss\color@endgroup}% + \setbox\z@\hbox{\etocleftrule\etocrightrule}% + \dimen\tw@\linewidth\advance\dimen\tw@-\wd\z@ + \advance\dimen\tw@-\etocinnerleftsep + \advance\dimen\tw@-\etocinnerrightsep + \setbox\etoc@framed@contentsbox=\vbox\bgroup + \hsize\dimen\tw@ + \kern\dimen\z@ + \vskip\etocinnertopsep + \hbox\bgroup + \begin{minipage}{\hsize}% + \etocframedmphook + \ifnum #1>\@ne + \expandafter\@firstoftwo + \else \expandafter\@secondoftwo + \fi + {\multicolpretolerance\etocmulticolpretolerance + \multicoltolerance\etocmulticoltolerance + \setlength{\columnsep}{\etoccolumnsep}% + \setlength{\multicolsep}{\etocmulticolsep}% + \begin{multicols}{#1}} + {\pretolerance\etocmulticolpretolerance + \tolerance\etocmulticoltolerance}} + {\ifnum #1>\@ne\expandafter\@firstofone + \else \expandafter\@gobble + \fi + {\end{multicols}\unskip }% + \end{minipage}% + \egroup + \vskip\etocinnerbottomsep + \egroup + \vbox{\hsize\linewidth + \ifx\etocbkgcolorcmd\Etoc@relax + \else + \kern\ht\etoc@framed@titlebox + \kern\dp\etoc@framed@titlebox + \hb@xt@\linewidth{\color@begingroup + \etocleftrulecolorcmd\etocleftrule + \etocbkgcolorcmd + \leaders\vrule + \@height\ht\etoc@framed@contentsbox + \@depth\dp\etoc@framed@contentsbox + \hss + \etocrightrulecolorcmd\etocrightrule + \color@endgroup}\nointerlineskip + \vskip-\dp\etoc@framed@contentsbox + \vskip-\ht\etoc@framed@contentsbox + \vskip-\dp\etoc@framed@titlebox + \vskip-\ht\etoc@framed@titlebox + \fi + \box\etoc@framed@titlebox\nointerlineskip + \hb@xt@\linewidth{\color@begingroup + {\etocleftrulecolorcmd\etocleftrule}% + \hss\box\etoc@framed@contentsbox\hss + \etocrightrulecolorcmd\etocrightrule\color@endgroup} + \nointerlineskip + \vskip\ht\etoc@framed@contentsbox + \vskip\dp\etoc@framed@contentsbox + \hb@xt@\linewidth{\color@begingroup\etocbottomrulecolorcmd + \leaders\etocbottomrule\hss\color@endgroup}} + \addvspace{\etocbelowtocskip}}} +\newcommand\etoc@multicoltoc[2][\etocdefaultnbcol]{% + \etocmulticolstyle[#1]{#2}% + \tableofcontents} +\newcommand\etoc@multicoltoci[2][\etocdefaultnbcol]{% + \etocmulticolstyle[#1]{#2}% + \tableofcontents*} +\newcommand\etoc@local@multicoltoc[2][\etocdefaultnbcol]{% + \etocmulticolstyle[#1]{#2}% + \localtableofcontents} +\newcommand\etoc@local@multicoltoci[2][\etocdefaultnbcol]{% + \etocmulticolstyle[#1]{#2}% + \localtableofcontents*} +\newcommand*\etoc@ruledtoc[2][\etocdefaultnbcol]{% + \etocruledstyle[#1]{#2}% + \tableofcontents} +\newcommand*\etoc@ruledtoci[2][\etocdefaultnbcol]{% + \etocruledstyle[#1]{#2}% + \tableofcontents*} +\newcommand*\etoc@local@ruledtoc[2][\etocdefaultnbcol]{% + \etocruledstyle[#1]{#2}% + \localtableofcontents} +\newcommand*\etoc@local@ruledtoci[2][\etocdefaultnbcol]{% + \etocruledstyle[#1]{#2}% + \localtableofcontents*} +\newcommand*\etoc@framedtoc[2][\etocdefaultnbcol]{% + \etocframedstyle[#1]{#2}% + \tableofcontents} +\newcommand*\etoc@framedtoci[2][\etocdefaultnbcol]{% + \etocframedstyle[#1]{#2}% + \tableofcontents*} +\newcommand*\etoc@local@framedtoc[2][\etocdefaultnbcol]{% + \etocframedstyle[#1]{#2}% + \localtableofcontents} +\newcommand*\etoc@local@framedtoci[2][\etocdefaultnbcol]{% + \etocframedstyle[#1]{#2}% + \localtableofcontents*} +\def\etocmulticol{\begingroup + \Etoc@mustclosegrouptrue + \@ifstar + {\etoc@multicoltoci} + {\etoc@multicoltoc}} +\def\etocruled{\begingroup + \Etoc@mustclosegrouptrue + \@ifstar + {\etoc@ruledtoci} + {\etoc@ruledtoc}} +\def\etocframed{\begingroup + \Etoc@mustclosegrouptrue + \@ifstar + {\etoc@framedtoci} + {\etoc@framedtoc}} +\def\etoclocalmulticol{\begingroup + \Etoc@mustclosegrouptrue + \@ifstar + {\etoc@local@multicoltoci} + {\etoc@local@multicoltoc}} +\def\etoclocalruled{\begingroup + \Etoc@mustclosegrouptrue + \@ifstar + {\etoc@local@ruledtoci} + {\etoc@local@ruledtoc}} +\def\etoclocalframed{\begingroup + \Etoc@mustclosegrouptrue + \@ifstar + {\etoc@local@framedtoci} + {\etoc@local@framedtoc}} +\def\etocmemoirtoctotocfmt #1#2{% + \PackageWarning{etoc} + {\string\etocmemoirtoctotocfmt\space is deprecated.\MessageBreak + Use in its place \string\etocsettoclineforclasstoc,\MessageBreak + and \string\etocsettoclineforclasslistof{toc} (or {lof}, {lot}). + I will do this now.\MessageBreak + Reported}% + \etocsettoclineforclasstoc{#1}{#2}% + \etocsettoclineforclasslistof{toc}{#1}{#2}% +} +\def\etocsettoclineforclasstoc #1#2{% + \def\etocclassmaintocaddtotoc{\etocglobalheadtotoc{#1}{#2}}% +} +\def\etocsettoclineforclasslistof #1#2#3{% + \@namedef{etocclasslocal#1addtotoc}{\etoclocalheadtotoc{#2}{#3}}% +} +\let\etocclasslocaltocaddtotoc\@empty +\let\etocclasslocallofaddtotoc\@empty +\let\etocclasslocallotaddtotoc\@empty +\ifdefined\c@chapter + \def\etocclasslocaltocmaketitle{\section*{\localcontentsname}} + \def\etocclasslocallofmaketitle{\section*{\locallistfigurename}} + \def\etocclasslocallotmaketitle{\section*{\locallisttablename}} + \etocsettoclineforclasstoc {chapter}{\contentsname} + \etocsettoclineforclasslistof{toc}{section}{\localcontentsname} + \etocsettoclineforclasslistof{lof}{section}{\locallistfigurename} + \etocsettoclineforclasslistof{lot}{section}{\locallisttablename} +\else + \def\etocclasslocaltocmaketitle{\subsection*{\localcontentsname}}% + \def\etocclasslocallofmaketitle{\subsection*{\locallistfigurename}}% + \def\etocclasslocallotmaketitle{\subsection*{\locallisttablename}}% + \etocsettoclineforclasstoc {section}{\contentsname} + \etocsettoclineforclasslistof{toc}{subsection}{\localcontentsname} + \etocsettoclineforclasslistof{lof}{subsection}{\locallistfigurename} + \etocsettoclineforclasslistof{lot}{subsection}{\locallisttablename} +\fi +\def\etocclasslocalperhapsaddtotoc #1{% + \etocifisstarred + {} + {\csname ifEtoc@local#1totoc\endcsname + \csname etocclasslocal#1addtotoc\endcsname + \fi + }% +} +\def\etocarticlestyle{% + \etocsettocstyle + {\ifEtoc@localtoc + \@nameuse{etocclasslocal\Etoc@currext maketitle}% + \etocclasslocalperhapsaddtotoc\Etoc@currext + \else + \section *{\contentsname + \@mkboth {\MakeUppercase \contentsname} + {\MakeUppercase \contentsname}}% + \etocifisstarred{}{\etocifmaintoctotoc{\etocclassmaintocaddtotoc}{}}% + \fi + } + {}% +} +\def\etocarticlestylenomarks{% + \etocsettocstyle + {\ifEtoc@localtoc + \@nameuse{etocclasslocal\Etoc@currext maketitle}% + \etocclasslocalperhapsaddtotoc\Etoc@currext + \else + \section *{\contentsname}% + \etocifisstarred{}{\etocifmaintoctotoc{\etocclassmaintocaddtotoc}{}}% + \fi + } + {}% +} +\def\etocbookstyle{% + \etocsettocstyle + {\if@twocolumn \@restonecoltrue \onecolumn \else \@restonecolfalse \fi + \ifEtoc@localtoc + \@nameuse{etocclasslocal\Etoc@currext maketitle}% + \etocclasslocalperhapsaddtotoc\Etoc@currext + \else + \chapter *{\contentsname + \@mkboth {\MakeUppercase \contentsname} + {\MakeUppercase \contentsname}}% + \etocifisstarred{}{\etocifmaintoctotoc{\etocclassmaintocaddtotoc}{}}% + \fi + }% + {\if@restonecol \twocolumn \fi}% +} +\def\etocbookstylenomarks{% + \etocsettocstyle + {\if@twocolumn \@restonecoltrue \onecolumn \else \@restonecolfalse \fi + \ifEtoc@localtoc + \@nameuse{etocclasslocal\Etoc@currext maketitle}% + \etocclasslocalperhapsaddtotoc\Etoc@currext + \else + \chapter *{\contentsname}% + \etocifisstarred{}{\etocifmaintoctotoc{\etocclassmaintocaddtotoc}{}}% + \fi + }% + {\if@restonecol \twocolumn \fi}% +} +\let\etocreportstyle\etocbookstyle +\let\etocreportstylenomarks\etocbookstylenomarks +\def\etocmemoirstyle{% + \etocsettocstyle + {\ensureonecol \par \begingroup \phantomsection + \ifx\Etoc@aftertitlehook\@empty + \else + \ifmem@em@starred@listof + \else + \ifEtoc@localtoc + \etocclasslocalperhapsaddtotoc\Etoc@currext + \else + \ifEtoc@maintoctotoc + \etocclassmaintocaddtotoc + \fi + \fi + \fi + \fi + \ifEtoc@localtoc + % trying to mimic a section title but there is no \sectionheadstart + % there is no \printsectiontitle etc... Oh well I will be more + % radical then + \@namedef{@\Etoc@currext maketitle}{% + \@nameuse{etocclasslocal\Etoc@currext maketitle}% + }% + \fi + \@nameuse {@\Etoc@currext maketitle} %<< space token here from memoir code + \ifx\Etoc@aftertitlehook\@empty + \else + \Etoc@aftertitlehook \let \Etoc@aftertitlehook \relax + \fi + \parskip \cftparskip \@nameuse {cft\Etoc@currext beforelisthook}% + }% + {\@nameuse {cft\Etoc@currext afterlisthook}% + \endgroup\restorefromonecol + }% +} +\let\Etoc@beforetitlehook\@empty +\if1\@ifclassloaded{scrartcl}0{\@ifclassloaded{scrbook}0{\@ifclassloaded{scrreprt}01}}% +\expandafter\@gobble +\else + \ifdefined\setuptoc + \def\Etoc@beforetitlehook{% + \ifEtoc@localtoc + \etocclasslocalperhapsaddtotoc\Etoc@currext + \setuptoc{\Etoc@currext}{leveldown}% + \else + \etocifisstarred{}{\etocifmaintoctotoc{\setuptoc{toc}{totoc}}}% + \fi + }% + \fi +\expandafter\@firstofone +\fi +{\def\etocclasslocalperhapsaddtotoc #1{% + \etocifisstarred + {}% + {\csname ifEtoc@local#1totoc\endcsname + \setuptoc{\Etoc@currext}{totoc}% + \fi + }% + }% +} +\ifdefined\Iftocfeature + \def\etoc@Iftocfeature{\Iftocfeature}% +\else + \def\etoc@Iftocfeature{\iftocfeature}% +\fi +\def\etocscrartclstyle{% + \etocsettocstyle + {\ifx\Etoc@currext\Etoc@tocext + \expandafter\@firstofone + \else + \expandafter\@gobble + \fi + {\let\if@dynlist\if@tocleft}% + \edef\@currext{\Etoc@currext}% + \@ifundefined{listof\@currext name}% + {\def\list@fname{\listofname~\@currext}}% + {\expandafter\let\expandafter\list@fname + \csname listof\@currext name\endcsname}% + \etoc@Iftocfeature {\@currext}{onecolumn} + {\etoc@Iftocfeature {\@currext}{leveldown} + {} + {\if@twocolumn \aftergroup \twocolumn \onecolumn \fi }} + {}% + \etoc@Iftocfeature {\@currext}{numberline}% + {\def \nonumberline {\numberline {}}}{}% + \expandafter\tocbasic@listhead\expandafter {\list@fname}% + \begingroup \expandafter \expandafter \expandafter + \endgroup \expandafter + \ifx + \csname microtypesetup\endcsname \relax + \else + \etoc@Iftocfeature {\@currext}{noprotrusion}{} + {\microtypesetup {protrusion=false}% + \PackageInfo {tocbasic}% + {character protrusion at \@currext\space deactivated}}% + \fi + \etoc@Iftocfeature{\@currext}{noparskipfake}{}{% + \ifvmode \@tempskipa\lastskip \vskip-\lastskip + \addtolength{\@tempskipa}{\parskip}\vskip\@tempskipa\fi + }% + \setlength {\parskip }{\z@ }% + \setlength {\parindent }{\z@ }% + \setlength {\parfillskip }{\z@ \@plus 1fil}% + \csname tocbasic@@before@hook\endcsname + \csname tb@\@currext @before@hook\endcsname + }% end of before_toc + {% start of after_toc + \providecommand\tocbasic@end@toc@file{}\tocbasic@end@toc@file + \edef\@currext{\Etoc@currext}% + \csname tb@\@currext @after@hook\endcsname + \csname tocbasic@@after@hook\endcsname + }% end of after_toc +} +\let\etocscrbookstyle\etocscrartclstyle +\let\etocscrreprtstyle\etocscrartclstyle +\def\etocclasstocstyle{\etocarticlestyle} +\newcommand*\etocmarkboth[1]{% + \@mkboth{\MakeUppercase{#1}}{\MakeUppercase{#1}}} +\newcommand*\etocmarkbothnouc[1]{\@mkboth{#1}{#1}} +\newcommand\etoctocstyle[3][section]{\etocmulticolstyle[#2]% + {\csname #1\endcsname *{#3}}} +\newcommand\etoctocstylewithmarks[4][section]{\etocmulticolstyle[#2]% + {\csname #1\endcsname *{#3\etocmarkboth{#4}}}} +\newcommand\etoctocstylewithmarksnouc[4][section]{\etocmulticolstyle[#2]% + {\csname #1\endcsname *{#3\etocmarkbothnouc{#4}}}} +\def\Etoc@redefetocstylesforchapters{% + \renewcommand\etoctocstylewithmarks[4][chapter]{% + \etocmulticolstyle[##2]{\csname ##1\endcsname *{##3\etocmarkboth{##4}}}% + } + \renewcommand\etoctocstylewithmarksnouc[4][chapter]{% + \etocmulticolstyle[##2]{\csname ##1\endcsname *{##3\etocmarkbothnouc{##4}}}% + } + \renewcommand\etoctocstyle[3][chapter]{% + \etocmulticolstyle[##2]{\csname ##1\endcsname *{##3}} + } +} +\@ifclassloaded{scrartcl} + {\renewcommand*\etocclasstocstyle{\etocscrartclstyle}}{} +\@ifclassloaded{book} + {\renewcommand*\etocfontone{\normalfont\normalsize} + \renewcommand*\etocclasstocstyle{\etocbookstyle} + \Etoc@redefetocstylesforchapters}{} +\@ifclassloaded{report} + {\renewcommand*\etocfontone{\normalfont\normalsize} + \renewcommand*\etocclasstocstyle{\etocreportstyle} + \Etoc@redefetocstylesforchapters}{} +\@ifclassloaded{scrbook} + {\renewcommand*\etocfontone{\normalfont\normalsize} + \renewcommand*\etocclasstocstyle{\etocscrbookstyle} + \Etoc@redefetocstylesforchapters}{} +\@ifclassloaded{scrreprt} + {\renewcommand*\etocfontone{\normalfont\normalsize} + \renewcommand*\etocclasstocstyle{\etocscrreprtstyle} + \Etoc@redefetocstylesforchapters}{} +\@ifclassloaded{memoir} + {\renewcommand*\etocfontone{\normalfont\normalsize} + \renewcommand*\etocclasstocstyle{\etocmemoirstyle} + \Etoc@redefetocstylesforchapters}{} +\def\etoctocloftstyle {% + \etocsettocstyle{% + \@cfttocstart + \par + \begingroup + \parindent\z@ \parskip\cftparskip + \@nameuse{@cftmake\Etoc@currext title}% + \ifEtoc@localtoc + \etoctocloftlocalperhapsaddtotoc\Etoc@currext + \else + \etocifisstarred {}{\ifEtoc@maintoctotoc\@cftdobibtoc\fi}% + \fi + }% + {% + \endgroup + \@cfttocfinish + }% +} +\def\etoctocloftlocalperhapsaddtotoc#1{% + \etocifisstarred + {}% + {\csname ifEtoc@local#1totoc\endcsname + \ifdefined\c@chapter\def\@tocextra{@section}\else\def\@tocextra{@subsection}\fi + \csname @cftdobib#1\endcsname + \fi + }% +} +\def\etoctocbibindstyle {% + \etocsettocstyle {% + \toc@start + \ifEtoc@localtoc + \@nameuse{etocclasslocal\Etoc@currext maketitle}% + \etocclasslocalperhapsaddtotoc\Etoc@currext + \else + \etoc@tocbibind@dotoctitle + \fi + }% + {\toc@finish}% +} +\def\etoc@tocbibind@dotoctitle {% + \if@bibchapter + \etocifisstarred + {\chapter*{\contentsname}\prw@mkboth{\contentsname} % id. + }% + {\ifEtoc@maintoctotoc + \toc@chapter{\contentsname} %<-space from original + \else + \chapter*{\contentsname}\prw@mkboth{\contentsname} % id. + \fi + }% + \else + \etocifisstarred + {\@nameuse{\@tocextra}*{\contentsname\prw@mkboth{\contentsname}} %<-space + } + {\ifEtoc@maintoctotoc + \toc@section{\@tocextra}{\contentsname} %<-space from original + \else + \@nameuse{\@tocextra}*{\contentsname\prw@mkboth{\contentsname}} % id. + \fi + }% + \fi +}% +\@ifclassloaded{memoir} +{} +{% memoir not loaded + \@ifpackageloaded{tocloft} + {\if@cftnctoc\else + \ifEtoc@keeporiginaltoc + \else + \let\tableofcontents\etoctableofcontents + \fi + \fi } + {\AtBeginDocument + {\@ifpackageloaded{tocloft} + {\if@cftnctoc\else + \PackageWarningNoLine {etoc} + {Package `tocloft' was loaded after `etoc'.\MessageBreak + To prevent it from overwriting \protect\tableofcontents, it will\MessageBreak + be tricked into believing to have been loaded with its\MessageBreak + option `titles'. \space But this will cause the `tocloft'\MessageBreak + customization of the titles of the main list of figures\MessageBreak + and list of tables to not apply either.\MessageBreak + You should load `tocloft' before `etoc'.}% + \AtEndDocument{\PackageWarning{etoc} + {Please load `tocloft' before `etoc'!\@gobbletwo}}% + \fi + \@cftnctoctrue }% + {}% + }% + }% +} +\@ifclassloaded{memoir} +{} +{% memoir not loaded + \AtBeginDocument{% + \@ifpackageloaded{tocloft} + {% + \def\etocclasstocstyle{% + \etoctocloftstyle + \Etoc@classstyletrue + }% + \ifEtoc@etocstyle + \ifEtoc@classstyle + \etocclasstocstyle + \Etoc@etocstyletrue + \fi + \else + \ifEtoc@classstyle + \etocclasstocstyle + \fi + \fi + }% + {% no tocloft + \@ifpackageloaded {tocbibind} + {\if@dotoctoc + \def\etocclasstocstyle{% + \etoctocbibindstyle + \Etoc@classstyletrue + }% + \ifEtoc@etocstyle + \ifEtoc@classstyle + \etocclasstocstyle + \Etoc@etocstyletrue + \fi + \else + \ifEtoc@classstyle + \etocclasstocstyle + \fi + \fi + \ifEtoc@keeporiginaltoc + \else + \let\tableofcontents\etoctableofcontents + \fi + }% + {}% + }% + \@ifpackageloaded{tocbibind} + {% tocbibind, perhaps with tocloft + \if@dotoctoc + \ifEtoc@keeporiginaltoc + \else + \let\tableofcontents\etoctableofcontents + \fi + \etocsetup{maintoctotoc,localtoctotoc}% + \PackageInfo{etoc}{% + Setting (or re-setting) the options `maintoctotoc' and\MessageBreak + `localtoctotoc' to true as tocbibind was detected and\MessageBreak + found to be configured for `TOC to toc'.\MessageBreak + Reported at begin document}% + \fi + \if@dotoclof + \ifEtoc@lof + \etocsetup{localloftotoc}% + \PackageInfo{etoc}{% + Setting (or re-setting) `localloftotoc=true' as the\MessageBreak + package tocbibind was detected and is configured for\MessageBreak + `LOF to toc'. Reported at begin document}% + \fi + \fi + \if@dotoclot + \ifEtoc@lot + \etocsetup{locallottotoc}% + \PackageInfo{etoc}{% + Setting (or re-setting) `locallottotoc=true' as the\MessageBreak + package tocbibind was detected and is configured for\MessageBreak + `LOT to toc'. Reported at begin document}% + \fi + \fi + }% end of tocbibind branch + {}% + }% end of at begin document +}% end of not with memoir branch +\def\Etoc@addtocontents #1#2{% + \addtocontents {toc}{% + \protect\contentsline{#1}{#2}{\thepage}{\ifEtoc@hyperref\@currentHref\fi}% + \ifdefined\protected@file@percent\protected@file@percent\fi + }% +} +\def\Etoc@addcontentsline@ #1#2#3{% + \@namedef{toclevel@#1}{#3}\addcontentsline {toc}{#1}{#2}% +} +\DeclareRobustCommand*{\etoctoccontentsline} + {\@ifstar{\Etoc@addcontentsline@}{\Etoc@addtocontents}} +\def\Etoc@addtocontents@immediately#1#2{% + \begingroup + \let\Etoc@originalwrite\write + \def\write{\immediate\Etoc@originalwrite}% + \Etoc@addtocontents{#1}{#2}% + \endgroup +} +\def\Etoc@addcontentsline@@immediately#1#2#3{% + \begingroup + \let\Etoc@originalwrite\write + \def\write{\immediate\Etoc@originalwrite}% + \Etoc@addcontentsline@{#1}{#2}{#3}% + \endgoroup +} +\DeclareRobustCommand*{\etocimmediatetoccontentsline} + {\@ifstar{\Etoc@addcontentsline@@immediately}{\Etoc@addtocontents@immediately}} +\def\Etoc@storetocdepth {\xdef\Etoc@savedtocdepth{\number\c@tocdepth}} +\def\Etoc@restoretocdepth {\global\c@tocdepth\Etoc@savedtocdepth\relax} +\def\etocobeytoctocdepth {\def\etoc@settocdepth + {\afterassignment\Etoc@@nottoodeep \global\c@tocdepth}} +\def\Etoc@@nottoodeep {\ifnum\Etoc@savedtocdepth<\c@tocdepth + \global\c@tocdepth\Etoc@savedtocdepth\relax\fi } +\def\etocignoretoctocdepth {\let\etoc@settocdepth\@gobble } +\def\etocsettocdepth {\futurelet\Etoc@nexttoken\Etoc@set@tocdepth } +\def\Etoc@set@tocdepth {\ifx\Etoc@nexttoken\bgroup + \expandafter\Etoc@set@tocdepth@ + \else\expandafter\Etoc@set@toctocdepth + \fi } +\def\Etoc@set@tocdepth@ #1{\@ifundefined {Etoc@#1@@} + {\PackageWarning{etoc} + {Unknown sectioning unit #1, \protect\etocsettocdepth\space ignored}} + {\global\c@tocdepth\csname Etoc@#1@@\endcsname}% +} +\def\Etoc@set@toctocdepth #1#{\Etoc@set@toctocdepth@ } +\def\Etoc@set@toctocdepth@ #1{% + \@ifundefined{Etoc@#1@@}% + {\PackageWarning{etoc} + {Unknown sectioning depth #1, \protect\etocsettocdepth.toc ignored}}% + {\addtocontents {toc} + {\protect\etoc@settocdepth\expandafter\protect\csname Etoc@#1@@\endcsname}}% +} +\def\etocimmediatesettocdepth #1#{\Etoc@set@toctocdepth@immediately} +\def\Etoc@set@toctocdepth@immediately #1{% + \@ifundefined{Etoc@#1@@}% + {\PackageWarning{etoc} + {Unknown sectioning depth #1, \protect\etocimmediatesettocdepth.toc ignored}}% + {\begingroup + \let\Etoc@originalwrite\write + \def\write{\immediate\Etoc@originalwrite}% + \addtocontents {toc} + {\protect\etoc@settocdepth\expandafter\protect + \csname Etoc@#1@@\endcsname}% + \endgroup + }% +} +\def\etocdepthtag #1#{\Etoc@depthtag } +\def\Etoc@depthtag #1{\addtocontents {toc}{\protect\etoc@depthtag {#1}}} +\def\etocimmediatedepthtag #1#{\Etoc@depthtag@immediately } +\def\Etoc@depthtag@immediately #1{% + \begingroup + \let\Etoc@originalwrite\write + \def\write{\immediate\Etoc@originalwrite}% + \addtocontents {toc}{\protect\etoc@depthtag {#1}}% + \endgroup +} +\def\etocignoredepthtags {\let\etoc@depthtag \@gobble } +\def\etocobeydepthtags {\let\etoc@depthtag \Etoc@depthtag@ } +\def\Etoc@depthtag@ #1{\@ifundefined{Etoc@depthof@#1}% + {}% ignore in silence if tag has no associated depth + {\afterassignment\Etoc@@nottoodeep + \global\c@tocdepth\csname Etoc@depthof@#1\endcsname}% +} +\def\etocsettagdepth #1#2{\@ifundefined{Etoc@#2@@}% + {\PackageWarning{etoc} + {Unknown sectioning depth #2, \protect\etocsettagdepth\space ignored}}% + {\@namedef{Etoc@depthof@#1}{\@nameuse{Etoc@#2@@}}}% +} +\def\Etoc@tocvsec@err #1{\PackageError {etoc} + {The command \protect#1\space is incompatible with `etoc'} + {Use \protect\etocsettocdepth.toc as replacement}% +}% +\AtBeginDocument {% + \@ifclassloaded{memoir} + {\PackageInfo {etoc} + {Regarding `memoir' class command \protect\settocdepth, consider\MessageBreak + \protect\etocsettocdepth.toc as a drop-in replacement with more\MessageBreak + capabilities (see `etoc' manual). \space + Also, \protect\etocsettocdepth\MessageBreak + and \protect\etocsetnexttocdepth\space should be used in place of\MessageBreak + `memoir' command \protect\maxtocdepth\@gobble}% + }% + {\@ifpackageloaded {tocvsec2}{% + \def\maxtocdepth #1{\Etoc@tocvsec@err \maxtocdepth }% + \def\settocdepth #1{\Etoc@tocvsec@err \settocdepth }% + \def\resettocdepth {\@ifstar {\Etoc@tocvsec@err \resettocdepth }% + {\Etoc@tocvsec@err \resettocdepth }% + }% + \def\save@tocdepth #1#2#3{}% + \let\reset@tocdepth\relax + \let\remax@tocdepth\relax + \let\tableofcontents\etoctableofcontents + \PackageWarningNoLine {etoc} + {Package `tocvsec2' detected and its modification of\MessageBreak + \protect\tableofcontents\space reverted. \space Use + \protect\etocsettocdepth.toc\MessageBreak as a replacement + for `tocvsec2' toc-related commands}% + }% tocvsec2 loaded + {}% tocvsec2 not loaded + }% +}% +\def\invisibletableofcontents {\etocsetnexttocdepth {-3}\tableofcontents }% +\def\invisiblelocaltableofcontents + {\etocsetnexttocdepth {-3}\localtableofcontents }% +\def\etocsetnexttocdepth #1{% + \@ifundefined{Etoc@#1@@} + {\PackageWarning{etoc} + {Unknown sectioning unit #1, \protect\etocsetnextocdepth\space ignored}} + {\Etoc@setnexttocdepth{\csname Etoc@#1@@\endcsname}}% +}% +\def\Etoc@setnexttocdepth#1{% + \def\Etoc@tocdepthset{% + \Etoc@tocdepthreset + \edef\Etoc@tocdepthreset {% + \global\c@tocdepth\the\c@tocdepth\space + \global\let\noexpand\Etoc@tocdepthreset\noexpand\@empty + }% + \global\c@tocdepth#1% + \global\let\Etoc@tocdepthset\@empty + }% +}% +\let\Etoc@tocdepthreset\@empty +\let\Etoc@tocdepthset \@empty +\def\etocsetlocaltop #1#{\Etoc@set@localtop}% +\def\Etoc@set@localtop #1{% + \@ifundefined{Etoc@#1@@}% + {\PackageWarning{etoc} + {Unknown sectioning depth #1, \protect\etocsetlocaltop.toc ignored}}% + {\addtocontents {toc} + {\protect\etoc@setlocaltop\expandafter\protect\csname Etoc@#1@@\endcsname}}% +}% +\def\etocimmediatesetlocaltop #1#{\Etoc@set@localtop@immediately}% +\def\Etoc@set@localtop@immediately #1{% + \@ifundefined{Etoc@#1@@}% + {\PackageWarning{etoc} + {Unknown sectioning depth #1, \protect\etocimmediatesetlocaltop.toc ignored}}% + {\begingroup + \let\Etoc@originalwrite\write + \def\write{\immediate\Etoc@originalwrite}% + \addtocontents {toc} + {\protect\etoc@setlocaltop\expandafter\protect + \csname Etoc@#1@@\endcsname}% + \endgroup + }% +}% +\def\etoc@setlocaltop #1{% + \ifnum#1=\Etoc@maxlevel + \Etoc@skipthisonetrue + \else + \Etoc@skipthisonefalse + \global\let\Etoc@level #1% + \global\let\Etoc@virtualtop #1% + \ifEtoc@localtoc + \ifEtoc@stoptoc + \Etoc@skipthisonetrue + \else + \ifEtoc@notactive + \Etoc@skipthisonetrue + \else + \unless\ifnum\Etoc@level>\etoclocaltop + \Etoc@skipthisonetrue + \global\Etoc@stoptoctrue + \fi + \fi + \fi + \fi + \fi + \let\Etoc@next\@empty + \ifEtoc@skipthisone + \else + \ifnum\Etoc@level>\c@tocdepth + \else + \ifEtoc@standardlines + \else + \let\Etoc@next\Etoc@setlocaltop@doendsandbegin + \fi + \fi + \fi + \Etoc@next +}% +\def\Etoc@setlocaltop@doendsandbegin{% + \Etoc@doendsandbegin + \global\Etoc@skipprefixfalse +} +\addtocontents {toc}{\protect\@ifundefined{etoctocstyle}% + {\let\protect\etoc@startlocaltoc\protect\@gobble + \let\protect\etoc@settocdepth\protect\@gobble + \let\protect\etoc@depthtag\protect\@gobble + \let\protect\etoc@setlocaltop\protect\@gobble}{}}% +\def\etocstandardlines {\Etoc@standardlinestrue} +\def\etoctoclines {\Etoc@standardlinesfalse} +\etocdefaultlines +\etocstandardlines +\def\etocstandarddisplaystyle{% + \PackageWarningNoLine{etoc}{% + \string\etocstandarddisplaystyle \on@line\MessageBreak + is deprecated. \space Please use \string\etocclasstocstyle}% +} +\expandafter\def\expandafter\etocclasstocstyle\expandafter{% + \etocclasstocstyle + \Etoc@classstyletrue +} +\def\etocetoclocaltocstyle{\Etoc@etocstyletrue} +\def\etocusertocstyle{\Etoc@etocstylefalse} +\etocclasstocstyle +\etocetoclocaltocstyle +\etocobeytoctocdepth +\etocobeydepthtags +\let\etocbeforetitlehook \@empty +\let\etocaftertitlehook \@empty +\let\etocaftercontentshook \@empty +\let\etocaftertochook \@empty +\def\etockeeporiginaltableofcontents + {\Etoc@keeporiginaltoctrue\let\tableofcontents\etocoriginaltableofcontents}% +\endinput +%% +%% End of file `etoc.sty'. + diff --git a/documentation/latex/files.tex b/documentation/latex/files.tex new file mode 100644 index 0000000..f86b117 --- /dev/null +++ b/documentation/latex/files.tex @@ -0,0 +1,4 @@ +\doxysection{File List} +Here is a list of all documented files with brief descriptions\+:\begin{DoxyCompactList} +\item\contentsline{section}{D\+:/development/git/esp32\+\_\+\+BNO08x/\textbf{ BNO08x.\+hpp} }{\pageref{_b_n_o08x_8hpp_source}}{} +\end{DoxyCompactList} diff --git a/documentation/latex/longtable_doxygen.sty b/documentation/latex/longtable_doxygen.sty new file mode 100644 index 0000000..e94b78b --- /dev/null +++ b/documentation/latex/longtable_doxygen.sty @@ -0,0 +1,456 @@ +%% +%% This is file `longtable.sty', +%% generated with the docstrip utility. +%% +%% The original source files were: +%% +%% longtable.dtx (with options: `package') +%% +%% This is a generated file. +%% +%% The source is maintained by the LaTeX Project team and bug +%% reports for it can be opened at http://latex-project.org/bugs.html +%% (but please observe conditions on bug reports sent to that address!) +%% +%% Copyright 1993-2016 +%% The LaTeX3 Project and any individual authors listed elsewhere +%% in this file. +%% +%% This file was generated from file(s) of the Standard LaTeX `Tools Bundle'. +%% -------------------------------------------------------------------------- +%% +%% It may be distributed and/or modified under the +%% conditions of the LaTeX Project Public License, either version 1.3c +%% of this license or (at your option) any later version. +%% The latest version of this license is in +%% http://www.latex-project.org/lppl.txt +%% and version 1.3c or later is part of all distributions of LaTeX +%% version 2005/12/01 or later. +%% +%% This file may only be distributed together with a copy of the LaTeX +%% `Tools Bundle'. You may however distribute the LaTeX `Tools Bundle' +%% without such generated files. +%% +%% The list of all files belonging to the LaTeX `Tools Bundle' is +%% given in the file `manifest.txt'. +%% +%% File: longtable.dtx Copyright (C) 1990-2001 David Carlisle +\NeedsTeXFormat{LaTeX2e}[1995/06/01] +\ProvidesPackage{longtable_doxygen} + [2014/10/28 v4.11 Multi-page Table package (DPC) - frozen version for doxygen] +\def\LT@err{\PackageError{longtable}} +\def\LT@warn{\PackageWarning{longtable}} +\def\LT@final@warn{% + \AtEndDocument{% + \LT@warn{Table \@width s have changed. Rerun LaTeX.\@gobbletwo}}% + \global\let\LT@final@warn\relax} +\DeclareOption{errorshow}{% + \def\LT@warn{\PackageInfo{longtable}}} +\DeclareOption{pausing}{% + \def\LT@warn#1{% + \LT@err{#1}{This is not really an error}}} +\DeclareOption{set}{} +\DeclareOption{final}{} +\ProcessOptions +\newskip\LTleft \LTleft=\fill +\newskip\LTright \LTright=\fill +\newskip\LTpre \LTpre=\bigskipamount +\newskip\LTpost \LTpost=\bigskipamount +\newcount\LTchunksize \LTchunksize=20 +\let\c@LTchunksize\LTchunksize +\newdimen\LTcapwidth \LTcapwidth=4in +\newbox\LT@head +\newbox\LT@firsthead +\newbox\LT@foot +\newbox\LT@lastfoot +\newcount\LT@cols +\newcount\LT@rows +\newcounter{LT@tables} +\newcounter{LT@chunks}[LT@tables] +\ifx\c@table\undefined + \newcounter{table} + \def\fnum@table{\tablename~\thetable} +\fi +\ifx\tablename\undefined + \def\tablename{Table} +\fi +\newtoks\LT@p@ftn +\mathchardef\LT@end@pen=30000 +\def\longtable{% + \par + \ifx\multicols\@undefined + \else + \ifnum\col@number>\@ne + \@twocolumntrue + \fi + \fi + \if@twocolumn + \LT@err{longtable not in 1-column mode}\@ehc + \fi + \begingroup + \@ifnextchar[\LT@array{\LT@array[x]}} +\def\LT@array[#1]#2{% + \refstepcounter{table}\stepcounter{LT@tables}% + \if l#1% + \LTleft\z@ \LTright\fill + \else\if r#1% + \LTleft\fill \LTright\z@ + \else\if c#1% + \LTleft\fill \LTright\fill + \fi\fi\fi + \let\LT@mcol\multicolumn + \let\LT@@tabarray\@tabarray + \let\LT@@hl\hline + \def\@tabarray{% + \let\hline\LT@@hl + \LT@@tabarray}% + \let\\\LT@tabularcr\let\tabularnewline\\% + \def\newpage{\noalign{\break}}% + \def\pagebreak{\noalign{\ifnum`}=0\fi\@testopt{\LT@no@pgbk-}4}% + \def\nopagebreak{\noalign{\ifnum`}=0\fi\@testopt\LT@no@pgbk4}% + \let\hline\LT@hline \let\kill\LT@kill\let\caption\LT@caption + \@tempdima\ht\strutbox + \let\@endpbox\LT@endpbox + \ifx\extrarowheight\@undefined + \let\@acol\@tabacol + \let\@classz\@tabclassz \let\@classiv\@tabclassiv + \def\@startpbox{\vtop\LT@startpbox}% + \let\@@startpbox\@startpbox + \let\@@endpbox\@endpbox + \let\LT@LL@FM@cr\@tabularcr + \else + \advance\@tempdima\extrarowheight + \col@sep\tabcolsep + \let\@startpbox\LT@startpbox\let\LT@LL@FM@cr\@arraycr + \fi + \setbox\@arstrutbox\hbox{\vrule + \@height \arraystretch \@tempdima + \@depth \arraystretch \dp \strutbox + \@width \z@}% + \let\@sharp##\let\protect\relax + \begingroup + \@mkpream{#2}% + \xdef\LT@bchunk{% + \global\advance\c@LT@chunks\@ne + \global\LT@rows\z@\setbox\z@\vbox\bgroup + \LT@setprevdepth + \tabskip\LTleft \noexpand\halign to\hsize\bgroup + \tabskip\z@ \@arstrut \@preamble \tabskip\LTright \cr}% + \endgroup + \expandafter\LT@nofcols\LT@bchunk&\LT@nofcols + \LT@make@row + \m@th\let\par\@empty + \everycr{}\lineskip\z@\baselineskip\z@ + \LT@bchunk} +\def\LT@no@pgbk#1[#2]{\penalty #1\@getpen{#2}\ifnum`{=0\fi}} +\def\LT@start{% + \let\LT@start\endgraf + \endgraf\penalty\z@\vskip\LTpre + \dimen@\pagetotal + \advance\dimen@ \ht\ifvoid\LT@firsthead\LT@head\else\LT@firsthead\fi + \advance\dimen@ \dp\ifvoid\LT@firsthead\LT@head\else\LT@firsthead\fi + \advance\dimen@ \ht\LT@foot + \dimen@ii\vfuzz + \vfuzz\maxdimen + \setbox\tw@\copy\z@ + \setbox\tw@\vsplit\tw@ to \ht\@arstrutbox + \setbox\tw@\vbox{\unvbox\tw@}% + \vfuzz\dimen@ii + \advance\dimen@ \ht + \ifdim\ht\@arstrutbox>\ht\tw@\@arstrutbox\else\tw@\fi + \advance\dimen@\dp + \ifdim\dp\@arstrutbox>\dp\tw@\@arstrutbox\else\tw@\fi + \advance\dimen@ -\pagegoal + \ifdim \dimen@>\z@\vfil\break\fi + \global\@colroom\@colht + \ifvoid\LT@foot\else + \advance\vsize-\ht\LT@foot + \global\advance\@colroom-\ht\LT@foot + \dimen@\pagegoal\advance\dimen@-\ht\LT@foot\pagegoal\dimen@ + \maxdepth\z@ + \fi + \ifvoid\LT@firsthead\copy\LT@head\else\box\LT@firsthead\fi\nobreak + \output{\LT@output}} +\def\endlongtable{% + \crcr + \noalign{% + \let\LT@entry\LT@entry@chop + \xdef\LT@save@row{\LT@save@row}}% + \LT@echunk + \LT@start + \unvbox\z@ + \LT@get@widths + \if@filesw + {\let\LT@entry\LT@entry@write\immediate\write\@auxout{% + \gdef\expandafter\noexpand + \csname LT@\romannumeral\c@LT@tables\endcsname + {\LT@save@row}}}% + \fi + \ifx\LT@save@row\LT@@save@row + \else + \LT@warn{Column \@width s have changed\MessageBreak + in table \thetable}% + \LT@final@warn + \fi + \endgraf\penalty -\LT@end@pen + \endgroup + \global\@mparbottom\z@ + \pagegoal\vsize + \endgraf\penalty\z@\addvspace\LTpost + \ifvoid\footins\else\insert\footins{}\fi} +\def\LT@nofcols#1&{% + \futurelet\@let@token\LT@n@fcols} +\def\LT@n@fcols{% + \advance\LT@cols\@ne + \ifx\@let@token\LT@nofcols + \expandafter\@gobble + \else + \expandafter\LT@nofcols + \fi} +\def\LT@tabularcr{% + \relax\iffalse{\fi\ifnum0=`}\fi + \@ifstar + {\def\crcr{\LT@crcr\noalign{\nobreak}}\let\cr\crcr + \LT@t@bularcr}% + {\LT@t@bularcr}} +\let\LT@crcr\crcr +\let\LT@setprevdepth\relax +\def\LT@t@bularcr{% + \global\advance\LT@rows\@ne + \ifnum\LT@rows=\LTchunksize + \gdef\LT@setprevdepth{% + \prevdepth\z@\global + \global\let\LT@setprevdepth\relax}% + \expandafter\LT@xtabularcr + \else + \ifnum0=`{}\fi + \expandafter\LT@LL@FM@cr + \fi} +\def\LT@xtabularcr{% + \@ifnextchar[\LT@argtabularcr\LT@ntabularcr} +\def\LT@ntabularcr{% + \ifnum0=`{}\fi + \LT@echunk + \LT@start + \unvbox\z@ + \LT@get@widths + \LT@bchunk} +\def\LT@argtabularcr[#1]{% + \ifnum0=`{}\fi + \ifdim #1>\z@ + \unskip\@xargarraycr{#1}% + \else + \@yargarraycr{#1}% + \fi + \LT@echunk + \LT@start + \unvbox\z@ + \LT@get@widths + \LT@bchunk} +\def\LT@echunk{% + \crcr\LT@save@row\cr\egroup + \global\setbox\@ne\lastbox + \unskip + \egroup} +\def\LT@entry#1#2{% + \ifhmode\@firstofone{&}\fi\omit + \ifnum#1=\c@LT@chunks + \else + \kern#2\relax + \fi} +\def\LT@entry@chop#1#2{% + \noexpand\LT@entry + {\ifnum#1>\c@LT@chunks + 1}{0pt% + \else + #1}{#2% + \fi}} +\def\LT@entry@write{% + \noexpand\LT@entry^^J% + \@spaces} +\def\LT@kill{% + \LT@echunk + \LT@get@widths + \expandafter\LT@rebox\LT@bchunk} +\def\LT@rebox#1\bgroup{% + #1\bgroup + \unvbox\z@ + \unskip + \setbox\z@\lastbox} +\def\LT@blank@row{% + \xdef\LT@save@row{\expandafter\LT@build@blank + \romannumeral\number\LT@cols 001 }} +\def\LT@build@blank#1{% + \if#1m% + \noexpand\LT@entry{1}{0pt}% + \expandafter\LT@build@blank + \fi} +\def\LT@make@row{% + \global\expandafter\let\expandafter\LT@save@row + \csname LT@\romannumeral\c@LT@tables\endcsname + \ifx\LT@save@row\relax + \LT@blank@row + \else + {\let\LT@entry\or + \if!% + \ifcase\expandafter\expandafter\expandafter\LT@cols + \expandafter\@gobble\LT@save@row + \or + \else + \relax + \fi + !% + \else + \aftergroup\LT@blank@row + \fi}% + \fi} +\let\setlongtables\relax +\def\LT@get@widths{% + \setbox\tw@\hbox{% + \unhbox\@ne + \let\LT@old@row\LT@save@row + \global\let\LT@save@row\@empty + \count@\LT@cols + \loop + \unskip + \setbox\tw@\lastbox + \ifhbox\tw@ + \LT@def@row + \advance\count@\m@ne + \repeat}% + \ifx\LT@@save@row\@undefined + \let\LT@@save@row\LT@save@row + \fi} +\def\LT@def@row{% + \let\LT@entry\or + \edef\@tempa{% + \ifcase\expandafter\count@\LT@old@row + \else + {1}{0pt}% + \fi}% + \let\LT@entry\relax + \xdef\LT@save@row{% + \LT@entry + \expandafter\LT@max@sel\@tempa + \LT@save@row}} +\def\LT@max@sel#1#2{% + {\ifdim#2=\wd\tw@ + #1% + \else + \number\c@LT@chunks + \fi}% + {\the\wd\tw@}} +\def\LT@hline{% + \noalign{\ifnum0=`}\fi + \penalty\@M + \futurelet\@let@token\LT@@hline} +\def\LT@@hline{% + \ifx\@let@token\hline + \global\let\@gtempa\@gobble + \gdef\LT@sep{\penalty-\@medpenalty\vskip\doublerulesep}% + \else + \global\let\@gtempa\@empty + \gdef\LT@sep{\penalty-\@lowpenalty\vskip-\arrayrulewidth}% + \fi + \ifnum0=`{\fi}% + \multispan\LT@cols + \unskip\leaders\hrule\@height\arrayrulewidth\hfill\cr + \noalign{\LT@sep}% + \multispan\LT@cols + \unskip\leaders\hrule\@height\arrayrulewidth\hfill\cr + \noalign{\penalty\@M}% + \@gtempa} +\def\LT@caption{% + \noalign\bgroup + \@ifnextchar[{\egroup\LT@c@ption\@firstofone}\LT@capti@n} +\def\LT@c@ption#1[#2]#3{% + \LT@makecaption#1\fnum@table{#3}% + \def\@tempa{#2}% + \ifx\@tempa\@empty\else + {\let\\\space + \addcontentsline{lot}{table}{\protect\numberline{\thetable}{#2}}}% + \fi} +\def\LT@capti@n{% + \@ifstar + {\egroup\LT@c@ption\@gobble[]}% + {\egroup\@xdblarg{\LT@c@ption\@firstofone}}} +\def\LT@makecaption#1#2#3{% + \LT@mcol\LT@cols c{\hbox to\z@{\hss\parbox[t]\LTcapwidth{% + \sbox\@tempboxa{#1{#2: }#3}% + \ifdim\wd\@tempboxa>\hsize + #1{#2: }#3% + \else + \hbox to\hsize{\hfil\box\@tempboxa\hfil}% + \fi + \endgraf\vskip\baselineskip}% + \hss}}} +\def\LT@output{% + \ifnum\outputpenalty <-\@Mi + \ifnum\outputpenalty > -\LT@end@pen + \LT@err{floats and marginpars not allowed in a longtable}\@ehc + \else + \setbox\z@\vbox{\unvbox\@cclv}% + \ifdim \ht\LT@lastfoot>\ht\LT@foot + \dimen@\pagegoal + \advance\dimen@-\ht\LT@lastfoot + \ifdim\dimen@<\ht\z@ + \setbox\@cclv\vbox{\unvbox\z@\copy\LT@foot\vss}% + \@makecol + \@outputpage + \setbox\z@\vbox{\box\LT@head}% + \fi + \fi + \global\@colroom\@colht + \global\vsize\@colht + \vbox + {\unvbox\z@\box\ifvoid\LT@lastfoot\LT@foot\else\LT@lastfoot\fi}% + \fi + \else + \setbox\@cclv\vbox{\unvbox\@cclv\copy\LT@foot\vss}% + \@makecol + \@outputpage + \global\vsize\@colroom + \copy\LT@head\nobreak + \fi} +\def\LT@end@hd@ft#1{% + \LT@echunk + \ifx\LT@start\endgraf + \LT@err + {Longtable head or foot not at start of table}% + {Increase LTchunksize}% + \fi + \setbox#1\box\z@ + \LT@get@widths + \LT@bchunk} +\def\endfirsthead{\LT@end@hd@ft\LT@firsthead} +\def\endhead{\LT@end@hd@ft\LT@head} +\def\endfoot{\LT@end@hd@ft\LT@foot} +\def\endlastfoot{\LT@end@hd@ft\LT@lastfoot} +\def\LT@startpbox#1{% + \bgroup + \let\@footnotetext\LT@p@ftntext + \setlength\hsize{#1}% + \@arrayparboxrestore + \vrule \@height \ht\@arstrutbox \@width \z@} +\def\LT@endpbox{% + \@finalstrut\@arstrutbox + \egroup + \the\LT@p@ftn + \global\LT@p@ftn{}% + \hfil} +%% added \long to prevent: +% LaTeX Warning: Command \LT@p@ftntext has changed. +% +% from the original repository (https://github.com/latex3/latex2e/blob/develop/required/tools/longtable.dtx): +% \changes{v4.15}{2021/03/28} +% {make long for gh/364} +% Inside the `p' column, just save up the footnote text in a token +% register. +\long\def\LT@p@ftntext#1{% + \edef\@tempa{\the\LT@p@ftn\noexpand\footnotetext[\the\c@footnote]}% + \global\LT@p@ftn\expandafter{\@tempa{#1}}}% + +\@namedef{ver@longtable.sty}{2014/10/28 v4.11 Multi-page Table package (DPC) - frozen version for doxygen} +\endinput +%% +%% End of file `longtable.sty'. diff --git a/documentation/latex/make.bat b/documentation/latex/make.bat new file mode 100644 index 0000000..96da1c8 --- /dev/null +++ b/documentation/latex/make.bat @@ -0,0 +1,56 @@ +pushd %~dp0 +if not %errorlevel% == 0 goto :end + +set ORG_LATEX_CMD=%LATEX_CMD% +set ORG_MKIDX_CMD=%MKIDX_CMD% +set ORG_BIBTEX_CMD=%BIBTEX_CMD% +set ORG_LATEX_COUNT=%LATEX_COUNT% +set ORG_MANUAL_FILE=%MANUAL_FILE% +if "X"%LATEX_CMD% == "X" set LATEX_CMD=pdflatex +if "X"%MKIDX_CMD% == "X" set MKIDX_CMD=makeindex +if "X"%BIBTEX_CMD% == "X" set BIBTEX_CMD=bibtex +if "X"%LATEX_COUNT% == "X" set LATEX_COUNT=8 +if "X"%MANUAL_FILE% == "X" set MANUAL_FILE=refman + +del /s /f *.ps *.dvi *.aux *.toc *.idx *.ind *.ilg *.log *.out *.brf *.blg *.bbl %MANUAL_FILE%.pdf + + +%LATEX_CMD% %MANUAL_FILE% +echo ---- +%MKIDX_CMD% %MANUAL_FILE%.idx +echo ---- +%LATEX_CMD% %MANUAL_FILE% + +setlocal enabledelayedexpansion +set count=%LATEX_COUNT% +:repeat +set content=X +for /F "tokens=*" %%T in ( 'findstr /C:"Rerun LaTeX" %MANUAL_FILE%.log' ) do set content="%%~T" +if !content! == X for /F "tokens=*" %%T in ( 'findstr /C:"Rerun to get cross-references right" %MANUAL_FILE%.log' ) do set content="%%~T" +if !content! == X for /F "tokens=*" %%T in ( 'findstr /C:"Rerun to get bibliographical references right" %MANUAL_FILE%.log' ) do set content="%%~T" +if !content! == X goto :skip +set /a count-=1 +if !count! EQU 0 goto :skip + +echo ---- +%LATEX_CMD% %MANUAL_FILE% +goto :repeat +:skip +endlocal +%MKIDX_CMD% %MANUAL_FILE%.idx +%LATEX_CMD% %MANUAL_FILE% + +@REM reset environment +popd +set LATEX_CMD=%ORG_LATEX_CMD% +set ORG_LATEX_CMD= +set MKIDX_CMD=%ORG_MKIDX_CMD% +set ORG_MKIDX_CMD= +set BIBTEX_CMD=%ORG_BIBTEX_CMD% +set ORG_BIBTEX_CMD= +set MANUAL_FILE=%ORG_MANUAL_FILE% +set ORG_MANUAL_FILE= +set LATEX_COUNT=%ORG_LATEX_COUNT% +set ORG_LATEX_COUNT= + +:end diff --git a/documentation/latex/md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e.tex b/documentation/latex/md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e.tex new file mode 100644 index 0000000..3f45ff4 --- /dev/null +++ b/documentation/latex/md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e.tex @@ -0,0 +1,115 @@ +\chapter{README} +\label{md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e}\index{README@{README}} +Table of Contents. + + + + +\begin{DoxyEnumerate} +\item {\texttt{ About}} +\item {\texttt{ Getting Started}} +\begin{DoxyItemize} +\item {\texttt{ Wiring}} +\item {\texttt{ Adding to Project}} +\end{DoxyItemize} +\item {\texttt{ Example}} +\item {\texttt{ Documentation}} +\item {\texttt{ Acknowledgements}} +\item {\texttt{ License}} +\item {\texttt{ Contact}} +\end{DoxyEnumerate}\doxysubsection{About}\label{md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md0} +esp32\+\_\+\+BNO08x is a C++ component written for esp-\/idf version 5.\+1 to serve as a driver for the BNO085 or BNO080 IMU. ~\newline + This library is heavy influenced by the Spark\+Fun BNO080 Arduino Library, it is more or less a port. It supports access to all the same data that the \doxyref{BNO08x}{p.}{class_b_n_o08x} provides. ~\newline + Currently, only SPI is supported, there is no plans to support I2C (esp32 has I2C driver silicone bug, leading to unpredictable behavior). ~\newline + I may implement UART at some point in the future.\doxysubsection{Getting Started}\label{md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md1} +({\texttt{ back to top}})\doxysubsubsection{Wiring}\label{md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md2} +The default wiring is depicted below, it can be changed at driver initialization (see example section). + +({\texttt{ back to top}})\doxysubsubsection{Adding to Project}\label{md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md3} + +\begin{DoxyEnumerate} +\item Create a \"{}components\"{} directory in the root workspace directory of your esp-\/idf project if it does not exist already. ~\newline + + +In workspace directory\+: ~\newline + +\begin{DoxyCode}{0} +\DoxyCodeLine{mkdir\ components} + +\end{DoxyCode} + +\item Cd into the components directory and clone the esp32\+\_\+\+BNO08x repo. + + +\begin{DoxyCode}{0} +\DoxyCodeLine{cd\ components} +\DoxyCodeLine{git\ clone\ https://github.com/myles-\/parfeniuk/esp32\_BNO08x.git} + +\end{DoxyCode} + + +({\texttt{ back to top}}) +\end{DoxyEnumerate}\doxysubsubsection{Example}\label{md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md4} + +\begin{DoxyCode}{0} +\DoxyCodeLine{\textcolor{preprocessor}{\#include\ }} +\DoxyCodeLine{\textcolor{preprocessor}{\#include\ "{}BNO08x.hpp"{}}} +\DoxyCodeLine{} +\DoxyCodeLine{\textcolor{keyword}{extern}\ \textcolor{stringliteral}{"{}C"{}}\ \textcolor{keywordtype}{void}\ app\_main(\textcolor{keywordtype}{void})} +\DoxyCodeLine{\{} +\DoxyCodeLine{\ \ \ \ BNO08x\ imu;\ \textcolor{comment}{//create\ IMU\ object\ with\ default\ wiring\ scheme}} +\DoxyCodeLine{} +\DoxyCodeLine{\ \ \ \ \textcolor{comment}{/*}} +\DoxyCodeLine{\textcolor{comment}{\ \ \ \ //if\ a\ custom\ wiring\ scheme\ is\ desired:}} +\DoxyCodeLine{\textcolor{comment}{\ \ \ \ //create\ config\ struct}} +\DoxyCodeLine{\textcolor{comment}{\ \ \ \ bno08x\_config\_t\ imu\_config;\ }} +\DoxyCodeLine{\textcolor{comment}{\ \ \ \ imu\_config.io\_mos\ =\ GPIO\_NUM\_X;}} +\DoxyCodeLine{\textcolor{comment}{\ \ \ \ imu\_config.io\_miso\ =\ GPIO\_NUM\_X;}} +\DoxyCodeLine{\textcolor{comment}{\ \ \ \ //etc...}} +\DoxyCodeLine{\textcolor{comment}{}} +\DoxyCodeLine{\textcolor{comment}{\ \ \ \ BNO08x\ imu(imu\_config);}} +\DoxyCodeLine{\textcolor{comment}{\ \ \ \ */}} +\DoxyCodeLine{} +\DoxyCodeLine{\ \ \ \ imu.initialize();\ \ \textcolor{comment}{//initialize\ IMU}} +\DoxyCodeLine{} +\DoxyCodeLine{\ \ \ \ \textcolor{comment}{//enable\ gyro\ \&\ game\ rotation\ vector}} +\DoxyCodeLine{\ \ \ \ imu.enable\_game\_rotation\_vector(100);} +\DoxyCodeLine{\ \ \ \ imu.enable\_gyro(150);} +\DoxyCodeLine{} +\DoxyCodeLine{\ \ \ \ \textcolor{keywordflow}{while}(1)} +\DoxyCodeLine{\ \ \ \ \{} +\DoxyCodeLine{\ \ \ \ \ \ \ \ \textcolor{comment}{//print\ absolute\ heading\ in\ degrees\ and\ angular\ velocity\ in\ Rad/s}} +\DoxyCodeLine{\ \ \ \ \ \ \ \ \textcolor{keywordflow}{if}(imu.data\_available())} +\DoxyCodeLine{\ \ \ \ \ \ \ \ \{} +\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ ESP\_LOGW(\textcolor{stringliteral}{"{}Main"{}},\ \textcolor{stringliteral}{"{}Velocity:\ x:\ \%.3f\ y:\ \%.3f\ z:\ \%.3f"{}},\ imu.get\_gyro\_calibrated\_velocity\_X(),\ imu.get\_gyro\_calibrated\_velocity\_Y(),\ imu.get\_gyro\_calibrated\_velocity\_Z());} +\DoxyCodeLine{\ \ \ \ \ \ \ \ \ \ \ \ ESP\_LOGI(\textcolor{stringliteral}{"{}Main"{}},\ \textcolor{stringliteral}{"{}Euler\ Angle:\ pitch:\ \%.3f\ roll:\ \%.3f\ yaw:\ \%.3f"{}},\ imu.get\_pitch\_deg(),\ imu.get\_roll\_deg(),\ imu.get\_yaw\_deg());} +\DoxyCodeLine{\ \ \ \ \ \ \ \ \}} +\DoxyCodeLine{\ \ \ \ \}} +\DoxyCodeLine{} +\DoxyCodeLine{\}} + +\end{DoxyCode} + + +({\texttt{ back to top}})\doxysubsection{Documentation}\label{md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md5} +API documentation generated with doxygen can be found in the documentation directory of the master branch. ~\newline + + +({\texttt{ back to top}})\doxysubsection{Acknowledgements}\label{md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md6} +Special thanks to the original creators of the sparkfun BNO080 library. Developing this without a reference would have been much more time consuming. ~\newline + {\texttt{ https\+://github.\+com/sparkfun/\+Spark\+Fun\+\_\+\+BNO080\+\_\+\+Arduino\+\_\+\+Library}} ~\newline + + +Special thanks to Anton Babiy, aka hw\+Birdy007 for helping with debugging SPI. ~\newline + {\texttt{ https\+://github.\+com/hw\+Birdy007}} ~\newline + + +({\texttt{ back to top}})\doxysubsection{License}\label{md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md7} +Distributed under the MIT License. See {\ttfamily LICENSE.\+md} for more information. + +({\texttt{ back to top}})\doxysubsection{Contact}\label{md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e_autotoc_md8} +Myles Parfeniuk -\/ {\texttt{ myles.\+parfenyuk@gmail.\+com}} + +Project Link\+: {\texttt{ https\+://github.\+com/myles-\/parfeniuk/esp32\+\_\+\+BNO08x.\+git}} + +({\texttt{ back to top}}) \ No newline at end of file diff --git a/documentation/latex/refman.tex b/documentation/latex/refman.tex new file mode 100644 index 0000000..a689c6a --- /dev/null +++ b/documentation/latex/refman.tex @@ -0,0 +1,203 @@ + % Handle batch mode + % to overcome problems with too many open files + \let\mypdfximage\pdfximage\def\pdfximage{\immediate\mypdfximage} + \pdfminorversion=7 + % Set document class depending on configuration + \documentclass[twoside]{book} + %% moved from doxygen.sty due to workaround for LaTex 2019 version and unmaintained tabu package + \usepackage{ifthen} + \ifx\requestedLaTeXdate\undefined + \usepackage{array} + \else + \usepackage{array}[=2016-10-06] + \fi + %% + % Packages required by doxygen + \makeatletter + \providecommand\IfFormatAtLeastTF{\@ifl@t@r\fmtversion} + % suppress package identification of infwarerr as it contains the word "warning" + \let\@@protected@wlog\protected@wlog + \def\protected@wlog#1{\wlog{package info suppressed}} + \RequirePackage{infwarerr} + \let\protected@wlog\@@protected@wlog + \makeatother + \IfFormatAtLeastTF{2016/01/01}{}{\usepackage{fixltx2e}} % for \textsubscript + \IfFormatAtLeastTF{2015/01/01}{\pdfsuppresswarningpagegroup=1}{} + \usepackage{doxygen} + \usepackage{graphicx} + \usepackage[utf8]{inputenc} + \usepackage{makeidx} + \PassOptionsToPackage{warn}{textcomp} + \usepackage{textcomp} + \usepackage[nointegrals]{wasysym} + \usepackage{ifxetex} + % NLS support packages + % Define default fonts + % Font selection + \usepackage[T1]{fontenc} + % set main and monospaced font + \usepackage[scaled=.90]{helvet} +\usepackage{courier} +\renewcommand{\familydefault}{\sfdefault} + \doxyallsectionsfont{% + \fontseries{bc}\selectfont% + \color{darkgray}% + } + \renewcommand{\DoxyLabelFont}{% + \fontseries{bc}\selectfont% + \color{darkgray}% + } + \newcommand{\+}{\discretionary{\mbox{\scriptsize$\hookleftarrow$}}{}{}} + % Arguments of doxygenemoji: + % 1) '::' form of the emoji, already LaTeX-escaped + % 2) file with the name of the emoji without the .png extension + % in case image exist use this otherwise use the '::' form + \newcommand{\doxygenemoji}[2]{% + \IfFileExists{./#2.png}{\raisebox{-0.1em}{\includegraphics[height=0.9em]{./#2.png}}}{#1}% + } + % Page & text layout + \usepackage{geometry} + \geometry{% + a4paper,% + top=2.5cm,% + bottom=2.5cm,% + left=2.5cm,% + right=2.5cm% + } + \usepackage{changepage} + % Allow a bit of overflow to go unnoticed by other means + \tolerance=750 + \hfuzz=15pt + \hbadness=750 + \setlength{\emergencystretch}{15pt} + \setlength{\parindent}{0cm} + \newcommand{\doxynormalparskip}{\setlength{\parskip}{3ex plus 2ex minus 2ex}} + \newcommand{\doxytocparskip}{\setlength{\parskip}{1ex plus 0ex minus 0ex}} + \doxynormalparskip + % Redefine paragraph/subparagraph environments, using sectsty fonts + \makeatletter + \renewcommand{\paragraph}{% + \@startsection{paragraph}{4}{0ex}{-1.0ex}{1.0ex}{% + \normalfont\normalsize\bfseries\SS@parafont% + }% + } + \renewcommand{\subparagraph}{% + \@startsection{subparagraph}{5}{0ex}{-1.0ex}{1.0ex}{% + \normalfont\normalsize\bfseries\SS@subparafont% + }% + } + \makeatother + \makeatletter + \newcommand\hrulefilll{\leavevmode\leaders\hrule\hskip 0pt plus 1filll\kern\z@} + \makeatother + % Headers & footers + \usepackage{fancyhdr} + \pagestyle{fancyplain} + \renewcommand{\footrulewidth}{0.4pt} + \fancypagestyle{fancyplain}{ + \fancyhf{} + \fancyhead[LE, RO]{\bfseries\thepage} + \fancyhead[LO]{\bfseries\rightmark} + \fancyhead[RE]{\bfseries\leftmark} + \fancyfoot[LO, RE]{\bfseries\scriptsize Generated by Doxygen } + } + \fancypagestyle{plain}{ + \fancyhf{} + \fancyfoot[LO, RE]{\bfseries\scriptsize Generated by Doxygen } + \renewcommand{\headrulewidth}{0pt} + } + \pagestyle{fancyplain} + \renewcommand{\chaptermark}[1]{% + \markboth{#1}{}% + } + \renewcommand{\sectionmark}[1]{% + \markright{\thesection\ #1}% + } + % ToC, LoF, LoT, bibliography, and index + % Indices & bibliography + \usepackage{natbib} + \usepackage[titles]{tocloft} + \setcounter{tocdepth}{3} + \setcounter{secnumdepth}{5} + % creating indexes + \makeindex + \usepackage{newunicodechar} + \makeatletter + \def\doxynewunicodechar#1#2{% + \@tempswafalse + \edef\nuc@tempa{\detokenize{#1}}% + \if\relax\nuc@tempa\relax + \nuc@emptyargerr + \else + \edef\@tempb{\expandafter\@car\nuc@tempa\@nil}% + \nuc@check + \if@tempswa + \@namedef{u8:\nuc@tempa}{#2}% + \fi + \fi + } + \makeatother + \doxynewunicodechar{⁻}{${}^{-}$}% Superscript minus + \doxynewunicodechar{²}{${}^{2}$}% Superscript two + \doxynewunicodechar{³}{${}^{3}$}% Superscript three + % Hyperlinks + % Custom commands used by the header + % Custom commands + \newcommand{\clearemptydoublepage}{% + \newpage{\pagestyle{empty}\cleardoublepage}% + } + % caption style definition + \usepackage{caption} + \captionsetup{labelsep=space,justification=centering,font={bf},singlelinecheck=off,skip=4pt,position=top} + % in page table of contents + \IfFormatAtLeastTF{2023/05/01}{\usepackage[deeplevels]{etoc}}{\usepackage[deeplevels]{etoc_doxygen}} + \etocsettocstyle{\doxytocparskip}{\doxynormalparskip} + \etocsetlevel{subsubsubsection}{4} + \etocsetlevel{subsubsubsubsection}{5} + \etocsetlevel{subsubsubsubsubsection}{6} + \etocsetlevel{subsubsubsubsubsubsection}{7} + \etocsetlevel{paragraph}{8} + \etocsetlevel{subparagraph}{9} + % prevent numbers overlap the titles in toc + \renewcommand{\numberline}[1]{#1~} +% End of preamble, now comes the document contents +%===== C O N T E N T S ===== +\begin{document} + \raggedbottom + % Titlepage & ToC + \pagenumbering{alph} + \begin{titlepage} + \vspace*{7cm} + \begin{center}% + {\Large esp32\+\_\+\+BNO08x}\\ + [1ex]\large 1.\+00 \\ + \vspace*{1cm} + {\large Generated by Doxygen 1.9.7}\\ + \end{center} + \end{titlepage} + \clearemptydoublepage + \pagenumbering{roman} + \tableofcontents + \clearemptydoublepage + \pagenumbering{arabic} +%--- Begin generated contents --- +\input{md__d_1_2development_2git_2esp32___b_n_o08x_2_r_e_a_d_m_e} +\chapter{Class Index} +\input{annotated} +\chapter{File Index} +\input{files} +\chapter{Class Documentation} +\input{class_b_n_o08x} +\input{structbno08x__config__t} +\chapter{File Documentation} +\input{_b_n_o08x_8hpp_source} +%--- End generated contents --- +% Index + \backmatter + \newpage + \phantomsection + \clearemptydoublepage + \addcontentsline{toc}{chapter}{\indexname} + \printindex +% Required for some languages (in combination with latexdocumentpre from the header) +\end{document} diff --git a/documentation/latex/structbno08x__config__t.tex b/documentation/latex/structbno08x__config__t.tex new file mode 100644 index 0000000..c5514be --- /dev/null +++ b/documentation/latex/structbno08x__config__t.tex @@ -0,0 +1,71 @@ +\doxysection{bno08x\+\_\+config\+\_\+t Struct Reference} +\label{structbno08x__config__t}\index{bno08x\_config\_t@{bno08x\_config\_t}} + + +IMU configuration settings passed into constructor. + + + + +{\ttfamily \#include $<$BNO08x.\+hpp$>$} + +\doxysubsubsection*{Public Member Functions} +\begin{DoxyCompactItemize} +\item +\label{structbno08x__config__t_abf8805292192f4c30c5000423175a2e1} +{\bfseries bno08x\+\_\+config\+\_\+t} () +\begin{DoxyCompactList}\small\item\em Default IMU configuration settings ~\newline + \end{DoxyCompactList}\end{DoxyCompactItemize} +\doxysubsubsection*{Public Attributes} +\begin{DoxyCompactItemize} +\item +\label{structbno08x__config__t_a020d2343750bb7debc2a108ae038c9ec} +spi\+\_\+host\+\_\+device\+\_\+t {\bfseries spi\+\_\+peripheral} +\begin{DoxyCompactList}\small\item\em SPI peripheral to be used. \end{DoxyCompactList}\item +\label{structbno08x__config__t_a79023fd80039e41a22b7f73ccd5fc861} +gpio\+\_\+num\+\_\+t {\bfseries io\+\_\+mosi} +\begin{DoxyCompactList}\small\item\em MOSI GPIO pin (connects to \doxyref{BNO08x}{p.}{class_b_n_o08x} DI pin) \end{DoxyCompactList}\item +\label{structbno08x__config__t_a9468180a773892977db39cc5ed9368e3} +gpio\+\_\+num\+\_\+t {\bfseries io\+\_\+miso} +\begin{DoxyCompactList}\small\item\em MISO GPIO pin (connects to \doxyref{BNO08x}{p.}{class_b_n_o08x} SDA pin) \end{DoxyCompactList}\item +\label{structbno08x__config__t_a639685b91ae3198909d722316495246a} +gpio\+\_\+num\+\_\+t {\bfseries io\+\_\+sclk} +\begin{DoxyCompactList}\small\item\em SCLK pin (connects to \doxyref{BNO08x}{p.}{class_b_n_o08x} SCL pin) \end{DoxyCompactList}\item +\label{structbno08x__config__t_ab1b5351b63da0c172c942463d0dc2505} +gpio\+\_\+num\+\_\+t {\bfseries io\+\_\+cs} +\item +\label{structbno08x__config__t_a3cfe965659cfbc6b0c5269bd0211975f} +gpio\+\_\+num\+\_\+t {\bfseries io\+\_\+int} +\begin{DoxyCompactList}\small\item\em Chip select pin (connects to \doxyref{BNO08x}{p.}{class_b_n_o08x} CS pin) \end{DoxyCompactList}\item +\label{structbno08x__config__t_a62745c761219139f66ecd173b51577fc} +gpio\+\_\+num\+\_\+t {\bfseries io\+\_\+rst} +\begin{DoxyCompactList}\small\item\em Host interrupt pin (connects to \doxyref{BNO08x}{p.}{class_b_n_o08x} INT pin) \end{DoxyCompactList}\item +gpio\+\_\+num\+\_\+t \textbf{ io\+\_\+wake} +\begin{DoxyCompactList}\small\item\em Reset pin (connects to \doxyref{BNO08x}{p.}{class_b_n_o08x} RST pin) \end{DoxyCompactList}\item +\label{structbno08x__config__t_a652ad01310ba21afcae1bb765de51cfe} +uint64\+\_\+t {\bfseries sclk\+\_\+speed} +\begin{DoxyCompactList}\small\item\em Desired SPI SCLK speed in Hz (max 3MHz) \end{DoxyCompactList}\item +\label{structbno08x__config__t_a720c215a75b3922ffa6f683e7ca70abe} +bool {\bfseries debug\+\_\+en} +\begin{DoxyCompactList}\small\item\em Whether or not debugging print statements are enabled. \end{DoxyCompactList}\end{DoxyCompactItemize} + + +\doxysubsection{Detailed Description} +IMU configuration settings passed into constructor. + +\doxysubsection{Member Data Documentation} +\label{structbno08x__config__t_a90ad7f316dc443874d19dc7e723a0ce0} +\index{bno08x\_config\_t@{bno08x\_config\_t}!io\_wake@{io\_wake}} +\index{io\_wake@{io\_wake}!bno08x\_config\_t@{bno08x\_config\_t}} +\doxysubsubsection{io\_wake} +{\footnotesize\ttfamily gpio\+\_\+num\+\_\+t bno08x\+\_\+config\+\_\+t\+::io\+\_\+wake} + + + +Reset pin (connects to \doxyref{BNO08x}{p.}{class_b_n_o08x} RST pin) + +Wake pin (optional, connects to \doxyref{BNO08x}{p.}{class_b_n_o08x} P0) + +The documentation for this struct was generated from the following file\+:\begin{DoxyCompactItemize} +\item +D\+:/development/git/esp32\+\_\+\+BNO08x/BNO08x.\+hpp\end{DoxyCompactItemize} diff --git a/documentation/latex/tabu_doxygen.sty b/documentation/latex/tabu_doxygen.sty new file mode 100644 index 0000000..3f17d1d --- /dev/null +++ b/documentation/latex/tabu_doxygen.sty @@ -0,0 +1,2557 @@ +%% +%% This is file `tabu.sty', +%% generated with the docstrip utility. +%% +%% The original source files were: +%% +%% tabu.dtx (with options: `package') +%% +%% This is a generated file. +%% Copyright (FC) 2010-2011 - lppl +%% +%% tabu : 2011/02/26 v2.8 - tabu : Flexible LaTeX tabulars +%% +%% ********************************************************************************************** +%% \begin{tabu} { preamble } => default target: \linewidth or \linegoal +%% \begin{tabu} to { preamble } => target specified +%% \begin{tabu} spread { preamble } => target relative to the ``natural width'' +%% +%% tabu works in text and in math modes. +%% +%% X columns: automatic width adjustment + horizontal and vertical alignment +%% \begin{tabu} { X[4c] X[1c] X[-2ml] } +%% +%% Horizontal lines and / or leaders: +%% \hline\hline => double horizontal line +%% \firsthline\hline => for nested tabulars +%% \lasthline\hline => for nested tabulars +%% \tabucline[line spec]{column-column} => ``funny'' lines (dash/leader) +%% Automatic lines / leaders : +%% \everyrow{\hline\hline} +%% +%% Vertical lines and / or leaders: +%% \begin{tabu} { |[3pt red] X[4c] X[1c] X[-2ml] |[3pt blue] } +%% \begin{tabu} { |[3pt red] X[4c] X[1c] X[-2ml] |[3pt on 2pt off 4pt blue] } +%% +%% Fixed vertical spacing adjustment: +%% \extrarowheight= \extrarowdepth= +%% or: \extrarowsep= => may be prefixed by \global +%% +%% Dynamic vertical spacing adjustment: +%% \abovetabulinesep= \belowtabulinesep= +%% or: \tabulinesep= => may be prefixed by \global +%% +%% delarray.sty shortcuts: in math and text modes +%% \begin{tabu} .... \({ preamble }\) +%% +%% Algorithms reports: +%% \tracingtabu=1 \tracingtabu=2 +%% +%% ********************************************************************************************** +%% +%% This work may be distributed and/or modified under the +%% conditions of the LaTeX Project Public License, either +%% version 1.3 of this license or (at your option) any later +%% version. The latest version of this license is in +%% http://www.latex-project.org/lppl.txt +%% +%% This work consists of the main source file tabu.dtx +%% and the derived files +%% tabu.sty, tabu.pdf, tabu.ins +%% +%% tabu : Flexible LaTeX tabulars +%% lppl copyright 2010-2011 by FC +%% + +\NeedsTeXFormat{LaTeX2e}[2005/12/01] +\ProvidesPackage{tabu_doxygen}[2011/02/26 v2.8 - flexible LaTeX tabulars (FC), frozen version for doxygen] +\RequirePackage{array}[2008/09/09] +\RequirePackage{varwidth}[2009/03/30] +\AtEndOfPackage{\tabu@AtEnd \let\tabu@AtEnd \@undefined} +\let\tabu@AtEnd\@empty +\def\TMP@EnsureCode#1={% + \edef\tabu@AtEnd{\tabu@AtEnd + \catcode#1 \the\catcode#1}% + \catcode#1=% +}% \TMP@EnsureCode +\TMP@EnsureCode 33 = 12 % ! +\TMP@EnsureCode 58 = 12 % : (for siunitx) +\TMP@EnsureCode124 = 12 % | +\TMP@EnsureCode 36 = 3 % $ = math shift +\TMP@EnsureCode 38 = 4 % & = tab alignment character +\TMP@EnsureCode 32 = 10 % space +\TMP@EnsureCode 94 = 7 % ^ +\TMP@EnsureCode 95 = 8 % _ +%% Constants -------------------------------------------------------- +\newcount \c@taburow \def\thetaburow {\number\c@taburow} +\newcount \tabu@nbcols +\newcount \tabu@cnt +\newcount \tabu@Xcol +\let\tabu@start \@tempcnta +\let\tabu@stop \@tempcntb +\newcount \tabu@alloc \tabu@alloc=\m@ne +\newcount \tabu@nested +\def\tabu@alloc@{\global\advance\tabu@alloc \@ne \tabu@nested\tabu@alloc} +\newdimen \tabu@target +\newdimen \tabu@spreadtarget +\newdimen \tabu@naturalX +\newdimen \tabucolX +\let\tabu@DELTA \@tempdimc +\let\tabu@thick \@tempdima +\let\tabu@on \@tempdimb +\let\tabu@off \@tempdimc +\newdimen \tabu@Xsum +\newdimen \extrarowdepth +\newdimen \abovetabulinesep +\newdimen \belowtabulinesep +\newdimen \tabustrutrule \tabustrutrule \z@ +\newtoks \tabu@thebody +\newtoks \tabu@footnotes +\newsavebox \tabu@box +\newsavebox \tabu@arstrutbox +\newsavebox \tabu@hleads +\newsavebox \tabu@vleads +\newif \iftabu@colortbl +\newif \iftabu@siunitx +\newif \iftabu@measuring +\newif \iftabu@spread +\newif \iftabu@negcoef +\newif \iftabu@everyrow +\def\tabu@everyrowtrue {\global\let\iftabu@everyrow \iftrue} +\def\tabu@everyrowfalse{\global\let\iftabu@everyrow \iffalse} +\newif \iftabu@long +\newif \iftabuscantokens +\def\tabu@rescan {\tabu@verbatim \scantokens } +%% Utilities (for internal usage) ----------------------------------- +\def\tabu@gobblespace #1 {#1} +\def\tabu@gobbletoken #1#2{#1} +\def\tabu@gobbleX{\futurelet\@let@token \tabu@gobblex} +\def\tabu@gobblex{\if ^^J\noexpand\@let@token \expandafter\@gobble + \else\ifx \@sptoken\@let@token + \expandafter\tabu@gobblespace\expandafter\tabu@gobbleX + \fi\fi +}% \tabu@gobblex +\def\tabu@X{^^J} +{\obeyspaces +\global\let\tabu@spxiii= % saves an active space (for \ifx) +\gdef\tabu@@spxiii{ }} +\def\tabu@ifenvir {% only for \multicolumn + \expandafter\tabu@if@nvir\csname\@currenvir\endcsname +}% \tabu@ifenvir +\def\tabu@if@nvir #1{\csname @\ifx\tabu#1first\else + \ifx\longtabu#1first\else + second\fi\fi oftwo\endcsname +}% \tabu@ifenvir +\def\tabu@modulo #1#2{\numexpr\ifnum\numexpr#1=\z@ 0\else #1-(#1-(#2-1)/2)/(#2)*(#2)\fi} +{\catcode`\&=3 +\gdef\tabu@strtrim #1{% #1 = control sequence to trim + \ifodd 1\ifx #1\@empty \else \ifx #1\space \else 0\fi \fi + \let\tabu@c@l@r \@empty \let#1\@empty + \else \expandafter \tabu@trimspaces #1\@nnil + \fi +}% \tabu@strtrim +\gdef\tabu@trimspaces #1\@nnil{\let\tabu@c@l@r=#2\tabu@firstspace .#1& }% +\gdef\tabu@firstspace #1#2#3 &{\tabu@lastspace #2#3&} +\gdef\tabu@lastspace #1{\def #3{#1}% + \ifx #3\tabu@c@l@r \def\tabu@c@l@r{\protect\color{#1}}\expandafter\remove@to@nnil \fi + \tabu@trimspaces #1\@nnil} +}% \catcode +\def\tabu@sanitizearg #1#2{{% + \csname \ifcsname if@safe@actives\endcsname % + @safe@activestrue\else + relax\fi \endcsname + \edef#2{#1}\tabu@strtrim#2\@onelevel@sanitize#2% + \expandafter}\expandafter\def\expandafter#2\expandafter{#2}% +}% \tabu@sanitizearg +\def\tabu@textbar #1{\begingroup \endlinechar\m@ne \scantokens{\def\:{|}}% + \expandafter\endgroup \expandafter#1\:% !!! semi simple group !!! +}% \tabu@textbar +\def\tabu@everyrow@bgroup{\iftabu@everyrow \begingroup \else \noalign{\ifnum0=`}\fi \fi} +\def\tabu@everyrow@egroup{% + \iftabu@everyrow \expandafter \endgroup \the\toks@ + \else \ifnum0=`{\fi}% + \fi +}% \tabu@everyrow@egroup +\def\tabu@arstrut {\global\setbox\@arstrutbox \hbox{\vrule + height \arraystretch \dimexpr\ht\strutbox+\extrarowheight + depth \arraystretch \dimexpr\dp\strutbox+\extrarowdepth + width \z@}% +}% \tabu@arstrut +\def\tabu@rearstrut {% + \@tempdima \arraystretch\dimexpr\ht\strutbox+\extrarowheight \relax + \@tempdimb \arraystretch\dimexpr\dp\strutbox+\extrarowdepth \relax + \ifodd 1\ifdim \ht\@arstrutbox=\@tempdima + \ifdim \dp\@arstrutbox=\@tempdimb 0 \fi\fi + \tabu@mkarstrut + \fi +}% \tabu@rearstrut +\def\tabu@@DBG #1{\ifdim\tabustrutrule>\z@ \color{#1}\fi} +\def\tabu@DBG@arstrut {\global\setbox\@arstrutbox + \hbox to\z@{\hbox to\z@{\hss + {\tabu@DBG{cyan}\vrule + height \arraystretch \dimexpr\ht\strutbox+\extrarowheight + depth \z@ + width \tabustrutrule}\kern-\tabustrutrule + {\tabu@DBG{pink}\vrule + height \z@ + depth \arraystretch \dimexpr\dp\strutbox+\extrarowdepth + width \tabustrutrule}}}% +}% \tabu@DBG@arstrut +\def\tabu@save@decl{\toks\count@ \expandafter{\the\toks\expandafter\count@ + \@nextchar}}% +\def\tabu@savedecl{\ifcat$\d@llarend\else + \let\save@decl \tabu@save@decl \fi % no inversion of tokens in text mode +}% \tabu@savedecl +\def\tabu@finalstrut #1{\unskip\ifhmode\nobreak\fi\vrule height\z@ depth\z@ width\z@} +\newcommand*\tabuDisableCommands {\g@addto@macro\tabu@trialh@@k } +\let\tabu@trialh@@k \@empty +\def\tabu@nowrite #1#{{\afterassignment}\toks@} +\let\tabu@write\write +\let\tabu@immediate\immediate +\def\tabu@WRITE{\begingroup + \def\immediate\write{\aftergroup\endgroup + \tabu@immediate\tabu@write}% +}% \tabu@WRITE +\expandafter\def\expandafter\tabu@GenericError\expandafter{% + \expandafter\tabu@WRITE\GenericError} +\def\tabu@warn{\tabu@WRITE\PackageWarning{tabu}} +\def\tabu@noxfootnote [#1]{\@gobble} +\def\tabu@nocolor #1#{\@gobble} +\newcommand*\tabu@norowcolor[2][]{} +\def\tabu@maybesiunitx #1{\def\tabu@temp{#1}% + \futurelet\@let@token \tabu@m@ybesiunitx} +\def\tabu@m@ybesiunitx #1{\def\tabu@m@ybesiunitx {% + \ifx #1\@let@token \let\tabu@cellleft \@empty \let\tabu@cellright \@empty \fi + \tabu@temp}% \tabu@m@ybesiunitx +}\expandafter\tabu@m@ybesiunitx \csname siunitx_table_collect_begin:Nn\endcsname +\def\tabu@celllalign@def #1{\def\tabu@celllalign{\tabu@maybesiunitx{#1}}}% +%% Fixed vertical spacing adjustment: \extrarowsep ------------------ +\newcommand*\extrarowsep{\edef\tabu@C@extra{\the\numexpr\tabu@C@extra+1}% + \iftabu@everyrow \aftergroup\tabu@Gextra + \else \aftergroup\tabu@n@Gextra + \fi + \@ifnextchar={\tabu@gobbletoken\tabu@extra} \tabu@extra +}% \extrarowsep +\def\tabu@extra {\@ifnextchar_% + {\tabu@gobbletoken{\tabu@setextra\extrarowheight \extrarowdepth}} + {\ifx ^\@let@token \def\tabu@temp{% + \tabu@gobbletoken{\tabu@setextra\extrarowdepth \extrarowheight}}% + \else \let\tabu@temp \@empty + \afterassignment \tabu@setextrasep \extrarowdepth + \fi \tabu@temp}% +}% \tabu@extra +\def\tabu@setextra #1#2{\def\tabu@temp{\tabu@extr@#1#2}\afterassignment\tabu@temp#2} +\def\tabu@extr@ #1#2{\@ifnextchar^% + {\tabu@gobbletoken{\tabu@setextra\extrarowdepth \extrarowheight}} + {\ifx _\@let@token \def\tabu@temp{% + \tabu@gobbletoken{\tabu@setextra\extrarowheight \extrarowdepth}}% + \else \let\tabu@temp \@empty + \tabu@Gsave \tabu@G@extra \tabu@C@extra \extrarowheight \extrarowdepth + \fi \tabu@temp}% +}% \tabu@extr@ +\def\tabu@setextrasep {\extrarowheight=\extrarowdepth + \tabu@Gsave \tabu@G@extra \tabu@C@extra \extrarowheight \extrarowdepth +}% \tabu@setextrasep +\def\tabu@Gextra{\ifx \tabu@G@extra\@empty \else {\tabu@Rextra}\fi} +\def\tabu@n@Gextra{\ifx \tabu@G@extra\@empty \else \noalign{\tabu@Rextra}\fi} +\def\tabu@Rextra{\tabu@Grestore \tabu@G@extra \tabu@C@extra} +\let\tabu@C@extra \z@ +\let\tabu@G@extra \@empty +%% Dynamic vertical spacing adjustment: \tabulinesep ---------------- +\newcommand*\tabulinesep{\edef\tabu@C@linesep{\the\numexpr\tabu@C@linesep+1}% + \iftabu@everyrow \aftergroup\tabu@Glinesep + \else \aftergroup\tabu@n@Glinesep + \fi + \@ifnextchar={\tabu@gobbletoken\tabu@linesep} \tabu@linesep +}% \tabulinesep +\def\tabu@linesep {\@ifnextchar_% + {\tabu@gobbletoken{\tabu@setsep\abovetabulinesep \belowtabulinesep}} + {\ifx ^\@let@token \def\tabu@temp{% + \tabu@gobbletoken{\tabu@setsep\belowtabulinesep \abovetabulinesep}}% + \else \let\tabu@temp \@empty + \afterassignment \tabu@setlinesep \abovetabulinesep + \fi \tabu@temp}% +}% \tabu@linesep +\def\tabu@setsep #1#2{\def\tabu@temp{\tabu@sets@p#1#2}\afterassignment\tabu@temp#2} +\def\tabu@sets@p #1#2{\@ifnextchar^% + {\tabu@gobbletoken{\tabu@setsep\belowtabulinesep \abovetabulinesep}} + {\ifx _\@let@token \def\tabu@temp{% + \tabu@gobbletoken{\tabu@setsep\abovetabulinesep \belowtabulinesep}}% + \else \let\tabu@temp \@empty + \tabu@Gsave \tabu@G@linesep \tabu@C@linesep \abovetabulinesep \belowtabulinesep + \fi \tabu@temp}% +}% \tabu@sets@p +\def\tabu@setlinesep {\belowtabulinesep=\abovetabulinesep + \tabu@Gsave \tabu@G@linesep \tabu@C@linesep \abovetabulinesep \belowtabulinesep +}% \tabu@setlinesep +\def\tabu@Glinesep{\ifx \tabu@G@linesep\@empty \else {\tabu@Rlinesep}\fi} +\def\tabu@n@Glinesep{\ifx \tabu@G@linesep\@empty \else \noalign{\tabu@Rlinesep}\fi} +\def\tabu@Rlinesep{\tabu@Grestore \tabu@G@linesep \tabu@C@linesep} +\let\tabu@C@linesep \z@ +\let\tabu@G@linesep \@empty +%% \global\extrarowsep and \global\tabulinesep ------------------- +\def\tabu@Gsave #1#2#3#4{\xdef#1{#1% + \toks#2{\toks\the\currentgrouplevel{\global#3\the#3\global#4\the#4}}}% +}% \tabu@Gsave +\def\tabu@Grestore#1#2{% + \toks#2{}#1\toks\currentgrouplevel\expandafter{\expandafter}\the\toks#2\relax + \ifcat$\the\toks\currentgrouplevel$\else + \global\let#1\@empty \global\let#2\z@ + \the\toks\currentgrouplevel + \fi +}% \tabu@Grestore +%% Setting code for every row --------------------------------------- +\newcommand*\everyrow{\tabu@everyrow@bgroup + \tabu@start \z@ \tabu@stop \z@ \tabu@evrstartstop +}% \everyrow +\def\tabu@evrstartstop {\@ifnextchar^% + {\afterassignment \tabu@evrstartstop \tabu@stop=}% + {\ifx ^\@let@token + \afterassignment\tabu@evrstartstop \tabu@start=% + \else \afterassignment\tabu@everyr@w \toks@ + \fi}% +}% \tabu@evrstartstop +\def\tabu@everyr@w {% + \xdef\tabu@everyrow{% + \noexpand\tabu@everyrowfalse + \let\noalign \relax + \noexpand\tabu@rowfontreset + \iftabu@colortbl \noexpand\tabu@rc@ \fi % \taburowcolors + \let\noexpand\tabu@docline \noexpand\tabu@docline@evr + \the\toks@ + \noexpand\tabu@evrh@@k + \noexpand\tabu@rearstrut + \global\advance\c@taburow \@ne}% + \iftabu@everyrow \toks@\expandafter + {\expandafter\def\expandafter\tabu@evr@L\expandafter{\the\toks@}\ignorespaces}% + \else \xdef\tabu@evr@G{\the\toks@}% + \fi + \tabu@everyrow@egroup +}% \tabu@everyr@w +\def\tabu@evr {\def\tabu@evrh@@k} % for internal use only +\tabu@evr{} +%% line style and leaders ------------------------------------------- +\newcommand*\newtabulinestyle [1]{% + {\@for \@tempa :=#1\do{\expandafter\tabu@newlinestyle \@tempa==\@nil}}% +}% \newtabulinestyle +\def\tabu@newlinestyle #1=#2=#3\@nil{\tabu@getline {#2}% + \tabu@sanitizearg {#1}\@tempa + \ifodd 1\ifx \@tempa\@empty \ifdefined\tabu@linestyle@ 0 \fi\fi + \global\expandafter\let + \csname tabu@linestyle@\@tempa \endcsname =\tabu@thestyle \fi +}% \tabu@newlinestyle +\newcommand*\tabulinestyle [1]{\tabu@everyrow@bgroup \tabu@getline{#1}% + \iftabu@everyrow + \toks@\expandafter{\expandafter \def \expandafter + \tabu@ls@L\expandafter{\tabu@thestyle}\ignorespaces}% + \gdef\tabu@ls@{\tabu@ls@L}% + \else + \global\let\tabu@ls@G \tabu@thestyle + \gdef\tabu@ls@{\tabu@ls@G}% + \fi + \tabu@everyrow@egroup +}% \tabulinestyle +\newcommand*\taburulecolor{\tabu@everyrow@bgroup \tabu@textbar \tabu@rulecolor} +\def\tabu@rulecolor #1{\toks@{}% + \def\tabu@temp #1##1#1{\tabu@ruledrsc{##1}}\@ifnextchar #1% + \tabu@temp + \tabu@rulearc +}% \tabu@rulecolor +\def\tabu@ruledrsc #1{\edef\tabu@temp{#1}\tabu@strtrim\tabu@temp + \ifx \tabu@temp\@empty \def\tabu@temp{\tabu@rule@drsc@ {}{}}% + \else \edef\tabu@temp{\noexpand\tabu@rule@drsc@ {}{\tabu@temp}}% + \fi + \tabu@temp +}% \tabu@ruledrsc@ +\def\tabu@ruledrsc@ #1#{\tabu@rule@drsc@ {#1}} +\def\tabu@rule@drsc@ #1#2{% + \iftabu@everyrow + \ifx \\#1#2\\\toks@{\let\CT@drsc@ \relax}% + \else \toks@{\def\CT@drsc@{\color #1{#2}}}% + \fi + \else + \ifx \\#1#2\\\global\let\CT@drsc@ \relax + \else \gdef\CT@drsc@{\color #1{#2}}% + \fi + \fi + \tabu@rulearc +}% \tabu@rule@drsc@ +\def\tabu@rulearc #1#{\tabu@rule@arc@ {#1}} +\def\tabu@rule@arc@ #1#2{% + \iftabu@everyrow + \ifx \\#1#2\\\toks@\expandafter{\the\toks@ \def\CT@arc@{}}% + \else \toks@\expandafter{\the\toks@ \def\CT@arc@{\color #1{#2}}}% + \fi + \toks@\expandafter{\the\toks@ + \let\tabu@arc@L \CT@arc@ + \let\tabu@drsc@L \CT@drsc@ + \ignorespaces}% + \else + \ifx \\#1#2\\\gdef\CT@arc@{}% + \else \gdef\CT@arc@{\color #1{#2}}% + \fi + \global\let\tabu@arc@G \CT@arc@ + \global\let\tabu@drsc@G \CT@drsc@ + \fi + \tabu@everyrow@egroup +}% \tabu@rule@arc@ +\def\taburowcolors {\tabu@everyrow@bgroup \@testopt \tabu@rowcolors 1} +\def\tabu@rowcolors [#1]#2#{\tabu@rowc@lors{#1}{#2}} +\def\tabu@rowc@lors #1#2#3{% + \toks@{}\@defaultunits \count@ =\number0#2\relax \@nnil + \@defaultunits \tabu@start =\number0#1\relax \@nnil + \ifnum \count@<\tw@ \count@=\tw@ \fi + \advance\tabu@start \m@ne + \ifnum \tabu@start<\z@ \tabu@start \z@ \fi + \tabu@rowcolorseries #3\in@..\in@ \@nnil +}% \tabu@rowcolors +\def\tabu@rowcolorseries #1..#2\in@ #3\@nnil {% + \ifx \in@#1\relax + \iftabu@everyrow \toks@{\def\tabu@rc@{}\let\tabu@rc@L \tabu@rc@}% + \else \gdef\tabu@rc@{}\global\let\tabu@rc@G \tabu@rc@ + \fi + \else + \ifx \\#2\\\tabu@rowcolorserieserror \fi + \tabu@sanitizearg{#1}\tabu@temp + \tabu@sanitizearg{#2}\@tempa + \advance\count@ \m@ne + \iftabu@everyrow + \def\tabu@rc@ ##1##2##3##4{\def\tabu@rc@{% + \ifnum ##2=\c@taburow + \definecolorseries{tabu@rcseries@\the\tabu@nested}{rgb}{last}{##3}{##4}\fi + \ifnum \c@taburow<##2 \else + \ifnum \tabu@modulo {\c@taburow-##2}{##1+1}=\z@ + \resetcolorseries[{##1}]{tabu@rcseries@\the\tabu@nested}\fi + \xglobal\colorlet{tabu@rc@\the\tabu@nested}{tabu@rcseries@\the\tabu@nested!!+}% + \rowcolor{tabu@rc@\the\tabu@nested}\fi}% + }\edef\x{\noexpand\tabu@rc@ {\the\count@} + {\the\tabu@start} + {\tabu@temp} + {\@tempa}% + }\x + \toks@\expandafter{\expandafter\def\expandafter\tabu@rc@\expandafter{\tabu@rc@}}% + \toks@\expandafter{\the\toks@ \let\tabu@rc@L \tabu@rc@ \ignorespaces}% + \else % inside \noalign + \definecolorseries{tabu@rcseries@\the\tabu@nested}{rgb}{last}{\tabu@temp}{\@tempa}% + \expandafter\resetcolorseries\expandafter[\the\count@]{tabu@rcseries@\the\tabu@nested}% + \xglobal\colorlet{tabu@rc@\the\tabu@nested}{tabu@rcseries@\the\tabu@nested!!+}% + \let\noalign \relax \rowcolor{tabu@rc@\the\tabu@nested}% + \def\tabu@rc@ ##1##2{\gdef\tabu@rc@{% + \ifnum \tabu@modulo {\c@taburow-##2}{##1+1}=\@ne + \resetcolorseries[{##1}]{tabu@rcseries@\the\tabu@nested}\fi + \xglobal\colorlet{tabu@rc@\the\tabu@nested}{tabu@rcseries@\the\tabu@nested!!+}% + \rowcolor{tabu@rc@\the\tabu@nested}}% + }\edef\x{\noexpand\tabu@rc@{\the\count@}{\the\c@taburow}}\x + \global\let\tabu@rc@G \tabu@rc@ + \fi + \fi + \tabu@everyrow@egroup +}% \tabu@rowcolorseries +\tabuDisableCommands {\let\tabu@rc@ \@empty } +\def\tabu@rowcolorserieserror {\PackageError{tabu} + {Invalid syntax for \string\taburowcolors + \MessageBreak Please look at the documentation!}\@ehd +}% \tabu@rowcolorserieserror +\newcommand*\tabureset {% + \tabulinesep=\z@ \extrarowsep=\z@ \extratabsurround=\z@ + \tabulinestyle{}\everyrow{}\taburulecolor||{}\taburowcolors{}% +}% \tabureset +%% Parsing the line styles ------------------------------------------ +\def\tabu@getline #1{\begingroup + \csname \ifcsname if@safe@actives\endcsname % + @safe@activestrue\else + relax\fi \endcsname + \edef\tabu@temp{#1}\tabu@sanitizearg{#1}\@tempa + \let\tabu@thestyle \relax + \ifcsname tabu@linestyle@\@tempa \endcsname + \edef\tabu@thestyle{\endgroup + \def\tabu@thestyle{\expandafter\noexpand + \csname tabu@linestyle@\@tempa\endcsname}% + }\tabu@thestyle + \else \expandafter\tabu@definestyle \tabu@temp \@nil + \fi +}% \tabu@getline +\def\tabu@definestyle #1#2\@nil {\endlinechar \m@ne \makeatletter + \tabu@thick \maxdimen \tabu@on \maxdimen \tabu@off \maxdimen + \let\tabu@c@lon \@undefined \let\tabu@c@loff \@undefined + \ifodd 1\ifcat .#1\else\ifcat\relax #1\else 0\fi\fi % catcode 12 or non expandable cs + \def\tabu@temp{\tabu@getparam{thick}}% + \else \def\tabu@temp{\tabu@getparam{thick}\maxdimen}% + \fi + {% + \let\tabu@ \relax + \def\:{\obeyspaces \tabu@oXIII \tabu@commaXIII \edef\:}% (space active \: happy ;-)) + \scantokens{\:{\tabu@temp #1#2 \tabu@\tabu@}}% + \expandafter}\expandafter + \def\expandafter\:\expandafter{\:}% line spec rewritten now ;-) + \def\;{\def\:}% + \scantokens\expandafter{\expandafter\;\expandafter{\:}}% space is now inactive (catcode 10) + \let\tabu@ \tabu@getcolor \:% all arguments are ready now ;-) + \ifdefined\tabu@c@lon \else \let\tabu@c@lon\@empty \fi + \ifx \tabu@c@lon\@empty \def\tabu@c@lon{\CT@arc@}\fi + \ifdefined\tabu@c@loff \else \let\tabu@c@loff \@empty \fi + \ifdim \tabu@on=\maxdimen \ifdim \tabu@off<\maxdimen + \tabu@on \tabulineon \fi\fi + \ifdim \tabu@off=\maxdimen \ifdim \tabu@on<\maxdimen + \tabu@off \tabulineoff \fi\fi + \ifodd 1\ifdim \tabu@off=\maxdimen \ifdim \tabu@on=\maxdimen 0 \fi\fi + \in@true % + \else \in@false % + \fi + \ifdim\tabu@thick=\maxdimen \def\tabu@thick{\arrayrulewidth}% + \else \edef\tabu@thick{\the\tabu@thick}% + \fi + \edef \tabu@thestyle ##1##2{\endgroup + \def\tabu@thestyle{% + \ifin@ \noexpand\tabu@leadersstyle {\tabu@thick} + {\the\tabu@on}{##1} + {\the\tabu@off}{##2}% + \else \noexpand\tabu@rulesstyle + {##1\vrule width \tabu@thick}% + {##1\leaders \hrule height \tabu@thick \hfil}% + \fi}% + }\expandafter \expandafter + \expandafter \tabu@thestyle \expandafter + \expandafter \expandafter + {\expandafter\tabu@c@lon\expandafter}\expandafter{\tabu@c@loff}% +}% \tabu@definestyle +{\catcode`\O=\active \lccode`\O=`\o \catcode`\,=\active + \lowercase{\gdef\tabu@oXIII {\catcode`\o=\active \let O=\tabu@oxiii}} + \gdef\tabu@commaXIII {\catcode`\,=\active \let ,=\space} +}% \catcode +\def\tabu@oxiii #1{% + \ifcase \ifx n#1\z@ \else + \ifx f#1\@ne\else + \tw@ \fi\fi + \expandafter\tabu@onxiii + \or \expandafter\tabu@ofxiii + \else o% + \fi#1}% +\def\tabu@onxiii #1#2{% + \ifcase \ifx !#2\tw@ \else + \ifcat.\noexpand#2\z@ \else + \ifx \tabu@spxiii#2\@ne\else + \tw@ \fi\fi\fi + \tabu@getparam{on}#2\expandafter\@gobble + \or \expandafter\tabu@onxiii % (space is active) + \else o\expandafter\@firstofone + \fi{#1#2}}% +\def\tabu@ofxiii #1#2{% + \ifx #2f\expandafter\tabu@offxiii + \else o\expandafter\@firstofone + \fi{#1#2}} +\def\tabu@offxiii #1#2{% + \ifcase \ifx !#2\tw@ \else + \ifcat.\noexpand#2\z@ \else + \ifx\tabu@spxiii#2\@ne \else + \tw@ \fi\fi\fi + \tabu@getparam{off}#2\expandafter\@gobble + \or \expandafter\tabu@offxiii % (space is active) + \else o\expandafter\@firstofone + \fi{#1#2}} +\def\tabu@getparam #1{\tabu@ \csname tabu@#1\endcsname=} +\def\tabu@getcolor #1{% \tabu@ <- \tabu@getcolor after \edef + \ifx \tabu@#1\else % no more spec + \let\tabu@theparam=#1\afterassignment \tabu@getc@l@r #1\fi +}% \tabu@getcolor +\def\tabu@getc@l@r #1\tabu@ {% + \def\tabu@temp{#1}\tabu@strtrim \tabu@temp + \ifx \tabu@temp\@empty + \else%\ifcsname \string\color@\tabu@temp \endcsname % if the color exists + \ifx \tabu@theparam \tabu@off \let\tabu@c@loff \tabu@c@l@r + \else \let\tabu@c@lon \tabu@c@l@r + \fi + %\else \tabu@warncolour{\tabu@temp}% + \fi%\fi + \tabu@ % next spec +}% \tabu@getc@l@r +\def\tabu@warncolour #1{\PackageWarning{tabu} + {Color #1 is not defined. Default color used}% +}% \tabu@warncolour +\def\tabu@leadersstyle #1#2#3#4#5{\def\tabu@leaders{{#1}{#2}{#3}{#4}{#5}}% + \ifx \tabu@leaders\tabu@leaders@G \else + \tabu@LEADERS{#1}{#2}{#3}{#4}{#5}\fi +}% \tabu@leadersstyle +\def\tabu@rulesstyle #1#2{\let\tabu@leaders \@undefined + \gdef\tabu@thevrule{#1}\gdef\tabu@thehrule{#2}% +}% \tabu@rulesstyle +%% The leaders boxes ------------------------------------------------ +\def\tabu@LEADERS #1#2#3#4#5{%% width, dash, dash color, gap, gap color + {\let\color \tabu@color % => during trials -> \color = \tabu@nocolor + {% % but the leaders boxes should have colors ! + \def\@therule{\vrule}\def\@thick{height}\def\@length{width}% + \def\@box{\hbox}\def\@unbox{\unhbox}\def\@elt{\wd}% + \def\@skip{\hskip}\def\@ss{\hss}\def\tabu@leads{\tabu@hleads}% + \tabu@l@@d@rs {#1}{#2}{#3}{#4}{#5}% + \global\let\tabu@thehleaders \tabu@theleaders + }% + {% + \def\@therule{\hrule}\def\@thick{width}\def\@length{height}% + \def\@box{\vbox}\def\@unbox{\unvbox}\def\@elt{\ht}% + \def\@skip{\vskip}\def\@ss{\vss}\def\tabu@leads{\tabu@vleads}% + \tabu@l@@d@rs {#1}{#2}{#3}{#4}{#5}% + \global\let\tabu@thevleaders \tabu@theleaders + }% + \gdef\tabu@leaders@G{{#1}{#2}{#3}{#4}{#5}}% + }% +}% \tabu@LEADERS +\def\tabu@therule #1#2{\@therule \@thick#1\@length\dimexpr#2/2 \@depth\z@} +\def\tabu@l@@d@rs #1#2#3#4#5{%% width, dash, dash color, gap, gap color + \global\setbox \tabu@leads=\@box{% + {#3\tabu@therule{#1}{#2}}% + \ifx\\#5\\\@skip#4\else{#5\tabu@therule{#1}{#4*2}}\fi + {#3\tabu@therule{#1}{#2}}}% + \global\setbox\tabu@leads=\@box to\@elt\tabu@leads{\@ss + {#3\tabu@therule{#1}{#2}}\@unbox\tabu@leads}% + \edef\tabu@theleaders ##1{\def\noexpand\tabu@theleaders {% + {##1\tabu@therule{#1}{#2}}% + \xleaders \copy\tabu@leads \@ss + \tabu@therule{0pt}{-#2}{##1\tabu@therule{#1}{#2}}}% + }\tabu@theleaders{#3}% +}% \tabu@l@@d@rs +%% \tabu \endtabu \tabu* \longtabu \endlongtabu \longtabu* ---------- +\newcommand*\tabu {\tabu@longfalse + \ifmmode \def\tabu@ {\array}\def\endtabu {\endarray}% + \else \def\tabu@ {\tabu@tabular}\def\endtabu {\endtabular}\fi + \expandafter\let\csname tabu*\endcsname \tabu + \expandafter\def\csname endtabu*\endcsname{\endtabu}% + \tabu@spreadfalse \tabu@negcoeffalse \tabu@settarget +}% {tabu} +\let\tabu@tabular \tabular % +\expandafter\def\csname tabu*\endcsname{\tabuscantokenstrue \tabu} +\newcommand*\longtabu {\tabu@longtrue + \ifmmode\PackageError{tabu}{longtabu not allowed in math mode}\fi + \def\tabu@{\longtable}\def\endlongtabu{\endlongtable}% + \LTchunksize=\@M + \expandafter\let\csname tabu*\endcsname \tabu + \expandafter\def\csname endlongtabu*\endcsname{\endlongtabu}% + \let\LT@startpbox \tabu@LT@startpbox % \everypar{ array struts } + \tabu@spreadfalse \tabu@negcoeffalse \tabu@settarget +}% {longtabu} +\expandafter\def\csname longtabu*\endcsname{\tabuscantokenstrue \longtabu} +\def\tabu@nolongtabu{\PackageError{tabu} + {longtabu requires the longtable package}\@ehd} +%% Read the target and then : \tabular or \@array ------------------ +\def\tabu@settarget {\futurelet\@let@token \tabu@sett@rget } +\def\tabu@sett@rget {\tabu@target \z@ + \ifcase \ifx \bgroup\@let@token \z@ \else + \ifx \@sptoken\@let@token \@ne \else + \if t\@let@token \tw@ \else + \if s\@let@token \thr@@\else + \z@\fi\fi\fi\fi + \expandafter\tabu@begin + \or \expandafter\tabu@gobblespace\expandafter\tabu@settarget + \or \expandafter\tabu@to + \or \expandafter\tabu@spread + \fi +}% \tabu@sett@rget +\def\tabu@to to{\def\tabu@halignto{to}\tabu@gettarget} +\def\tabu@spread spread{\tabu@spreadtrue\def\tabu@halignto{spread}\tabu@gettarget} +\def\tabu@gettarget {\afterassignment\tabu@linegoaltarget \tabu@target } +\def\tabu@linegoaltarget {\futurelet\tabu@temp \tabu@linegoalt@rget } +\def\tabu@linegoalt@rget {% + \ifx \tabu@temp\LNGL@setlinegoal + \LNGL@setlinegoal \expandafter \@firstoftwo \fi % @gobbles \LNGL@setlinegoal + \tabu@begin +}% \tabu@linegoalt@rget +\def\tabu@begin #1#{% + \iftabu@measuring \expandafter\tabu@nestedmeasure \fi + \ifdim \tabu@target=\z@ \let\tabu@halignto \@empty + \else \edef\tabu@halignto{\tabu@halignto\the\tabu@target}% + \fi + \@testopt \tabu@tabu@ \tabu@aligndefault #1\@nil +}% \tabu@begin +\long\def\tabu@tabu@ [#1]#2\@nil #3{\tabu@setup + \def\tabu@align {#1}\def\tabu@savedpream{\NC@find #3}% + \tabu@ [\tabu@align ]#2{#3\tabu@rewritefirst }% +}% \tabu@tabu@ +\def\tabu@nestedmeasure {% + \ifodd 1\iftabu@spread \else \ifdim\tabu@target=\z@ \else 0 \fi\fi\relax + \tabu@spreadtrue + \else \begingroup \iffalse{\fi \ifnum0=`}\fi + \toks@{}\def\tabu@stack{b}% + \expandafter\tabu@collectbody\expandafter\tabu@quickrule + \expandafter\endgroup + \fi +}% \tabu@nestedmeasure +\def\tabu@quickrule {\indent\vrule height\z@ depth\z@ width\tabu@target} +%% \tabu@setup \tabu@init \tabu@indent +\def\tabu@setup{\tabu@alloc@ + \ifcase \tabu@nested + \ifmmode \else \iftabu@spread\else \ifdim\tabu@target=\z@ + \let\tabu@afterendpar \par + \fi\fi\fi + \def\tabu@aligndefault{c}\tabu@init \tabu@indent + \else % + \def\tabu@aligndefault{t}\let\tabudefaulttarget \linewidth + \fi + \let\tabu@thetarget \tabudefaulttarget \let\tabu@restored \@undefined + \edef\tabu@NC@list{\the\NC@list}\NC@list{\NC@do \tabu@rewritefirst}% + \everycr{}\let\@startpbox \tabu@startpbox % for nested tabu inside longtabu... + \let\@endpbox \tabu@endpbox % idem " " " " " " + \let\@tabarray \tabu@tabarray % idem " " " " " " + \tabu@setcleanup \tabu@setreset +}% \tabu@setup +\def\tabu@init{\tabu@starttimer \tabu@measuringfalse + \edef\tabu@hfuzz {\the\dimexpr\hfuzz+1sp}\global\tabu@footnotes{}% + \let\firsthline \tabu@firsthline \let\lasthline \tabu@lasthline + \let\firstline \tabu@firstline \let\lastline \tabu@lastline + \let\hline \tabu@hline \let\@xhline \tabu@xhline + \let\color \tabu@color \let\@arstrutbox \tabu@arstrutbox + \iftabu@colortbl\else\let\LT@@hline \tabu@LT@@hline \fi + \tabu@trivlist % + \let\@footnotetext \tabu@footnotetext \let\@xfootnotetext \tabu@xfootnotetext + \let\@xfootnote \tabu@xfootnote \let\centering \tabu@centering + \let\raggedright \tabu@raggedright \let\raggedleft \tabu@raggedleft + \let\tabudecimal \tabu@tabudecimal \let\Centering \tabu@Centering + \let\RaggedRight \tabu@RaggedRight \let\RaggedLeft \tabu@RaggedLeft + \let\justifying \tabu@justifying \let\rowfont \tabu@rowfont + \let\fbox \tabu@fbox \let\color@b@x \tabu@color@b@x + \let\tabu@@everycr \everycr \let\tabu@@everypar \everypar + \let\tabu@prepnext@tokORI \prepnext@tok\let\prepnext@tok \tabu@prepnext@tok + \let\tabu@multicolumnORI\multicolumn \let\multicolumn \tabu@multicolumn + \let\tabu@startpbox \@startpbox % for nested tabu inside longtabu pfff !!! + \let\tabu@endpbox \@endpbox % idem " " " " " " " + \let\tabu@tabarray \@tabarray % idem " " " " " " " + \tabu@adl@fix \let\endarray \tabu@endarray % colortbl & arydshln (delarray) + \iftabu@colortbl\CT@everycr\expandafter{\expandafter\iftabu@everyrow \the\CT@everycr \fi}\fi +}% \tabu@init +\def\tabu@indent{% correction for indentation + \ifdim \parindent>\z@\ifx \linewidth\tabudefaulttarget + \everypar\expandafter{% + \the\everypar\everypar\expandafter{\the\everypar}% + \setbox\z@=\lastbox + \ifdim\wd\z@>\z@ \edef\tabu@thetarget + {\the\dimexpr -\wd\z@+\tabudefaulttarget}\fi + \box\z@}% + \fi\fi +}% \tabu@indent +\def\tabu@setcleanup {% saves last global assignments + \ifodd 1\ifmmode \else \iftabu@long \else 0\fi\fi\relax + \def\tabu@aftergroupcleanup{% + \def\tabu@aftergroupcleanup{\aftergroup\tabu@cleanup}}% + \else + \def\tabu@aftergroupcleanup{% + \aftergroup\aftergroup\aftergroup\tabu@cleanup + \let\tabu@aftergroupcleanup \relax}% + \fi + \let\tabu@arc@Gsave \tabu@arc@G + \let\tabu@arc@G \tabu@arc@L % + \let\tabu@drsc@Gsave \tabu@drsc@G + \let\tabu@drsc@G \tabu@drsc@L % + \let\tabu@ls@Gsave \tabu@ls@G + \let\tabu@ls@G \tabu@ls@L % + \let\tabu@rc@Gsave \tabu@rc@G + \let\tabu@rc@G \tabu@rc@L % + \let\tabu@evr@Gsave \tabu@evr@G + \let\tabu@evr@G \tabu@evr@L % + \let\tabu@celllalign@save \tabu@celllalign + \let\tabu@cellralign@save \tabu@cellralign + \let\tabu@cellleft@save \tabu@cellleft + \let\tabu@cellright@save \tabu@cellright + \let\tabu@@celllalign@save \tabu@@celllalign + \let\tabu@@cellralign@save \tabu@@cellralign + \let\tabu@@cellleft@save \tabu@@cellleft + \let\tabu@@cellright@save \tabu@@cellright + \let\tabu@rowfontreset@save \tabu@rowfontreset + \let\tabu@@rowfontreset@save\tabu@@rowfontreset + \let\tabu@rowfontreset \@empty + \edef\tabu@alloc@save {\the\tabu@alloc}% restore at \tabu@reset + \edef\c@taburow@save {\the\c@taburow}% + \edef\tabu@naturalX@save {\the\tabu@naturalX}% + \let\tabu@naturalXmin@save \tabu@naturalXmin + \let\tabu@naturalXmax@save \tabu@naturalXmax + \let\tabu@mkarstrut@save \tabu@mkarstrut + \edef\tabu@clarstrut{% + \extrarowheight \the\dimexpr \ht\@arstrutbox-\ht\strutbox \relax + \extrarowdepth \the\dimexpr \dp\@arstrutbox-\dp\strutbox \relax + \let\noexpand\@arraystretch \@ne \noexpand\tabu@rearstrut}% +}% \tabu@setcleanup +\def\tabu@cleanup {\begingroup + \globaldefs\@ne \tabu@everyrowtrue + \let\tabu@arc@G \tabu@arc@Gsave + \let\CT@arc@ \tabu@arc@G + \let\tabu@drsc@G \tabu@drsc@Gsave + \let\CT@drsc@ \tabu@drsc@G + \let\tabu@ls@G \tabu@ls@Gsave + \let\tabu@ls@ \tabu@ls@G + \let\tabu@rc@G \tabu@rc@Gsave + \let\tabu@rc@ \tabu@rc@G + \let\CT@do@color \relax + \let\tabu@evr@G \tabu@evr@Gsave + \let\tabu@celllalign \tabu@celllalign@save + \let\tabu@cellralign \tabu@cellralign@save + \let\tabu@cellleft \tabu@cellleft@save + \let\tabu@cellright \tabu@cellright@save + \let\tabu@@celllalign \tabu@@celllalign@save + \let\tabu@@cellralign \tabu@@cellralign@save + \let\tabu@@cellleft \tabu@@cellleft@save + \let\tabu@@cellright \tabu@@cellright@save + \let\tabu@rowfontreset \tabu@rowfontreset@save + \let\tabu@@rowfontreset \tabu@@rowfontreset@save + \tabu@naturalX =\tabu@naturalX@save + \let\tabu@naturalXmax \tabu@naturalXmax@save + \let\tabu@naturalXmin \tabu@naturalXmin@save + \let\tabu@mkarstrut \tabu@mkarstrut@save + \c@taburow =\c@taburow@save + \ifcase \tabu@nested \tabu@alloc \m@ne\fi + \endgroup % + \ifcase \tabu@nested + \the\tabu@footnotes \global\tabu@footnotes{}% + \tabu@afterendpar \tabu@elapsedtime + \fi + \tabu@clarstrut + \everyrow\expandafter {\tabu@evr@G}% +}% \tabu@cleanup +\let\tabu@afterendpar \relax +\def\tabu@setreset {% + \edef\tabu@savedparams {% \relax for \tabu@message@save + \ifmmode \col@sep \the\arraycolsep + \else \col@sep \the\tabcolsep \fi \relax + \arrayrulewidth \the\arrayrulewidth \relax + \doublerulesep \the\doublerulesep \relax + \extratabsurround \the\extratabsurround \relax + \extrarowheight \the\extrarowheight \relax + \extrarowdepth \the\extrarowdepth \relax + \abovetabulinesep \the\abovetabulinesep \relax + \belowtabulinesep \the\belowtabulinesep \relax + \def\noexpand\arraystretch{\arraystretch}% + \ifdefined\minrowclearance \minrowclearance\the\minrowclearance\relax\fi}% + \begingroup + \@temptokena\expandafter{\tabu@savedparams}% => only for \savetabu / \usetabu + \ifx \tabu@arc@L\relax \else \tabu@setsave \tabu@arc@L \fi + \ifx \tabu@drsc@L\relax \else \tabu@setsave \tabu@drsc@L \fi + \tabu@setsave \tabu@ls@L \tabu@setsave \tabu@evr@L + \expandafter \endgroup \expandafter + \def\expandafter\tabu@saved@ \expandafter{\the\@temptokena + \let\tabu@arc@G \tabu@arc@L + \let\tabu@drsc@G \tabu@drsc@L + \let\tabu@ls@G \tabu@ls@L + \let\tabu@rc@G \tabu@rc@L + \let\tabu@evr@G \tabu@evr@L}% + \def\tabu@reset{\tabu@savedparams + \tabu@everyrowtrue \c@taburow \z@ + \let\CT@arc@ \tabu@arc@L + \let\CT@drsc@ \tabu@drsc@L + \let\tabu@ls@ \tabu@ls@L + \let\tabu@rc@ \tabu@rc@L + \global\tabu@alloc \tabu@alloc@save + \everyrow\expandafter{\tabu@evr@L}}% +}% \tabu@reset +\def\tabu@setsave #1{\expandafter\tabu@sets@ve #1\@nil{#1}} +\long\def\tabu@sets@ve #1\@nil #2{\@temptokena\expandafter{\the\@temptokena \def#2{#1}}} +%% The Rewriting Process ------------------------------------------- +\def\tabu@newcolumntype #1{% + \expandafter\tabu@new@columntype + \csname NC@find@\string#1\expandafter\endcsname + \csname NC@rewrite@\string#1\endcsname + {#1}% +}% \tabu@newcolumntype +\def\tabu@new@columntype #1#2#3{% + \def#1##1#3{\NC@{##1}}% + \let#2\relax \newcommand*#2% +}% \tabu@new@columntype +\def\tabu@privatecolumntype #1{% + \expandafter\tabu@private@columntype + \csname NC@find@\string#1\expandafter\endcsname + \csname NC@rewrite@\string#1\expandafter\endcsname + \csname tabu@NC@find@\string#1\expandafter\endcsname + \csname tabu@NC@rewrite@\string#1\endcsname + {#1}% +}% \tabu@privatecolumntype +\def\tabu@private@columntype#1#2#3#4{% + \g@addto@macro\tabu@privatecolumns{\let#1#3\let#2#4}% + \tabu@new@columntype#3#4% +}% \tabu@private@columntype +\let\tabu@privatecolumns \@empty +\newcommand*\tabucolumn [1]{\expandafter \def \expandafter + \tabu@highprioritycolumns\expandafter{\tabu@highprioritycolumns + \NC@do #1}}% +\let\tabu@highprioritycolumns \@empty +%% The | ``column'' : rewriting process -------------------------- +\tabu@privatecolumntype |{\tabu@rewritevline} +\newcommand*\tabu@rewritevline[1][]{\tabu@vlinearg{#1}% + \expandafter \NC@find \tabu@rewritten} +\def\tabu@lines #1{% + \ifx|#1\else \tabu@privatecolumntype #1{\tabu@rewritevline}\fi + \NC@list\expandafter{\the\NC@list \NC@do #1}% +}% \tabu@lines@ +\def\tabu@vlinearg #1{% + \ifx\\#1\\\def\tabu@thestyle {\tabu@ls@}% + \else\tabu@getline {#1}% + \fi + \def\tabu@rewritten ##1{\def\tabu@rewritten{!{##1\tabu@thevline}}% + }\expandafter\tabu@rewritten\expandafter{\tabu@thestyle}% + \expandafter \tabu@keepls \tabu@thestyle \@nil +}% \tabu@vlinearg +\def\tabu@keepls #1\@nil{% + \ifcat $\@cdr #1\@nil $% + \ifx \relax#1\else + \ifx \tabu@ls@#1\else + \let#1\relax + \xdef\tabu@mkpreambuffer{\tabu@mkpreambuffer + \tabu@savels\noexpand#1}\fi\fi\fi +}% \tabu@keepls +\def\tabu@thevline {\begingroup + \ifdefined\tabu@leaders + \setbox\@tempboxa=\vtop to\dimexpr + \ht\@arstrutbox+\dp\@arstrutbox{{\tabu@thevleaders}}% + \ht\@tempboxa=\ht\@arstrutbox \dp\@tempboxa=\dp\@arstrutbox + \box\@tempboxa + \else + \tabu@thevrule + \fi \endgroup +}% \tabu@thevline +\def\tabu@savels #1{% + \expandafter\let\csname\string#1\endcsname #1% + \expandafter\def\expandafter\tabu@reset\expandafter{\tabu@reset + \tabu@resetls#1}}% +\def\tabu@resetls #1{\expandafter\let\expandafter#1\csname\string#1\endcsname}% +%% \multicolumn inside tabu environment ----------------------------- +\tabu@newcolumntype \tabu@rewritemulticolumn{% + \aftergroup \tabu@endrewritemulticolumn % after \@mkpream group + \NC@list{\NC@do *}\tabu@textbar \tabu@lines + \tabu@savedecl + \tabu@privatecolumns + \NC@list\expandafter{\the\expandafter\NC@list \tabu@NC@list}% + \let\tabu@savels \relax + \NC@find +}% \tabu@rewritemulticolumn +\def\tabu@endrewritemulticolumn{\gdef\tabu@mkpreambuffer{}\endgroup} +\def\tabu@multicolumn{\tabu@ifenvir \tabu@multic@lumn \tabu@multicolumnORI} +\long\def\tabu@multic@lumn #1#2#3{\multispan{#1}\begingroup + \tabu@everyrowtrue + \NC@list{\NC@do \tabu@rewritemulticolumn}% + \expandafter\@gobbletwo % gobbles \multispan{#1} + \tabu@multicolumnORI{#1}{\tabu@rewritemulticolumn #2}% + {\iftabuscantokens \tabu@rescan \else \expandafter\@firstofone \fi + {#3}}% +}% \tabu@multic@lumn +%% The X column(s): rewriting process ----------------------------- +\tabu@privatecolumntype X[1][]{\begingroup \tabu@siunitx{\endgroup \tabu@rewriteX {#1}}} +\def\tabu@nosiunitx #1{#1{}{}\expandafter \NC@find \tabu@rewritten } +\def\tabu@siunitx #1{\@ifnextchar \bgroup + {\tabu@rewriteX@Ss{#1}} + {\tabu@nosiunitx{#1}}} +\def\tabu@rewriteX@Ss #1#2{\@temptokena{}% + \@defaultunits \let\tabu@temp =#2\relax\@nnil + \ifodd 1\ifx S\tabu@temp \else \ifx s\tabu@temp \else 0 \fi\fi + \def\NC@find{\def\NC@find >####1####2<####3\relax{#1 {####1}{####3}% + }\expandafter\NC@find \the\@temptokena \relax + }\expandafter\NC@rewrite@S \@gobble #2\relax + \else \tabu@siunitxerror + \fi + \expandafter \NC@find \tabu@rewritten +}% \tabu@rewriteX@Ss +\def\tabu@siunitxerror {\PackageError{tabu}{Not a S nor s column ! + \MessageBreak X column can only embed siunitx S or s columns}\@ehd +}% \tabu@siunitxerror +\def\tabu@rewriteX #1#2#3{\tabu@Xarg {#1}{#2}{#3}% + \iftabu@measuring + \else \tabu@measuringtrue % first X column found in the preamble + \let\@halignto \relax \let\tabu@halignto \relax + \iftabu@spread \tabu@spreadtarget \tabu@target \tabu@target \z@ + \else \tabu@spreadtarget \z@ \fi + \ifdim \tabu@target=\z@ + \setlength\tabu@target \tabu@thetarget + \tabu@message{\tabu@message@defaulttarget}% + \else \tabu@message{\tabu@message@target}\fi + \fi +}% \tabu@rewriteX +\def\tabu@rewriteXrestore #1#2#3{\let\@halignto \relax + \def\tabu@rewritten{l}} +\def\tabu@Xarg #1#2#3{% + \advance\tabu@Xcol \@ne \let\tabu@Xlcr \@empty + \let\tabu@Xdisp \@empty \let\tabu@Xmath \@empty + \ifx\\#1\\% + \def\tabu@rewritten{p}\tabucolX \p@ % + \else + \let\tabu@rewritten \@empty \let\tabu@temp \@empty \tabucolX \z@ + \tabu@Xparse {}#1\relax + \fi + \tabu@Xrewritten{#2}{#3}% +}% \tabu@Xarg +\def\tabu@Xparse #1{\futurelet\@let@token \tabu@Xtest} +\expandafter\def\expandafter\tabu@Xparsespace\space{\tabu@Xparse{}} +\def\tabu@Xtest{% + \ifcase \ifx \relax\@let@token \z@ \else + \if ,\@let@token \m@ne\else + \if p\@let@token 1\else + \if m\@let@token 2\else + \if b\@let@token 3\else + \if l\@let@token 4\else + \if c\@let@token 5\else + \if r\@let@token 6\else + \if j\@let@token 7\else + \if L\@let@token 8\else + \if C\@let@token 9\else + \if R\@let@token 10\else + \if J\@let@token 11\else + \ifx \@sptoken\@let@token 12\else + \if .\@let@token 13\else + \if -\@let@token 13\else + \ifcat $\@let@token 14\else + 15\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\relax + \or \tabu@Xtype {p}% + \or \tabu@Xtype {m}% + \or \tabu@Xtype {b}% + \or \tabu@Xalign \raggedright\relax + \or \tabu@Xalign \centering\relax + \or \tabu@Xalign \raggedleft\relax + \or \tabu@Xalign \tabu@justify\relax + \or \tabu@Xalign \RaggedRight\raggedright + \or \tabu@Xalign \Centering\centering + \or \tabu@Xalign \RaggedLeft\raggedleft + \or \tabu@Xalign \justifying\tabu@justify + \or \expandafter \tabu@Xparsespace + \or \expandafter \tabu@Xcoef + \or \expandafter \tabu@Xm@th + \or \tabu@Xcoef{}% + \else\expandafter \tabu@Xparse + \fi +}% \tabu@Xtest +\def\tabu@Xalign #1#2{% + \ifx \tabu@Xlcr\@empty \else \PackageWarning{tabu} + {Duplicate horizontal alignment specification}\fi + \ifdefined#1\def\tabu@Xlcr{#1}\let#1\relax + \else \def\tabu@Xlcr{#2}\let#2\relax\fi + \expandafter\tabu@Xparse +}% \tabu@Xalign +\def\tabu@Xtype #1{% + \ifx \tabu@rewritten\@empty \else \PackageWarning{tabu} + {Duplicate vertical alignment specification}\fi + \def\tabu@rewritten{#1}\expandafter\tabu@Xparse +}% \tabu@Xtype +\def\tabu@Xcoef#1{\edef\tabu@temp{\tabu@temp#1}% + \afterassignment\tabu@Xc@ef \tabu@cnt\number\if-#10\fi +}% \tabu@Xcoef +\def\tabu@Xc@ef{\advance\tabucolX \tabu@temp\the\tabu@cnt\p@ + \tabu@Xparse{}% +}% \tabu@Xc@ef +\def\tabu@Xm@th #1{\futurelet \@let@token \tabu@Xd@sp} +\def\tabu@Xd@sp{\let\tabu@Xmath=$% + \ifx $\@let@token \def\tabu@Xdisp{\displaystyle}% + \expandafter\tabu@Xparse + \else \expandafter\tabu@Xparse\expandafter{\expandafter}% + \fi +}% \tabu@Xd@sp +\def\tabu@Xrewritten {% + \ifx \tabu@rewritten\@empty \def\tabu@rewritten{p}\fi + \ifdim \tabucolX<\z@ \tabu@negcoeftrue + \else\ifdim \tabucolX=\z@ \tabucolX \p@ + \fi\fi + \edef\tabu@temp{{\the\tabu@Xcol}{\tabu@strippt\tabucolX}}% + \edef\tabu@Xcoefs{\tabu@Xcoefs \tabu@ \tabu@temp}% + \edef\tabu@rewritten ##1##2{\def\noexpand\tabu@rewritten{% + >{\tabu@Xlcr \ifx$\tabu@Xmath$\tabu@Xdisp\fi ##1}% + \tabu@rewritten {\tabu@hsize \tabu@temp}% + <{##2\ifx$\tabu@Xmath$\fi}}% + }\tabu@rewritten +}% \tabu@Xrewritten +\def\tabu@hsize #1#2{% + \ifdim #2\p@<\z@ + \ifdim \tabucolX=\maxdimen \tabu@wd{#1}\else + \ifdim \tabu@wd{#1}<-#2\tabucolX \tabu@wd{#1}\else -#2\tabucolX\fi + \fi + \else #2\tabucolX + \fi +}% \tabu@hsize +%% \usetabu and \preamble: rewriting process --------------------- +\tabu@privatecolumntype \usetabu [1]{% + \ifx\\#1\\\tabu@saveerr{}\else + \@ifundefined{tabu@saved@\string#1} + {\tabu@saveerr{#1}} + {\let\tabu@rewriteX \tabu@rewriteXrestore + \csname tabu@saved@\string#1\expandafter\endcsname\expandafter\@ne}% + \fi +}% \NC@rewrite@\usetabu +\tabu@privatecolumntype \preamble [1]{% + \ifx\\#1\\\tabu@saveerr{}\else + \@ifundefined{tabu@saved@\string#1} + {\tabu@saveerr{#1}} + {\csname tabu@saved@\string#1\expandafter\endcsname\expandafter\z@}% + \fi +}% \NC@rewrite@\preamble +%% Controlling the rewriting process ------------------------------- +\tabu@newcolumntype \tabu@rewritefirst{% + \iftabu@long \aftergroup \tabu@longpream % + \else \aftergroup \tabu@pream + \fi + \let\tabu@ \relax \let\tabu@hsize \relax + \let\tabu@Xcoefs \@empty \let\tabu@savels \relax + \tabu@Xcol \z@ \tabu@cnt \tw@ + \gdef\tabu@mkpreambuffer{\tabu@{}}\tabu@measuringfalse + \global\setbox\@arstrutbox \box\@arstrutbox + \NC@list{\NC@do *}\tabu@textbar \tabu@lines + \NC@list\expandafter{\the\NC@list \NC@do X}% + \iftabu@siunitx % + \NC@list\expandafter{\the\NC@list \NC@do S\NC@do s}\fi + \NC@list\expandafter{\the\expandafter\NC@list \tabu@highprioritycolumns}% + \expandafter\def\expandafter\tabu@NC@list\expandafter{% + \the\expandafter\NC@list \tabu@NC@list}% % * | X S + \NC@list\expandafter{\expandafter \NC@do \expandafter\usetabu + \expandafter \NC@do \expandafter\preamble + \the\NC@list \NC@do \tabu@rewritemiddle + \NC@do \tabu@rewritelast}% + \tabu@savedecl + \tabu@privatecolumns + \edef\tabu@prev{\the\@temptokena}\NC@find \tabu@rewritemiddle +}% NC@rewrite@\tabu@rewritefirst +\tabu@newcolumntype \tabu@rewritemiddle{% + \edef\tabu@temp{\the\@temptokena}\NC@find \tabu@rewritelast +}% \NC@rewrite@\tabu@rewritemiddle +\tabu@newcolumntype \tabu@rewritelast{% + \ifx \tabu@temp\tabu@prev \advance\tabu@cnt \m@ne + \NC@list\expandafter{\tabu@NC@list \NC@do \tabu@rewritemiddle + \NC@do \tabu@rewritelast}% + \else \let\tabu@prev\tabu@temp + \fi + \ifcase \tabu@cnt \expandafter\tabu@endrewrite + \else \expandafter\NC@find \expandafter\tabu@rewritemiddle + \fi +}% \NC@rewrite@\tabu@rewritelast +%% Choosing the strategy -------------------------------------------- +\def\tabu@endrewrite {% + \let\tabu@temp \NC@find + \ifx \@arrayright\relax \let\@arrayright \@empty \fi + \count@=% + \ifx \@finalstrut\tabu@finalstrut \z@ % outer in mode 0 print + \iftabu@measuring + \xdef\tabu@mkpreambuffer{\tabu@mkpreambuffer + \tabu@target \csname tabu@\the\tabu@nested.T\endcsname + \tabucolX \csname tabu@\the\tabu@nested.X\endcsname + \edef\@halignto {\ifx\@arrayright\@empty to\tabu@target\fi}}% + \fi + \else\iftabu@measuring 4 % X columns + \xdef\tabu@mkpreambuffer{\tabu@{\tabu@mkpreambuffer + \tabu@target \the\tabu@target + \tabu@spreadtarget \the\tabu@spreadtarget}% + \def\noexpand\tabu@Xcoefs{\tabu@Xcoefs}% + \edef\tabu@halignto{\ifx \@arrayright\@empty to\tabu@target\fi}}% + \let\tabu@Xcoefs \relax + \else\ifcase\tabu@nested \thr@@ % outer, no X + \global\let\tabu@afterendpar \relax + \else \@ne % inner, no X, outer in mode 1 or 2 + \fi + \ifdefined\tabu@usetabu + \else \ifdim\tabu@target=\z@ + \else \let\tabu@temp \tabu@extracolsep + \fi\fi + \fi + \fi + \xdef\tabu@mkpreambuffer{\count@ \the\count@ \tabu@mkpreambuffer}% + \tabu@temp +}% \tabu@endrewrite +\def\tabu@extracolsep{\@defaultunits \expandafter\let + \expandafter\tabu@temp \expandafter=\the\@temptokena \relax\@nnil + \ifx \tabu@temp\@sptoken + \expandafter\tabu@gobblespace \expandafter\tabu@extracolsep + \else + \edef\tabu@temp{\noexpand\NC@find + \if |\noexpand\tabu@temp @% + \else\if !\noexpand\tabu@temp @% + \else !% + \fi\fi + {\noexpand\extracolsep\noexpand\@flushglue}}% + \fi + \tabu@temp +}% \tabu@extrac@lsep +%% Implementing the strategy ---------------------------------------- +\long\def\tabu@pream #1\@preamble {% + \let\tabu@ \tabu@@ \tabu@mkpreambuffer \tabu@aftergroupcleanup + \NC@list\expandafter {\tabu@NC@list}% in case of nesting... + \ifdefined\tabu@usetabu \tabu@usetabu \tabu@target \z@ \fi + \let\tabu@savedpreamble \@preamble + \global\let\tabu@elapsedtime \relax + \tabu@thebody ={#1\tabu@aftergroupcleanup}% + \tabu@thebody =\expandafter{\the\expandafter\tabu@thebody + \@preamble}% + \edef\tabuthepreamble {\the\tabu@thebody}% ( no @ allowed for \scantokens ) + \tabu@select +}% \tabu@pream +\long\def\tabu@longpream #1\LT@bchunk #2\LT@bchunk{% + \let\tabu@ \tabu@@ \tabu@mkpreambuffer \tabu@aftergroupcleanup + \NC@list\expandafter {\tabu@NC@list}% in case of nesting... + \let\tabu@savedpreamble \@preamble + \global\let\tabu@elapsedtime \relax + \tabu@thebody ={#1\LT@bchunk #2\tabu@aftergroupcleanup \LT@bchunk}% + \edef\tabuthepreamble {\the\tabu@thebody}% ( no @ allowed for \scantokens ) + \tabu@select +}% \tabu@longpream +\def\tabu@select {% + \ifnum\tabu@nested>\z@ \tabuscantokensfalse \fi + \ifnum \count@=\@ne \iftabu@measuring \count@=\tw@ \fi\fi + \ifcase \count@ + \global\let\tabu@elapsedtime \relax + \tabu@seteverycr + \expandafter \tabuthepreamble % vertical adjustment (inherited from outer) + \or % exit in vertical measure + struts per cell because no X and outer in mode 3 + \tabu@evr{\tabu@verticalinit}\tabu@celllalign@def{\tabu@verticalmeasure}% + \def\tabu@cellralign{\tabu@verticalspacing}% + \tabu@seteverycr + \expandafter \tabuthepreamble + \or % exit without measure because no X and outer in mode 4 + \tabu@evr{}\tabu@celllalign@def{}\let\tabu@cellralign \@empty + \tabu@seteverycr + \expandafter \tabuthepreamble + \else % needs trials + \tabu@evr{}\tabu@celllalign@def{}\let\tabu@cellralign \@empty + \tabu@savecounters + \expandafter \tabu@setstrategy + \fi +}% \tabu@select +\def\tabu@@ {\gdef\tabu@mkpreambuffer} +%% Protections to set up before trials ------------------------------ +\def\tabu@setstrategy {\begingroup % + \tabu@trialh@@k \tabu@cnt \z@ % number of trials + \hbadness \@M \let\hbadness \@tempcnta + \hfuzz \maxdimen \let\hfuzz \@tempdima + \let\write \tabu@nowrite\let\GenericError \tabu@GenericError + \let\savetabu \@gobble \let\tabudefaulttarget \linewidth + \let\@footnotetext \@gobble \let\@xfootnote \tabu@xfootnote + \let\color \tabu@nocolor\let\rowcolor \tabu@norowcolor + \let\tabu@aftergroupcleanup \relax % only after the last trial + \tabu@mkpreambuffer + \ifnum \count@>\thr@@ \let\@halignto \@empty \tabucolX@init + \def\tabu@lasttry{\m@ne\p@}\fi + \begingroup \iffalse{\fi \ifnum0=`}\fi + \toks@{}\def\tabu@stack{b}\iftabuscantokens \endlinechar=10 \obeyspaces \fi % + \tabu@collectbody \tabu@strategy % +}% \tabu@setstrategy +\def\tabu@savecounters{% + \def\@elt ##1{\csname c@##1\endcsname\the\csname c@##1\endcsname}% + \edef\tabu@clckpt {\begingroup \globaldefs=\@ne \cl@@ckpt \endgroup}\let\@elt \relax +}% \tabu@savecounters +\def\tabucolX@init {% \tabucolX <= \tabu@target / (sum coefs > 0) + \dimen@ \z@ \tabu@Xsum \z@ \tabucolX \z@ \let\tabu@ \tabu@Xinit \tabu@Xcoefs + \ifdim \dimen@>\z@ + \@tempdima \dimexpr \tabu@target *\p@/\dimen@ + \tabu@hfuzz\relax + \ifdim \tabucolX<\@tempdima \tabucolX \@tempdima \fi + \fi +}% \tabucolX@init +\def\tabu@Xinit #1#2{\tabu@Xcol #1 \advance \tabu@Xsum + \ifdim #2\p@>\z@ #2\p@ \advance\dimen@ #2\p@ + \else -#2\p@ \tabu@negcoeftrue + \@tempdima \dimexpr \tabu@target*\p@/\dimexpr-#2\p@\relax \relax + \ifdim \tabucolX<\@tempdima \tabucolX \@tempdima \fi + \tabu@wddef{#1}{0pt}% + \fi +}% \tabu@Xinit +%% Collecting the environment body ---------------------------------- +\long\def\tabu@collectbody #1#2\end #3{% + \edef\tabu@stack{\tabu@pushbegins #2\begin\end\expandafter\@gobble\tabu@stack}% + \ifx \tabu@stack\@empty + \toks@\expandafter{\expandafter\tabu@thebody\expandafter{\the\toks@ #2}% + \def\tabu@end@envir{\end{#3}}% + \iftabuscantokens + \iftabu@long \def\tabu@endenvir {\end{#3}\tabu@gobbleX}% + \else \def\tabu@endenvir {\let\endarray \@empty + \end{#3}\tabu@gobbleX}% + \fi + \else \def\tabu@endenvir {\end{#3}}\fi}% + \let\tabu@collectbody \tabu@endofcollect + \else\def\tabu@temp{#3}% + \ifx \tabu@temp\@empty \toks@\expandafter{\the\toks@ #2\end }% + \else \ifx\tabu@temp\tabu@@spxiii \toks@\expandafter{\the\toks@ #2\end #3}% + \else \ifx\tabu@temp\tabu@X \toks@\expandafter{\the\toks@ #2\end #3}% + \else \toks@\expandafter{\the\toks@ #2\end{#3}}% + \fi\fi\fi + \fi + \tabu@collectbody{#1}% +}% \tabu@collectbody +\long\def\tabu@pushbegins#1\begin#2{\ifx\end#2\else b\expandafter\tabu@pushbegins\fi}% +\def\tabu@endofcollect #1{\ifnum0=`{}\fi + \expandafter\endgroup \the\toks@ #1% +}% \tabu@endofcollect +%% The trials: switching between strategies ------------------------- +\def\tabu@strategy {\relax % stops \count@ assignment ! + \ifcase\count@ % case 0 = print with vertical adjustment (outer is finished) + \expandafter \tabu@endoftrials + \or % case 1 = exit in vertical measure (outer in mode 3) + \expandafter\xdef\csname tabu@\the\tabu@nested.T\endcsname{\the\tabu@target}% + \expandafter\xdef\csname tabu@\the\tabu@nested.X\endcsname{\the\tabucolX}% + \expandafter \tabu@endoftrials + \or % case 2 = exit with a rule replacing the table (outer in mode 4) + \expandafter \tabu@quickend + \or % case 3 = outer is in mode 3 because of no X + \begingroup + \tabu@evr{\tabu@verticalinit}\tabu@celllalign@def{\tabu@verticalmeasure}% + \def\tabu@cellralign{\tabu@verticalspacing}% + \expandafter \tabu@measuring + \else % case 4 = horizontal measure + \begingroup + \global\let\tabu@elapsedtime \tabu@message@etime + \long\def\multicolumn##1##2##3{\multispan{##1}}% + \let\tabu@startpboxORI \@startpbox + \iftabu@spread + \def\tabu@naturalXmax {\z@}% + \let\tabu@naturalXmin \tabu@naturalXmax + \tabu@evr{\global\tabu@naturalX \z@}% + \let\@startpbox \tabu@startpboxmeasure + \else\iftabu@negcoef + \let\@startpbox \tabu@startpboxmeasure + \else \let\@startpbox \tabu@startpboxquick + \fi\fi + \expandafter \tabu@measuring + \fi +}% \tabu@strategy +\def\tabu@measuring{\expandafter \tabu@trial \expandafter + \count@ \the\count@ \tabu@endtrial +}% \tabu@measuring +\def\tabu@trial{\iftabu@long \tabu@longtrial \else \tabu@shorttrial \fi} +\def\tabu@shorttrial {\setbox\tabu@box \hbox\bgroup \tabu@seteverycr + \ifx \tabu@savecounters\relax \else + \let\tabu@savecounters \relax \tabu@clckpt \fi + $\iftabuscantokens \tabu@rescan \else \expandafter\@secondoftwo \fi + \expandafter{\expandafter \tabuthepreamble + \the\tabu@thebody + \csname tabu@adl@endtrial\endcsname + \endarray}$\egroup % got \tabu@box +}% \tabu@shorttrial +\def\tabu@longtrial {\setbox\tabu@box \hbox\bgroup \tabu@seteverycr + \ifx \tabu@savecounters\relax \else + \let\tabu@savecounters \relax \tabu@clckpt \fi + \iftabuscantokens \tabu@rescan \else \expandafter\@secondoftwo \fi + \expandafter{\expandafter \tabuthepreamble + \the\tabu@thebody + \tabuendlongtrial}\egroup % got \tabu@box +}% \tabu@longtrial +\def\tabuendlongtrial{% no @ allowed for \scantokens + \LT@echunk \global\setbox\@ne \hbox{\unhbox\@ne}\kern\wd\@ne + \LT@get@widths +}% \tabuendlongtrial +\def\tabu@adl@endtrial{% + \crcr \noalign{\global\adl@ncol \tabu@nbcols}}% anything global is crap, junky and fails ! +\def\tabu@seteverycr {\tabu@reset + \everycr \expandafter{\the\everycr \tabu@everycr}% + \let\everycr \tabu@noeverycr % +}% \tabu@seteverycr +\def\tabu@noeverycr{{\aftergroup\tabu@restoreeverycr \afterassignment}\toks@} +\def\tabu@restoreeverycr {\let\everycr \tabu@@everycr} +\def\tabu@everycr {\iftabu@everyrow \noalign{\tabu@everyrow}\fi} +\def\tabu@endoftrials {% + \iftabuscantokens \expandafter\@firstoftwo + \else \expandafter\@secondoftwo + \fi + {\expandafter \tabu@closetrialsgroup \expandafter + \tabu@rescan \expandafter{% + \expandafter\tabuthepreamble + \the\expandafter\tabu@thebody + \iftabu@long \else \endarray \fi}} + {\expandafter\tabu@closetrialsgroup \expandafter + \tabuthepreamble + \the\tabu@thebody}% + \tabu@endenvir % Finish ! +}% \tabu@endoftrials +\def\tabu@closetrialsgroup {% + \toks@\expandafter{\tabu@endenvir}% + \edef\tabu@bufferX{\endgroup + \tabucolX \the\tabucolX + \tabu@target \the\tabu@target + \tabu@cnt \the\tabu@cnt + \def\noexpand\tabu@endenvir{\the\toks@}% + %Quid de \@halignto = \tabu@halignto ?? + }% \tabu@bufferX + \tabu@bufferX + \ifcase\tabu@nested % print out (outer in mode 0) + \global\tabu@cnt \tabu@cnt + \tabu@evr{\tabu@verticaldynamicadjustment}% + \tabu@celllalign@def{\everypar{}}\let\tabu@cellralign \@empty + \let\@finalstrut \tabu@finalstrut + \else % vertical measure of nested tabu + \tabu@evr{\tabu@verticalinit}% + \tabu@celllalign@def{\tabu@verticalmeasure}% + \def\tabu@cellralign{\tabu@verticalspacing}% + \fi + \tabu@clckpt \let\@halignto \tabu@halignto + \let\@halignto \@empty + \tabu@seteverycr + \ifdim \tabustrutrule>\z@ \ifnum\tabu@nested=\z@ + \setbox\@arstrutbox \box\voidb@x % force \@arstrutbox to be rebuilt (visible struts) + \fi\fi +}% \tabu@closetrialsgroup +\def\tabu@quickend {\expandafter \endgroup \expandafter + \tabu@target \the\tabu@target \tabu@quickrule + \let\endarray \relax \tabu@endenvir +}% \tabu@quickend +\def\tabu@endtrial {\relax % stops \count@ assignment ! + \ifcase \count@ \tabu@err % case 0 = impossible here + \or \tabu@err % case 1 = impossible here + \or \tabu@err % case 2 = impossible here + \or % case 3 = outer goes into mode 0 + \def\tabu@bufferX{\endgroup}\count@ \z@ + \else % case 4 = outer goes into mode 3 + \iftabu@spread \tabu@spreadarith % inner into mode 1 (outer in mode 3) + \else \tabu@arith % or 2 (outer in mode 4) + \fi + \count@=% + \ifcase\tabu@nested \thr@@ % outer goes into mode 3 + \else\iftabu@measuring \tw@ % outer is in mode 4 + \else \@ne % outer is in mode 3 + \fi\fi + \edef\tabu@bufferX{\endgroup + \tabucolX \the\tabucolX + \tabu@target \the\tabu@target}% + \fi + \expandafter \tabu@bufferX \expandafter + \count@ \the\count@ \tabu@strategy +}% \tabu@endtrial +\def\tabu@err{\errmessage{(tabu) Internal impossible error! (\count@=\the\count@)}} +%% The algorithms: compute the widths / stop or go on --------------- +\def\tabu@arithnegcoef {% + \@tempdima \z@ \dimen@ \z@ \let\tabu@ \tabu@arith@negcoef \tabu@Xcoefs +}% \tabu@arithnegcoef +\def\tabu@arith@negcoef #1#2{% + \ifdim #2\p@>\z@ \advance\dimen@ #2\p@ % saturated by definition + \advance\@tempdima #2\tabucolX + \else + \ifdim -#2\tabucolX <\tabu@wd{#1}% c_i X < natural width <= \tabu@target-> saturated + \advance\dimen@ -#2\p@ + \advance\@tempdima -#2\tabucolX + \else + \advance\@tempdima \tabu@wd{#1}% natural width <= c_i X => neutralised + \ifdim \tabu@wd{#1}<\tabu@target \else % neutralised + \advance\dimen@ -#2\p@ % saturated (natural width = tabu@target) + \fi + \fi + \fi +}% \tabu@arith@negcoef +\def\tabu@givespace #1#2{% here \tabu@DELTA < \z@ + \ifdim \@tempdima=\z@ + \tabu@wddef{#1}{\the\dimexpr -\tabu@DELTA*\p@/\tabu@Xsum}% + \else + \tabu@wddef{#1}{\the\dimexpr \tabu@hsize{#1}{#2} + *(\p@ -\tabu@DELTA*\p@/\@tempdima)/\p@\relax}% + \fi +}% \tabu@givespace +\def\tabu@arith {\advance\tabu@cnt \@ne + \ifnum \tabu@cnt=\@ne \tabu@message{\tabu@titles}\fi + \tabu@arithnegcoef + \@tempdimb \dimexpr \wd\tabu@box -\@tempdima \relax % + \tabu@DELTA = \dimexpr \wd\tabu@box - \tabu@target \relax + \tabu@message{\tabu@message@arith}% + \ifdim \tabu@DELTA <\tabu@hfuzz + \ifdim \tabu@DELTA<\z@ % wd (tabu)<\tabu@target ? + \let\tabu@ \tabu@givespace \tabu@Xcoefs + \advance\@tempdima \@tempdimb \advance\@tempdima -\tabu@DELTA % for message + \else % already converged: nothing to do but nearly impossible... + \fi + \tabucolX \maxdimen + \tabu@measuringfalse + \else % need for narrower X columns + \tabucolX =\dimexpr (\@tempdima -\tabu@DELTA) *\p@/\tabu@Xsum \relax + \tabu@measuringtrue + \@whilesw \iftabu@measuring\fi {% + \advance\tabu@cnt \@ne + \tabu@arithnegcoef + \tabu@DELTA =\dimexpr \@tempdima+\@tempdimb -\tabu@target \relax % always < 0 here + \tabu@message{\tabu@header + \tabu@msgalign \tabucolX { }{ }{ }{ }{ }\@@ + \tabu@msgalign \@tempdima+\@tempdimb { }{ }{ }{ }{ }\@@ + \tabu@msgalign \tabu@target { }{ }{ }{ }{ }\@@ + \tabu@msgalign@PT \dimen@ { }{}{}{}{}{}{}\@@ + \ifdim -\tabu@DELTA<\tabu@hfuzz \tabu@spaces target ok\else + \tabu@msgalign \dimexpr -\tabu@DELTA *\p@/\dimen@ {}{}{}{}{}\@@ + \fi}% + \ifdim -\tabu@DELTA<\tabu@hfuzz + \advance\@tempdima \@tempdimb % for message + \tabu@measuringfalse + \else + \advance\tabucolX \dimexpr -\tabu@DELTA *\p@/\dimen@ \relax + \fi + }% + \fi + \tabu@message{\tabu@message@reached}% + \edef\tabu@bufferX{\endgroup \tabu@cnt \the\tabu@cnt + \tabucolX \the\tabucolX + \tabu@target \the\tabu@target}% +}% \tabu@arith +\def\tabu@spreadarith {% + \dimen@ \z@ \@tempdima \tabu@naturalXmax \let\tabu@ \tabu@spread@arith \tabu@Xcoefs + \edef\tabu@naturalXmin {\the\dimexpr\tabu@naturalXmin*\dimen@/\p@}% + \@tempdimc =\dimexpr \wd\tabu@box -\tabu@naturalXmax+\tabu@naturalXmin \relax + \iftabu@measuring + \tabu@target =\dimexpr \@tempdimc+\tabu@spreadtarget \relax + \edef\tabu@bufferX{\endgroup \tabucolX \the\tabucolX \tabu@target\the\tabu@target}% + \else + \tabu@message{\tabu@message@spreadarith}% + \ifdim \dimexpr \@tempdimc+\tabu@spreadtarget >\tabu@target + \tabu@message{(tabu) spread + \ifdim \@tempdimc>\tabu@target useless here: default target used% + \else too large: reduced to fit default target\fi.}% + \else + \tabu@target =\dimexpr \@tempdimc+\tabu@spreadtarget \relax + \tabu@message{(tabu) spread: New target set to \the\tabu@target^^J}% + \fi + \begingroup \let\tabu@wddef \@gobbletwo + \@tempdimb \@tempdima + \tabucolX@init + \tabu@arithnegcoef + \wd\tabu@box =\dimexpr \wd\tabu@box +\@tempdima-\@tempdimb \relax + \expandafter\endgroup \expandafter\tabucolX \the\tabucolX + \tabu@arith + \fi +}% \tabu@spreadarith +\def\tabu@spread@arith #1#2{% + \ifdim #2\p@>\z@ \advance\dimen@ #2\p@ + \else \advance\@tempdima \tabu@wd{#1}\relax + \fi +}% \tabu@spread@arith +%% Reporting in the .log file --------------------------------------- +\def\tabu@message@defaulttarget{% + \ifnum\tabu@nested=\z@^^J(tabu) Default target: + \ifx\tabudefaulttarget\linewidth \string\linewidth + \ifdim \tabu@thetarget=\linewidth \else + -\the\dimexpr\linewidth-\tabu@thetarget\fi = + \else\ifx\tabudefaulttarget\linegoal\string\linegoal= + \fi\fi + \else (tabu) Default target (nested): \fi + \the\tabu@target \on@line + \ifnum\tabu@nested=\z@ , page \the\c@page\fi} +\def\tabu@message@target {^^J(tabu) Target specified: + \the\tabu@target \on@line, page \the\c@page} +\def\tabu@message@arith {\tabu@header + \tabu@msgalign \tabucolX { }{ }{ }{ }{ }\@@ + \tabu@msgalign \wd\tabu@box { }{ }{ }{ }{ }\@@ + \tabu@msgalign \tabu@target { }{ }{ }{ }{ }\@@ + \tabu@msgalign@PT \dimen@ { }{}{}{}{}{}{}\@@ + \ifdim \tabu@DELTA<\tabu@hfuzz giving space\else + \tabu@msgalign \dimexpr (\@tempdima-\tabu@DELTA) *\p@/\tabu@Xsum -\tabucolX {}{}{}{}{}\@@ + \fi +}% \tabu@message@arith +\def\tabu@message@spreadarith {\tabu@spreadheader + \tabu@msgalign \tabu@spreadtarget { }{ }{ }{ }{}\@@ + \tabu@msgalign \wd\tabu@box { }{ }{ }{ }{}\@@ + \tabu@msgalign -\tabu@naturalXmax { }{}{}{}{}\@@ + \tabu@msgalign \tabu@naturalXmin { }{ }{ }{ }{}\@@ + \tabu@msgalign \ifdim \dimexpr\@tempdimc>\tabu@target \tabu@target + \else \@tempdimc+\tabu@spreadtarget \fi + {}{}{}{}{}\@@} +\def\tabu@message@negcoef #1#2{ + \tabu@spaces\tabu@spaces\space * #1. X[\rem@pt#2]: + \space width = \tabu@wd {#1} + \expandafter\string\csname tabu@\the\tabu@nested.W\number#1\endcsname + \ifdim -\tabu@pt#2\tabucolX<\tabu@target + < \number-\rem@pt#2 X + = \the\dimexpr -\tabu@pt#2\tabucolX \relax + \else + <= \the\tabu@target\space < \number-\rem@pt#2 X\fi} +\def\tabu@message@reached{\tabu@header + ******* Reached Target: + hfuzz = \tabu@hfuzz\on@line\space *******} +\def\tabu@message@etime{\edef\tabu@stoptime{\the\pdfelapsedtime}% + \tabu@message{(tabu)\tabu@spaces Time elapsed during measure: + \the\numexpr(\tabu@stoptime-\tabu@starttime-32767)/65536\relax sec + \the\numexpr\numexpr(\tabu@stoptime-\tabu@starttime) + -\numexpr(\tabu@stoptime-\tabu@starttime-32767)/65536\relax*65536\relax + *1000/65536\relax ms \tabu@spaces(\the\tabu@cnt\space + cycle\ifnum\tabu@cnt>\@ne s\fi)^^J^^J}} +\def\tabu@message@verticalsp {% + \ifdim \@tempdima>\tabu@ht + \ifdim \@tempdimb>\tabu@dp + \expandafter\expandafter\expandafter\string\tabu@ht = + \tabu@msgalign \@tempdima { }{ }{ }{ }{ }\@@ + \expandafter\expandafter\expandafter\string\tabu@dp = + \tabu@msgalign \@tempdimb { }{ }{ }{ }{ }\@@^^J% + \else + \expandafter\expandafter\expandafter\string\tabu@ht = + \tabu@msgalign \@tempdima { }{ }{ }{ }{ }\@@^^J% + \fi + \else\ifdim \@tempdimb>\tabu@dp + \tabu@spaces\tabu@spaces\tabu@spaces + \expandafter\expandafter\expandafter\string\tabu@dp = + \tabu@msgalign \@tempdimb { }{ }{ }{ }{ }\@@^^J\fi + \fi +}% \tabu@message@verticalsp +\edef\tabu@spaces{\@spaces} +\def\tabu@strippt{\expandafter\tabu@pt\the} +{\@makeother\P \@makeother\T\lowercase{\gdef\tabu@pt #1PT{#1}}} +\def\tabu@msgalign{\expandafter\tabu@msg@align\the\dimexpr} +\def\tabu@msgalign@PT{\expandafter\tabu@msg@align\romannumeral-`\0\tabu@strippt} +\def\do #1{% + \def\tabu@msg@align##1.##2##3##4##5##6##7##8##9\@@{% + \ifnum##1<10 #1 #1\else + \ifnum##1<100 #1 \else + \ifnum##1<\@m #1\fi\fi\fi + ##1.##2##3##4##5##6##7##8#1}% + \def\tabu@header{(tabu) \ifnum\tabu@cnt<10 #1\fi\the\tabu@cnt) }% + \def\tabu@titles{\ifnum \tabu@nested=\z@ + (tabu) Try#1 #1 tabu X #1 #1 #1tabu Width #1 #1 Target + #1 #1 #1 Coefs #1 #1 #1 Update^^J\fi}% + \def\tabu@spreadheader{% + (tabu) Try#1 #1 Spread #1 #1 tabu Width #1 #1 #1 Nat. X #1 #1 #1 #1Nat. Min. + #1 New Target^^J% + (tabu) sprd} + \def\tabu@message@save {\begingroup + \def\x ####1{\tabu@msg@align ####1{ }{ }{ }{ }{}\@@} + \def\z ####1{\expandafter\x\expandafter{\romannumeral-`\0\tabu@strippt + \dimexpr####1\p@{ }{ }}}% + \let\color \relax \def\tabu@rulesstyle ####1####2{\detokenize{####1}}% + \let\CT@arc@ \relax \let\@preamble \@gobble + \let\tabu@savedpream \@firstofone + \let\tabu@savedparams \@firstofone + \def\tabu@target ####1\relax {(tabu) target #1 #1 #1 #1 #1 = \x{####1}^^J}% + \def\tabucolX ####1\relax {(tabu) X columns width#1 = \x{####1}^^J}% + \def\tabu@nbcols ####1\relax {(tabu) Number of columns: \z{####1}^^J}% + \def\tabu@aligndefault ####1{(tabu) Default alignment: #1 #1 ####1^^J}% + \def\col@sep ####1\relax {(tabu) column sep #1 #1 #1 = \x{####1}^^J}% + \def\arrayrulewidth ####1\relax{(tabu) arrayrulewidth #1 = \x{####1}}% + \def\doublerulesep ####1\relax { doublerulesep = \x{####1}^^J}% + \def\extratabsurround####1\relax{(tabu) extratabsurround = \x{####1}^^J}% + \def\extrarowheight ####1\relax{(tabu) extrarowheight #1 = \x{####1}}% + \def\extrarowdepth ####1\relax {extrarowdepth = \x{####1}^^J}% + \def\abovetabulinesep####1\relax{(tabu) abovetabulinesep=\x{####1} }% + \def\belowtabulinesep####1\relax{ belowtabulinesep=\x{####1}^^J}% + \def\arraystretch ####1{(tabu) arraystretch #1 #1 = \z{####1}^^J}% + \def\minrowclearance####1\relax{(tabu) minrowclearance #1 = \x{####1}^^J}% + \def\tabu@arc@L ####1{(tabu) taburulecolor #1 #1 = ####1^^J}% + \def\tabu@drsc@L ####1{(tabu) tabudoublerulecolor= ####1^^J}% + \def\tabu@evr@L ####1{(tabu) everyrow #1 #1 #1 #1 = \detokenize{####1}^^J}% + \def\tabu@ls@L ####1{(tabu) line style = \detokenize{####1}^^J}% + \def\NC@find ####1\@nil{(tabu) tabu preamble#1 #1 = \detokenize{####1}^^J}% + \def\tabu@wddef####1####2{(tabu) Natural width ####1 = \x{####2}^^J}% + \let\edef \@gobbletwo \let\def \@empty \let\let \@gobbletwo + \tabu@message{% + (tabu) \string\savetabu{\tabu@temp}: \on@line^^J% + \tabu@usetabu \@nil^^J}% + \endgroup} +}\do{ } +%% Measuring the natural width (varwidth) - store the results ------- +\def\tabu@startpboxmeasure #1{\bgroup % entering \vtop + \edef\tabu@temp{\expandafter\@secondoftwo \ifx\tabu@hsize #1\else\relax\fi}% + \ifodd 1\ifx \tabu@temp\@empty 0 \else % starts with \tabu@hsize ? + \iftabu@spread \else % if spread -> measure + \ifdim \tabu@temp\p@>\z@ 0 \fi\fi\fi% if coef>0 -> do not measure + \let\@startpbox \tabu@startpboxORI % restore immediately (nesting) + \tabu@measuringtrue % for the quick option... + \tabu@Xcol =\expandafter\@firstoftwo\ifx\tabu@hsize #1\fi + \ifdim \tabu@temp\p@>\z@ \ifdim \tabu@temp\tabucolX<\tabu@target + \tabu@target=\tabu@temp\tabucolX \fi\fi + \setbox\tabu@box \hbox \bgroup + \begin{varwidth}\tabu@target + \let\FV@ListProcessLine \tabu@FV@ListProcessLine % \hbox to natural width... + \narrowragged \arraybackslash \parfillskip \@flushglue + \ifdefined\pdfadjustspacing \pdfadjustspacing\z@ \fi + \bgroup \aftergroup\tabu@endpboxmeasure + \ifdefined \cellspacetoplimit \tabu@cellspacepatch \fi + \else \expandafter\@gobble + \tabu@startpboxquick{#1}% \@gobble \bgroup + \fi +}% \tabu@startpboxmeasure +\def\tabu@cellspacepatch{\def\bcolumn##1\@nil{}\let\ecolumn\@empty + \bgroup\color@begingroup} +\def\tabu@endpboxmeasure {% + \@finalstrut \@arstrutbox + \end{varwidth}\egroup % + \ifdim \tabu@temp\p@ <\z@ % neg coef + \ifdim \tabu@wd\tabu@Xcol <\wd\tabu@box + \tabu@wddef\tabu@Xcol {\the\wd\tabu@box}% + \tabu@debug{\tabu@message@endpboxmeasure}% + \fi + \else % spread coef>0 + \global\advance \tabu@naturalX \wd\tabu@box + \@tempdima =\dimexpr \wd\tabu@box *\p@/\dimexpr \tabu@temp\p@\relax \relax + \ifdim \tabu@naturalXmax <\tabu@naturalX + \xdef\tabu@naturalXmax {\the\tabu@naturalX}\fi + \ifdim \tabu@naturalXmin <\@tempdima + \xdef\tabu@naturalXmin {\the\@tempdima}\fi + \fi + \box\tabu@box \egroup % end of \vtop (measure) restore \tabu@target +}% \tabu@endpboxmeasure +\def\tabu@wddef #1{\expandafter\xdef + \csname tabu@\the\tabu@nested.W\number#1\endcsname} +\def\tabu@wd #1{\csname tabu@\the\tabu@nested.W\number#1\endcsname} +\def\tabu@message@endpboxmeasure{\tabu@spaces\tabu@spaces<-> % <-> save natural wd + \the\tabu@Xcol. X[\tabu@temp]: + target = \the\tabucolX \space + \expandafter\expandafter\expandafter\string\tabu@wd\tabu@Xcol + =\tabu@wd\tabu@Xcol +}% \tabu@message@endpboxmeasure +\def\tabu@startpboxquick {\bgroup + \let\@startpbox \tabu@startpboxORI % restore immediately + \let\tabu \tabu@quick % \begin is expanded before... + \expandafter\@gobble \@startpbox % gobbles \bgroup +}% \tabu@startpboxquick +\def\tabu@quick {\begingroup \iffalse{\fi \ifnum0=`}\fi + \toks@{}\def\tabu@stack{b}\tabu@collectbody \tabu@endquick +}% \tabu@quick +\def\tabu@endquick {% + \ifodd 1\ifx\tabu@end@envir\tabu@endtabu \else + \ifx\tabu@end@envir\tabu@endtabus \else 0\fi\fi\relax + \endgroup + \else \let\endtabu \relax + \tabu@end@envir + \fi +}% \tabu@quick +\def\tabu@endtabu {\end{tabu}} +\def\tabu@endtabus {\end{tabu*}} +%% Measuring the heights and depths - store the results ------------- +\def\tabu@verticalmeasure{\everypar{}% + \ifnum \currentgrouptype>12 % 14=semi-simple, 15=math shift group + \setbox\tabu@box =\hbox\bgroup + \let\tabu@verticalspacing \tabu@verticalsp@lcr + \d@llarbegin % after \hbox ... + \else + \edef\tabu@temp{\ifnum\currentgrouptype=5\vtop + \else\ifnum\currentgrouptype=12\vcenter + \else\vbox\fi\fi}% + \setbox\tabu@box \hbox\bgroup$\tabu@temp \bgroup + \let\tabu@verticalspacing \tabu@verticalsp@pmb + \fi +}% \tabu@verticalmeasure +\def\tabu@verticalsp@lcr{% + \d@llarend \egroup % + \@tempdima \dimexpr \ht\tabu@box+\abovetabulinesep + \@tempdimb \dimexpr \dp\tabu@box+\belowtabulinesep \relax + \ifdim\tabustrutrule>\z@ \tabu@debug{\tabu@message@verticalsp}\fi + \ifdim \tabu@ht<\@tempdima \tabu@htdef{\the\@tempdima}\fi + \ifdim \tabu@dp<\@tempdimb \tabu@dpdef{\the\@tempdimb}\fi + \noindent\vrule height\@tempdima depth\@tempdimb +}% \tabu@verticalsp@lcr +\def\tabu@verticalsp@pmb{% inserts struts as needed + \par \expandafter\egroup + \expandafter$\expandafter + \egroup \expandafter + \@tempdimc \the\prevdepth + \@tempdima \dimexpr \ht\tabu@box+\abovetabulinesep + \@tempdimb \dimexpr \dp\tabu@box+\belowtabulinesep \relax + \ifdim\tabustrutrule>\z@ \tabu@debug{\tabu@message@verticalsp}\fi + \ifdim \tabu@ht<\@tempdima \tabu@htdef{\the\@tempdima}\fi + \ifdim \tabu@dp<\@tempdimb \tabu@dpdef{\the\@tempdimb}\fi + \let\@finalstrut \@gobble + \hrule height\@tempdima depth\@tempdimb width\hsize +%% \box\tabu@box +}% \tabu@verticalsp@pmb + +\def\tabu@verticalinit{% + \ifnum \c@taburow=\z@ \tabu@rearstrut \fi % after \tabu@reset ! + \advance\c@taburow \@ne + \tabu@htdef{\the\ht\@arstrutbox}\tabu@dpdef{\the\dp\@arstrutbox}% + \advance\c@taburow \m@ne +}% \tabu@verticalinit +\def\tabu@htdef {\expandafter\xdef \csname tabu@\the\tabu@nested.H\the\c@taburow\endcsname} +\def\tabu@ht {\csname tabu@\the\tabu@nested.H\the\c@taburow\endcsname} +\def\tabu@dpdef {\expandafter\xdef \csname tabu@\the\tabu@nested.D\the\c@taburow\endcsname} +\def\tabu@dp {\csname tabu@\the\tabu@nested.D\the\c@taburow\endcsname} +\def\tabu@verticaldynamicadjustment {% + \advance\c@taburow \@ne + \extrarowheight \dimexpr\tabu@ht - \ht\strutbox + \extrarowdepth \dimexpr\tabu@dp - \dp\strutbox + \let\arraystretch \@empty + \advance\c@taburow \m@ne +}% \tabu@verticaldynamicadjustment +\def\tabuphantomline{\crcr \noalign{% + {\globaldefs \@ne + \setbox\@arstrutbox \box\voidb@x + \let\tabu@@celllalign \tabu@celllalign + \let\tabu@@cellralign \tabu@cellralign + \let\tabu@@cellleft \tabu@cellleft + \let\tabu@@cellright \tabu@cellright + \let\tabu@@thevline \tabu@thevline + \let\tabu@celllalign \@empty + \let\tabu@cellralign \@empty + \let\tabu@cellright \@empty + \let\tabu@cellleft \@empty + \let\tabu@thevline \relax}% + \edef\tabu@temp{\tabu@multispan \tabu@nbcols{\noindent &}}% + \toks@\expandafter{\tabu@temp \noindent\tabu@everyrowfalse \cr + \noalign{\tabu@rearstrut + {\globaldefs\@ne + \let\tabu@celllalign \tabu@@celllalign + \let\tabu@cellralign \tabu@@cellralign + \let\tabu@cellleft \tabu@@cellleft + \let\tabu@cellright \tabu@@cellright + \let\tabu@thevline \tabu@@thevline}}}% + \expandafter}\the\toks@ +}% \tabuphantomline +%% \firsthline and \lasthline corrections --------------------------- +\def\tabu@firstline {\tabu@hlineAZ \tabu@firsthlinecorrection {}} +\def\tabu@firsthline{\tabu@hlineAZ \tabu@firsthlinecorrection \hline} +\def\tabu@lastline {\tabu@hlineAZ \tabu@lasthlinecorrection {}} +\def\tabu@lasthline {\tabu@hlineAZ \tabu@lasthlinecorrection \hline} +\def\tabu@hline {% replaces \hline if no colortbl (see \AtBeginDocument) + \noalign{\ifnum0=`}\fi + {\CT@arc@\hrule height\arrayrulewidth}% + \futurelet \tabu@temp \tabu@xhline +}% \tabu@hline +\def\tabu@xhline{% + \ifx \tabu@temp \hline + {\ifx \CT@drsc@\relax \vskip + \else\ifx \CT@drsc@\@empty \vskip + \else \CT@drsc@\hrule height + \fi\fi + \doublerulesep}% + \fi + \ifnum0=`{\fi}% +}% \tabu@xhline +\def\tabu@hlineAZ #1#2{\noalign{\ifnum0=`}\fi \dimen@ \z@ \count@ \z@ + \toks@{}\def\tabu@hlinecorrection{#1}\def\tabu@temp{#2}% + \tabu@hlineAZsurround +}% \tabu@hlineAZ +\newcommand*\tabu@hlineAZsurround[1][\extratabsurround]{% + \extratabsurround #1\let\tabucline \tabucline@scan + \let\hline \tabu@hlinescan \let\firsthline \hline + \let\cline \tabu@clinescan \let\lasthline \hline + \expandafter \futurelet \expandafter \tabu@temp + \expandafter \tabu@nexthlineAZ \tabu@temp +}% \tabu@hlineAZsurround +\def\tabu@hlinescan {\tabu@thick \arrayrulewidth \tabu@xhlineAZ \hline} +\def\tabu@clinescan #1{\tabu@thick \arrayrulewidth \tabu@xhlineAZ {\cline{#1}}} +\def\tabucline@scan{\@testopt \tabucline@sc@n {}} +\def\tabucline@sc@n #1[#2]{\tabu@xhlineAZ {\tabucline[{#1}]{#2}}} +\def\tabu@nexthlineAZ{% + \ifx \tabu@temp\hline \else + \ifx \tabu@temp\cline \else + \ifx \tabu@temp\tabucline \else + \tabu@hlinecorrection + \fi\fi\fi +}% \tabu@nexthlineAZ +\def\tabu@xhlineAZ #1{% + \toks@\expandafter{\the\toks@ #1}% + \@tempdimc \tabu@thick % The last line width + \ifcase\count@ \@tempdimb \tabu@thick % The first line width + \else \advance\dimen@ \dimexpr \tabu@thick+\doublerulesep \relax + \fi + \advance\count@ \@ne \futurelet \tabu@temp \tabu@nexthlineAZ +}% \tabu@xhlineAZ +\def\tabu@firsthlinecorrection{% \count@ = number of \hline -1 + \@tempdima \dimexpr \ht\@arstrutbox+\dimen@ + \edef\firsthline{% + \omit \hbox to\z@{\hss{\noexpand\tabu@DBG{yellow}\vrule + height \the\dimexpr\@tempdima+\extratabsurround + depth \dp\@arstrutbox + width \tabustrutrule}\hss}\cr + \noalign{\vskip -\the\dimexpr \@tempdima+\@tempdimb + +\dp\@arstrutbox \relax}% + \the\toks@ + }\ifnum0=`{\fi + \expandafter}\firsthline % we are then ! +}% \tabu@firsthlinecorrection +\def\tabu@lasthlinecorrection{% + \@tempdima \dimexpr \dp\@arstrutbox+\dimen@+\@tempdimb+\@tempdimc + \edef\lasthline{% + \the\toks@ + \noalign{\vskip -\the\dimexpr\dimen@+\@tempdimb+\dp\@arstrutbox}% + \omit \hbox to\z@{\hss{\noexpand\tabu@DBG{yellow}\vrule + depth \the\dimexpr \dp\@arstrutbox+\@tempdimb+\dimen@ + +\extratabsurround-\@tempdimc + height \z@ + width \tabustrutrule}\hss}\cr + }\ifnum0=`{\fi + \expandafter}\lasthline % we are then ! +}% \tabu@lasthlinecorrection +\def\tabu@LT@@hline{% + \ifx\LT@next\hline + \global\let\LT@next \@gobble + \ifx \CT@drsc@\relax + \gdef\CT@LT@sep{% + \noalign{\penalty-\@medpenalty\vskip\doublerulesep}}% + \else + \gdef\CT@LT@sep{% + \multispan\LT@cols{% + \CT@drsc@\leaders\hrule\@height\doublerulesep\hfill}\cr}% + \fi + \else + \global\let\LT@next\empty + \gdef\CT@LT@sep{% + \noalign{\penalty-\@lowpenalty\vskip-\arrayrulewidth}}% + \fi + \ifnum0=`{\fi}% + \multispan\LT@cols + {\CT@arc@\leaders\hrule\@height\arrayrulewidth\hfill}\cr + \CT@LT@sep + \multispan\LT@cols + {\CT@arc@\leaders\hrule\@height\arrayrulewidth\hfill}\cr + \noalign{\penalty\@M}% + \LT@next +}% \tabu@LT@@hline +%% Horizontal lines : \tabucline ------------------------------------ +\let\tabu@start \@tempcnta +\let\tabu@stop \@tempcntb +\newcommand*\tabucline{\noalign{\ifnum0=`}\fi \tabu@cline} +\newcommand*\tabu@cline[2][]{\tabu@startstop{#2}% + \ifnum \tabu@stop<\z@ \toks@{}% + \else \tabu@clinearg{#1}\tabu@thestyle + \edef\tabucline{\toks@{% + \ifnum \tabu@start>\z@ \omit + \tabu@multispan\tabu@start {\span\omit}&\fi + \omit \tabu@multispan\tabu@stop {\span\omit}% + \tabu@thehline\cr + }}\tabucline + \tabu@tracinglines{(tabu:tabucline) Style: #1^^J\the\toks@^^J^^J}% + \fi + \futurelet \tabu@temp \tabu@xcline +}% \tabu@cline +\def\tabu@clinearg #1{% + \ifx\\#1\\\let\tabu@thestyle \tabu@ls@ + \else \@defaultunits \expandafter\let\expandafter\@tempa + \romannumeral-`\0#1\relax \@nnil + \ifx \hbox\@tempa \tabu@clinebox{#1}% + \else\ifx \box\@tempa \tabu@clinebox{#1}% + \else\ifx \vbox\@tempa \tabu@clinebox{#1}% + \else\ifx \vtop\@tempa \tabu@clinebox{#1}% + \else\ifx \copy\@tempa \tabu@clinebox{#1}% + \else\ifx \leaders\@tempa \tabu@clineleads{#1}% + \else\ifx \cleaders\@tempa \tabu@clineleads{#1}% + \else\ifx \xleaders\@tempa \tabu@clineleads{#1}% + \else\tabu@getline {#1}% + \fi\fi\fi\fi\fi\fi\fi\fi + \fi +}% \tabu@clinearg +\def\tabu@clinebox #1{\tabu@clineleads{\xleaders#1\hss}} +\def\tabu@clineleads #1{% + \let\tabu@thestyle \relax \let\tabu@leaders \@undefined + \gdef\tabu@thehrule{#1}} +\def\tabu@thehline{\begingroup + \ifdefined\tabu@leaders + \noexpand\tabu@thehleaders + \else \noexpand\tabu@thehrule + \fi \endgroup +}% \tabu@thehline +\def\tabu@xcline{% + \ifx \tabu@temp\tabucline + \toks@\expandafter{\the\toks@ \noalign + {\ifx\CT@drsc@\relax \vskip + \else \CT@drsc@\hrule height + \fi + \doublerulesep}}% + \fi + \tabu@docline +}% \tabu@xcline +\def\tabu@docline {\ifnum0=`{\fi \expandafter}\the\toks@} +\def\tabu@docline@evr {\xdef\tabu@doclineafter{\the\toks@}% + \ifnum0=`{\fi}\aftergroup\tabu@doclineafter} +\def\tabu@multispan #1#2{% + \ifnum\numexpr#1>\@ne #2\expandafter\tabu@multispan + \else \expandafter\@gobbletwo + \fi {#1-1}{#2}% +}% \tabu@multispan +\def\tabu@startstop #1{\tabu@start@stop #1\relax 1-\tabu@nbcols \@nnil} +\def\tabu@start@stop #1-#2\@nnil{% + \@defaultunits \tabu@start\number 0#1\relax \@nnil + \@defaultunits \tabu@stop \number 0#2\relax \@nnil + \tabu@stop \ifnum \tabu@start>\tabu@nbcols \m@ne + \else\ifnum \tabu@stop=\z@ \tabu@nbcols + \else\ifnum \tabu@stop>\tabu@nbcols \tabu@nbcols + \else \tabu@stop + \fi\fi\fi + \advance\tabu@start \m@ne + \ifnum \tabu@start>\z@ \advance\tabu@stop -\tabu@start \fi +}% \tabu@start@stop +%% Numbers: siunitx S columns (and \tabudecimal) ------------------- +\def\tabu@tabudecimal #1{% + \def\tabu@decimal{#1}\@temptokena{}% + \let\tabu@getdecimal@ \tabu@getdecimal@ignorespaces + \tabu@scandecimal +}% \tabu@tabudecimal +\def\tabu@scandecimal{\futurelet \tabu@temp \tabu@getdecimal@} +\def\tabu@skipdecimal#1{#1\tabu@scandecimal} +\def\tabu@getdecimal@ignorespaces{% + \ifcase 0\ifx\tabu@temp\ignorespaces\else + \ifx\tabu@temp\@sptoken1\else + 2\fi\fi\relax + \let\tabu@getdecimal@ \tabu@getdecimal + \expandafter\tabu@skipdecimal + \or \expandafter\tabu@gobblespace\expandafter\tabu@scandecimal + \else \expandafter\tabu@skipdecimal + \fi +}% \tabu@getdecimal@ignorespaces +\def\tabu@get@decimal#1{\@temptokena\expandafter{\the\@temptokena #1}% + \tabu@scandecimal} +\def\do#1{% + \def\tabu@get@decimalspace#1{% + \@temptokena\expandafter{\the\@temptokena #1}\tabu@scandecimal}% +}\do{ } +\let\tabu@@tabudecimal \tabu@tabudecimal +\def\tabu@getdecimal{% + \ifcase 0\ifx 0\tabu@temp\else + \ifx 1\tabu@temp\else + \ifx 2\tabu@temp\else + \ifx 3\tabu@temp\else + \ifx 4\tabu@temp\else + \ifx 5\tabu@temp\else + \ifx 6\tabu@temp\else + \ifx 7\tabu@temp\else + \ifx 8\tabu@temp\else + \ifx 9\tabu@temp\else + \ifx .\tabu@temp\else + \ifx ,\tabu@temp\else + \ifx -\tabu@temp\else + \ifx +\tabu@temp\else + \ifx e\tabu@temp\else + \ifx E\tabu@temp\else + \ifx\tabu@cellleft\tabu@temp1\else + \ifx\ignorespaces\tabu@temp1\else + \ifx\@sptoken\tabu@temp2\else + 3\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\fi\relax + \expandafter\tabu@get@decimal + \or \expandafter\tabu@skipdecimal + \or \expandafter\tabu@get@decimalspace + \else\expandafter\tabu@printdecimal + \fi +}% \tabu@getdecimal +\def\tabu@printdecimal{% + \edef\tabu@temp{\the\@temptokena}% + \ifx\tabu@temp\@empty\else + \ifx\tabu@temp\space\else + \expandafter\tabu@decimal\expandafter{\the\@temptokena}% + \fi\fi +}% \tabu@printdecimal +%% Verbatim inside X columns ---------------------------------------- +\def\tabu@verbatim{% + \let\verb \tabu@verb + \let\FV@DefineCheckEnd \tabu@FV@DefineCheckEnd +}% \tabu@verbatim +\let\tabu@ltx@verb \verb +\def\tabu@verb{\@ifstar {\tabu@ltx@verb*} \tabu@ltx@verb} +\def\tabu@fancyvrb {% + \def\tabu@FV@DefineCheckEnd ##1{% + \def\tabu@FV@DefineCheckEnd{% + ##1% + \let\FV@CheckEnd \tabu@FV@CheckEnd + \let\FV@@CheckEnd \tabu@FV@@CheckEnd + \let\FV@@@CheckEnd \tabu@FV@@@CheckEnd + \edef\FV@EndScanning{% + \def\noexpand\next{\noexpand\end{\FV@EnvironName}}% + \global\let\noexpand\FV@EnvironName\relax + \noexpand\next}% + \xdef\FV@EnvironName{\detokenize\expandafter{\FV@EnvironName}}}% + }\expandafter\tabu@FV@DefineCheckEnd\expandafter{\FV@DefineCheckEnd} +}% \tabu@fancyvrb +\def\tabu@FV@CheckEnd #1{\expandafter\FV@@CheckEnd \detokenize{#1\end{}}\@nil} +\edef\tabu@FV@@@CheckEnd {\detokenize{\end{}}} +\begingroup +\catcode`\[1 \catcode`\]2 +\@makeother\{ \@makeother\} + \edef\x[\endgroup + \def\noexpand\tabu@FV@@CheckEnd ##1\detokenize[\end{]##2\detokenize[}]##3% + ]\x \@nil{\def\@tempa{#2}\def\@tempb{#3}} +\def\tabu@FV@ListProcessLine #1{% + \hbox {%to \hsize{% + \kern\leftmargin + \hbox {%to \linewidth{% + \FV@LeftListNumber + \FV@LeftListFrame + \FancyVerbFormatLine{#1}\hss +%% DG/SR modification begin - Jan. 28, 1998 (for numbers=right add-on) +%% \FV@RightListFrame}% + \FV@RightListFrame + \FV@RightListNumber}% +%% DG/SR modification end + \hss}} +%% \savetabu -------------------------------------------------------- +\newcommand*\savetabu[1]{\noalign{% + \tabu@sanitizearg{#1}\tabu@temp + \ifx \tabu@temp\@empty \tabu@savewarn{}{The tabu will not be saved}\else + \@ifundefined{tabu@saved@\tabu@temp}{}{\tabu@savewarn{#1}{Overwriting}}% + \ifdefined\tabu@restored \expandafter\let + \csname tabu@saved@\tabu@temp \endcsname \tabu@restored + \else {\tabu@save}% + \fi + \fi}% +}% \savetabu +\def\tabu@save {% + \toks0\expandafter{\tabu@saved@}% + \iftabu@negcoef + \let\tabu@wddef \relax \let\tabu@ \tabu@savewd \edef\tabu@savewd{\tabu@Xcoefs}% + \toks0\expandafter{\the\toks\expandafter0\tabu@savewd}\fi + \toks1\expandafter{\tabu@savedpream}% + \toks2\expandafter{\tabu@savedpreamble}% + \let\@preamble \relax + \let\tabu@savedpream \relax \let\tabu@savedparams \relax + \edef\tabu@preamble{% + \def\noexpand\tabu@aligndefault{\tabu@align}% + \def\tabu@savedparams {\noexpand\the\toks0}% + \def\tabu@savedpream {\noexpand\the\toks1}}% + \edef\tabu@usetabu{% + \def\@preamble {\noexpand\the\toks2}% + \tabu@target \the\tabu@target \relax + \tabucolX \the\tabucolX \relax + \tabu@nbcols \the\tabu@nbcols \relax + \def\noexpand\tabu@aligndefault{\tabu@align}% + \def\tabu@savedparams {\noexpand\the\toks0}% + \def\tabu@savedpream {\noexpand\the\toks1}}% + \let\tabu@aligndefault \relax \let\@sharp \relax + \edef\@tempa{\noexpand\tabu@s@ved + {\tabu@usetabu} + {\tabu@preamble} + {\the\toks1}}\@tempa + \tabu@message@save +}% \tabu@save +\long\def\tabu@s@ved #1#2#3{% + \def\tabu@usetabu{#1}% + \expandafter\gdef\csname tabu@saved@\tabu@temp\endcsname ##1{% + \ifodd ##1% \usetabu + \tabu@measuringfalse \tabu@spreadfalse % Just in case... + \gdef\tabu@usetabu {% + \ifdim \tabu@target>\z@ \tabu@warn@usetabu \fi + \global\let\tabu@usetabu \@undefined + \def\@halignto {to\tabu@target}% + #1% + \ifx \tabu@align\tabu@aligndefault@text + \ifnum \tabu@nested=\z@ + \let\tabu@align \tabu@aligndefault \fi\fi}% + \else % \preamble + \gdef\tabu@preamble {% + \global\let\tabu@preamble \@undefined + #2% + \ifx \tabu@align\tabu@aligndefault@text + \ifnum \tabu@nested=\z@ + \let\tabu@align \tabu@aligndefault \fi\fi}% + \fi + #3}% +}% \tabu@s@ved +\def\tabu@aligndefault@text {\tabu@aligndefault}% +\def\tabu@warn@usetabu {\PackageWarning{tabu} + {Specifying a target with \string\usetabu\space is useless + \MessageBreak The target cannot be changed!}} +\def\tabu@savewd #1#2{\ifdim #2\p@<\z@ \tabu@wddef{#1}{\tabu@wd{#1}}\fi} +\def\tabu@savewarn#1#2{\PackageInfo{tabu} + {User-name `#1' already used for \string\savetabu + \MessageBreak #2}}% +\def\tabu@saveerr#1{\PackageError{tabu} + {User-name `#1' is unknown for \string\usetabu + \MessageBreak I cannot restore an unknown preamble!}\@ehd} +%% \rowfont --------------------------------------------------------- +\newskip \tabu@cellskip +\def\tabu@rowfont{\ifdim \baselineskip=\z@\noalign\fi + {\ifnum0=`}\fi \tabu@row@font} +\newcommand*\tabu@row@font[2][]{% + \ifnum7=\currentgrouptype + \global\let\tabu@@cellleft \tabu@cellleft + \global\let\tabu@@cellright \tabu@cellright + \global\let\tabu@@celllalign \tabu@celllalign + \global\let\tabu@@cellralign \tabu@cellralign + \global\let\tabu@@rowfontreset\tabu@rowfontreset + \fi + \global\let\tabu@rowfontreset \tabu@rowfont@reset + \expandafter\gdef\expandafter\tabu@cellleft\expandafter{\tabu@cellleft #2}% + \ifcsname tabu@cell@#1\endcsname % row alignment + \csname tabu@cell@#1\endcsname \fi + \ifnum0=`{\fi}% end of group / noalign group +}% \rowfont +\def\tabu@ifcolorleavevmode #1{\let\color \tabu@leavevmodecolor #1\let\color\tabu@color}% +\def\tabu@rowfont@reset{% + \global\let\tabu@rowfontreset \tabu@@rowfontreset + \global\let\tabu@cellleft \tabu@@cellleft + \global\let\tabu@cellright \tabu@@cellright + \global\let\tabu@cellfont \@empty + \global\let\tabu@celllalign \tabu@@celllalign + \global\let\tabu@cellralign \tabu@@cellralign +}% \tabu@@rowfontreset +\let\tabu@rowfontreset \@empty % overwritten \AtBeginDocument if colortbl +%% \tabu@prepnext@tok ----------------------------------------------- +\newif \iftabu@cellright +\def\tabu@prepnext@tok{% + \ifnum \count@<\z@ % + \@tempcnta \@M % + \tabu@nbcols\z@ + \let\tabu@fornoopORI \@fornoop + \tabu@cellrightfalse + \else + \ifcase \numexpr \count@-\@tempcnta \relax % (case 0): prev. token is left + \advance \tabu@nbcols \@ne + \iftabu@cellright % before-previous token is right and is finished + \tabu@cellrightfalse % + \tabu@righttok + \fi + \tabu@lefttok + \or % (case 1) previous token is right + \tabu@cellrighttrue \let\@fornoop \tabu@lastnoop + \else % special column: do not change the token + \iftabu@cellright % before-previous token is right + \tabu@cellrightfalse + \tabu@righttok + \fi + \fi % \ifcase + \fi + \tabu@prepnext@tokORI +}% \tabu@prepnext@tok +\long\def\tabu@lastnoop#1\@@#2#3{\tabu@lastn@@p #2\@nextchar \in@\in@@} +\def\tabu@lastn@@p #1\@nextchar #2#3\in@@{% + \ifx \in@#2\else + \let\@fornoop \tabu@fornoopORI + \xdef\tabu@mkpreambuffer{\tabu@nbcols\the\tabu@nbcols \tabu@mkpreambuffer}% + \toks0\expandafter{\expandafter\tabu@everyrowtrue \the\toks0}% + \expandafter\prepnext@tok + \fi +}% \tabu@lastnoop +\def\tabu@righttok{% + \advance \count@ \m@ne + \toks\count@\expandafter {\the\toks\count@ \tabu@cellright \tabu@cellralign}% + \advance \count@ \@ne +}% \tabu@righttok +\def\tabu@lefttok{\toks\count@\expandafter{\expandafter\tabu@celllalign + \the\toks\count@ \tabu@cellleft}% after because of $ +}% \tabu@lefttok +%% Neutralisation of glues ------------------------------------------ +\let\tabu@cellleft \@empty +\let\tabu@cellright \@empty +\tabu@celllalign@def{\tabu@cellleft}% +\let\tabu@cellralign \@empty +\def\tabu@cell@align #1#2#3{% + \let\tabu@maybesiunitx \toks@ \tabu@celllalign + \global \expandafter \tabu@celllalign@def \expandafter {\the\toks@ #1}% + \toks@\expandafter{\tabu@cellralign #2}% + \xdef\tabu@cellralign{\the\toks@}% + \toks@\expandafter{\tabu@cellleft #3}% + \xdef\tabu@cellleft{\the\toks@}% +}% \tabu@cell@align +\def\tabu@cell@l{% force alignment to left + \tabu@cell@align + {\tabu@removehfil \raggedright \tabu@cellleft}% left + {\tabu@flush1\tabu@ignorehfil}% right + \raggedright +}% \tabu@cell@l +\def\tabu@cell@c{% force alignment to center + \tabu@cell@align + {\tabu@removehfil \centering \tabu@flush{.5}\tabu@cellleft} + {\tabu@flush{.5}\tabu@ignorehfil} + \centering +}% \tabu@cell@c +\def\tabu@cell@r{% force alignment to right + \tabu@cell@align + {\tabu@removehfil \raggedleft \tabu@flush1\tabu@cellleft} + \tabu@ignorehfil + \raggedleft +}% \tabu@cell@r +\def\tabu@cell@j{% force justification (for p, m, b columns) + \tabu@cell@align + {\tabu@justify\tabu@cellleft} + {} + \tabu@justify +}% \tabu@cell@j +\def\tabu@justify{% + \leftskip\z@skip \@rightskip\leftskip \rightskip\@rightskip + \parfillskip\@flushglue +}% \tabu@justify +%% ragged2e settings +\def\tabu@cell@L{% force alignment to left (ragged2e) + \tabu@cell@align + {\tabu@removehfil \RaggedRight \tabu@cellleft} + {\tabu@flush 1\tabu@ignorehfil} + \RaggedRight +}% \tabu@cell@L +\def\tabu@cell@C{% force alignment to center (ragged2e) + \tabu@cell@align + {\tabu@removehfil \Centering \tabu@flush{.5}\tabu@cellleft} + {\tabu@flush{.5}\tabu@ignorehfil} + \Centering +}% \tabu@cell@C +\def\tabu@cell@R{% force alignment to right (ragged2e) + \tabu@cell@align + {\tabu@removehfil \RaggedLeft \tabu@flush 1\tabu@cellleft} + \tabu@ignorehfil + \RaggedLeft +}% \tabu@cell@R +\def\tabu@cell@J{% force justification (ragged2e) + \tabu@cell@align + {\justifying \tabu@cellleft} + {} + \justifying +}% \tabu@cell@J +\def\tabu@flush#1{% + \iftabu@colortbl % colortbl uses \hfill rather than \hfil + \hskip \ifnum13<\currentgrouptype \stretch{#1}% + \else \ifdim#1pt<\p@ \tabu@cellskip + \else \stretch{#1} + \fi\fi \relax + \else % array.sty + \ifnum 13<\currentgrouptype + \hfil \hskip1sp \relax \fi + \fi +}% \tabu@flush +\let\tabu@hfil \hfil +\let\tabu@hfill \hfill +\let\tabu@hskip \hskip +\def\tabu@removehfil{% + \iftabu@colortbl + \unkern \tabu@cellskip =\lastskip + \ifnum\gluestretchorder\tabu@cellskip =\tw@ \hskip-\tabu@cellskip + \else \tabu@cellskip \z@skip + \fi + \else + \ifdim\lastskip=1sp\unskip\fi + \ifnum\gluestretchorder\lastskip =\@ne + \hfilneg % \hfilneg for array.sty but not for colortbl... + \fi + \fi +}% \tabu@removehfil +\def\tabu@ignorehfil{\aftergroup \tabu@nohfil} +\def\tabu@nohfil{% \hfil -> do nothing + restore original \hfil + \def\hfil{\let\hfil \tabu@hfil}% local to (alignment template) group +}% \tabu@nohfil +\def\tabu@colortblalignments {% if colortbl + \def\tabu@nohfil{% + \def\hfil {\let\hfil \tabu@hfil}% local to (alignment template) group + \def\hfill {\let\hfill \tabu@hfill}% (colortbl uses \hfill) pfff... + \def\hskip ####1\relax{\let\hskip \tabu@hskip}}% local +}% \tabu@colortblalignments +%% Taking care of footnotes and hyperfootnotes ---------------------- +\long\def\tabu@footnotetext #1{% + \edef\@tempa{\the\tabu@footnotes + \noexpand\footnotetext [\the\csname c@\@mpfn\endcsname]}% + \global\tabu@footnotes\expandafter{\@tempa {#1}}}% +\long\def\tabu@xfootnotetext [#1]#2{% + \global\tabu@footnotes\expandafter{\the\tabu@footnotes + \footnotetext [{#1}]{#2}}} +\let\tabu@xfootnote \@xfootnote +\long\def\tabu@Hy@ftntext{\tabu@Hy@ftntxt {\the \c@footnote }} +\long\def\tabu@Hy@xfootnote [#1]{% + \begingroup + \value\@mpfn #1\relax + \protected@xdef \@thefnmark {\thempfn}% + \endgroup + \@footnotemark \tabu@Hy@ftntxt {#1}% +}% \tabu@Hy@xfootnote +\long\def\tabu@Hy@ftntxt #1#2{% + \edef\@tempa{% + \the\tabu@footnotes + \begingroup + \value\@mpfn #1\relax + \noexpand\protected@xdef\noexpand\@thefnmark {\noexpand\thempfn}% + \expandafter \noexpand \expandafter + \tabu@Hy@footnotetext \expandafter{\Hy@footnote@currentHref}% + }% + \global\tabu@footnotes\expandafter{\@tempa {#2}% + \endgroup}% +}% \tabu@Hy@ftntxt +\long\def\tabu@Hy@footnotetext #1#2{% + \H@@footnotetext{% + \ifHy@nesting + \hyper@@anchor {#1}{#2}% + \else + \Hy@raisedlink{% + \hyper@@anchor {#1}{\relax}% + }% + \def\@currentHref {#1}% + \let\@currentlabelname \@empty + #2% + \fi + }% +}% \tabu@Hy@footnotetext +%% No need for \arraybackslash ! ------------------------------------ +\def\tabu@latextwoe {% +\def\tabu@temp##1##2##3{{\toks@\expandafter{##2##3}\xdef##1{\the\toks@}}} +\tabu@temp \tabu@centering \centering \arraybackslash +\tabu@temp \tabu@raggedleft \raggedleft \arraybackslash +\tabu@temp \tabu@raggedright \raggedright \arraybackslash +}% \tabu@latextwoe +\def\tabu@raggedtwoe {% +\def\tabu@temp ##1##2##3{{\toks@\expandafter{##2##3}\xdef##1{\the\toks@}}} +\tabu@temp \tabu@Centering \Centering \arraybackslash +\tabu@temp \tabu@RaggedLeft \RaggedLeft \arraybackslash +\tabu@temp \tabu@RaggedRight \RaggedRight \arraybackslash +\tabu@temp \tabu@justifying \justifying \arraybackslash +}% \tabu@raggedtwoe +\def\tabu@normalcrbackslash{\let\\\@normalcr} +\def\tabu@trivlist{\expandafter\def\expandafter\@trivlist\expandafter{% + \expandafter\tabu@normalcrbackslash \@trivlist}} +%% Utilities: \fbox \fcolorbox and \tabudecimal ------------------- +\def\tabu@fbox {\leavevmode\afterassignment\tabu@beginfbox \setbox\@tempboxa\hbox} +\def\tabu@beginfbox {\bgroup \kern\fboxsep + \bgroup\aftergroup\tabu@endfbox} +\def\tabu@endfbox {\kern\fboxsep\egroup\egroup + \@frameb@x\relax} +\def\tabu@color@b@x #1#2{\leavevmode \bgroup + \def\tabu@docolor@b@x{#1{#2\color@block{\wd\z@}{\ht\z@}{\dp\z@}\box\z@}}% + \afterassignment\tabu@begincolor@b@x \setbox\z@ \hbox +}% \tabu@color@b@x +\def\tabu@begincolor@b@x {\kern\fboxsep \bgroup + \aftergroup\tabu@endcolor@b@x \set@color} +\def\tabu@endcolor@b@x {\kern\fboxsep \egroup + \dimen@\ht\z@ \advance\dimen@ \fboxsep \ht\z@ \dimen@ + \dimen@\dp\z@ \advance\dimen@ \fboxsep \dp\z@ \dimen@ + \tabu@docolor@b@x \egroup +}% \tabu@endcolor@b@x +%% Corrections (arydshln, delarray, colortbl) ----------------------- +\def\tabu@fix@arrayright {%% \@arrayright is missing from \endarray + \iftabu@colortbl + \ifdefined\adl@array % + \def\tabu@endarray{% + \adl@endarray \egroup \adl@arrayrestore \CT@end \egroup % + \@arrayright % + \gdef\@preamble{}}% + \else % + \def\tabu@endarray{% + \crcr \egroup \egroup % + \@arrayright % + \gdef\@preamble{}\CT@end}% + \fi + \else + \ifdefined\adl@array % + \def\tabu@endarray{% + \adl@endarray \egroup \adl@arrayrestore \egroup % + \@arrayright % + \gdef\@preamble{}}% + \else % + \PackageWarning{tabu} + {\string\@arrayright\space is missing from the + \MessageBreak definition of \string\endarray. + \MessageBreak Compatibility with delarray.sty is broken.}% + \fi\fi +}% \tabu@fix@arrayright +\def\tabu@adl@xarraydashrule #1#2#3{% + \ifnum\@lastchclass=\adl@class@start\else + \ifnum\@lastchclass=\@ne\else + \ifnum\@lastchclass=5 \else % @-arg (class 5) and !-arg (class 1) + \adl@leftrulefalse \fi\fi % must be treated the same + \fi + \ifadl@zwvrule\else \ifadl@inactive\else + \@addtopreamble{\vrule\@width\arrayrulewidth + \@height\z@ \@depth\z@}\fi \fi + \ifadl@leftrule + \@addtopreamble{\adl@vlineL{\CT@arc@}{\adl@dashgapcolor}% + {\number#1}#3}% + \else \@addtopreamble{\adl@vlineR{\CT@arc@}{\adl@dashgapcolor}% + {\number#2}#3} + \fi +}% \tabu@adl@xarraydashrule +\def\tabu@adl@act@endpbox {% + \unskip \ifhmode \nobreak \fi \@finalstrut \@arstrutbox + \egroup \egroup + \adl@colhtdp \box\adl@box \hfil +}% \tabu@adl@act@endpbox +\def\tabu@adl@fix {% + \let\adl@xarraydashrule \tabu@adl@xarraydashrule % arydshln + \let\adl@act@endpbox \tabu@adl@act@endpbox % arydshln + \let\adl@act@@endpbox \tabu@adl@act@endpbox % arydshln + \let\@preamerror \@preamerr % arydshln +}% \tabu@adl@fix +%% Correction for longtable' \@startbox definition ------------------ +%% => \everypar is ``missing'' : TeX should be in vertical mode +\def\tabu@LT@startpbox #1{% + \bgroup + \let\@footnotetext\LT@p@ftntext + \setlength\hsize{#1}% + \@arrayparboxrestore + \everypar{% + \vrule \@height \ht\@arstrutbox \@width \z@ + \everypar{}}% +}% \tabu@LT@startpbox +%% \tracingtabu and the package options ------------------ +\DeclareOption{delarray}{\AtEndOfPackage{\RequirePackage{delarray}}} +\DeclareOption{linegoal}{% + \AtEndOfPackage{% + \RequirePackage{linegoal}[2010/12/07]% + \let\tabudefaulttarget \linegoal% \linegoal is \linewidth if not pdfTeX +}} +\DeclareOption{scantokens}{\tabuscantokenstrue} +\DeclareOption{debugshow}{\AtEndOfPackage{\tracingtabu=\tw@}} +\def\tracingtabu {\begingroup\@ifnextchar=% + {\afterassignment\tabu@tracing\count@} + {\afterassignment\tabu@tracing\count@1\relax}} +\def\tabu@tracing{\expandafter\endgroup + \expandafter\tabu@tr@cing \the\count@ \relax +}% \tabu@tracing +\def\tabu@tr@cing #1\relax {% + \ifnum#1>\thr@@ \let\tabu@tracinglines\message + \else \let\tabu@tracinglines\@gobble + \fi + \ifnum#1>\tw@ \let\tabu@DBG \tabu@@DBG + \def\tabu@mkarstrut {\tabu@DBG@arstrut}% + \tabustrutrule 1.5\p@ + \else \let\tabu@DBG \@gobble + \def\tabu@mkarstrut {\tabu@arstrut}% + \tabustrutrule \z@ + \fi + \ifnum#1>\@ne \let\tabu@debug \message + \else \let\tabu@debug \@gobble + \fi + \ifnum#1>\z@ + \let\tabu@message \message + \let\tabu@tracing@save \tabu@message@save + \let\tabu@starttimer \tabu@pdftimer + \else + \let\tabu@message \@gobble + \let\tabu@tracing@save \@gobble + \let\tabu@starttimer \relax + \fi +}% \tabu@tr@cing +%% Setup \AtBeginDocument +\AtBeginDocument{\tabu@AtBeginDocument} +\def\tabu@AtBeginDocument{\let\tabu@AtBeginDocument \@undefined + \ifdefined\arrayrulecolor \tabu@colortbltrue % + \tabu@colortblalignments % different glues are used + \else \tabu@colortblfalse \fi + \ifdefined\CT@arc@ \else \let\CT@arc@ \relax \fi + \ifdefined\CT@drsc@\else \let\CT@drsc@ \relax \fi + \let\tabu@arc@L \CT@arc@ \let\tabu@drsc@L \CT@drsc@ + \ifodd 1\ifcsname siunitx_table_collect_begin:Nn\endcsname % + \expandafter\ifx + \csname siunitx_table_collect_begin:Nn\endcsname\relax 0\fi\fi\relax + \tabu@siunitxtrue + \else \let\tabu@maybesiunitx \@firstofone % + \let\tabu@siunitx \tabu@nosiunitx + \tabu@siunitxfalse + \fi + \ifdefined\adl@array % + \else \let\tabu@adl@fix \relax + \let\tabu@adl@endtrial \@empty \fi + \ifdefined\longtable % + \else \let\longtabu \tabu@nolongtabu \fi + \ifdefined\cellspacetoplimit \tabu@warn@cellspace\fi + \csname\ifcsname ifHy@hyperfootnotes\endcsname % + ifHy@hyperfootnotes\else iffalse\fi\endcsname + \let\tabu@footnotetext \tabu@Hy@ftntext + \let\tabu@xfootnote \tabu@Hy@xfootnote \fi + \ifdefined\FV@DefineCheckEnd% + \tabu@fancyvrb \fi + \ifdefined\color % + \let\tabu@color \color + \def\tabu@leavevmodecolor ##1{% + \def\tabu@leavevmodecolor {\leavevmode ##1}% + }\expandafter\tabu@leavevmodecolor\expandafter{\color}% + \else + \let\tabu@color \tabu@nocolor + \let\tabu@leavevmodecolor \@firstofone \fi + \tabu@latextwoe + \ifdefined\@raggedtwoe@everyselectfont % + \tabu@raggedtwoe + \else + \let\tabu@cell@L \tabu@cell@l + \let\tabu@cell@R \tabu@cell@r + \let\tabu@cell@C \tabu@cell@c + \let\tabu@cell@J \tabu@cell@j \fi + \expandafter\in@ \expandafter\@arrayright \expandafter{\endarray}% + \ifin@ \let\tabu@endarray \endarray + \else \tabu@fix@arrayright \fi% + \everyrow{}% +}% \tabu@AtBeginDocument +\def\tabu@warn@cellspace{% + \PackageWarning{tabu}{% + Package cellspace has some limitations + \MessageBreak And redefines some macros of array.sty. + \MessageBreak Please use \string\tabulinesep\space to control + \MessageBreak vertical spacing of lines inside tabu environment}% +}% \tabu@warn@cellspace +%% tabu Package initialisation +\tabuscantokensfalse +\let\tabu@arc@G \relax +\let\tabu@drsc@G \relax +\let\tabu@evr@G \@empty +\let\tabu@rc@G \@empty +\def\tabu@ls@G {\tabu@linestyle@}% +\let\tabu@@rowfontreset \@empty % +\let\tabu@@celllalign \@empty +\let\tabu@@cellralign \@empty +\let\tabu@@cellleft \@empty +\let\tabu@@cellright \@empty +\def\tabu@naturalXmin {\z@} +\def\tabu@naturalXmax {\z@} +\let\tabu@rowfontreset \@empty +\def\tabulineon {4pt}\let\tabulineoff \tabulineon +\tabu@everyrowtrue +\ifdefined\pdfelapsedtime % + \def\tabu@pdftimer {\xdef\tabu@starttime{\the\pdfelapsedtime}}% +\else \let\tabu@pdftimer \relax \let\tabu@message@etime \relax +\fi +\tracingtabu=\z@ +\newtabulinestyle {=\maxdimen}% creates the 'factory' settings \tabu@linestyle@ +\tabulinestyle{} +\taburowcolors{} +\let\tabudefaulttarget \linewidth +\ProcessOptions* % \ProcessOptions* is quicker ! +\endinput +%% +%% End of file `tabu.sty'. diff --git a/esp32_BNO08x_banner.png b/esp32_BNO08x_banner.png new file mode 100644 index 0000000..d754d33 Binary files /dev/null and b/esp32_BNO08x_banner.png differ diff --git a/esp32_BNO08x_wiring.png b/esp32_BNO08x_wiring.png new file mode 100644 index 0000000..f92d5dd Binary files /dev/null and b/esp32_BNO08x_wiring.png differ