diff --git a/components/bldc_driver/include/bldc_driver.hpp b/components/bldc_driver/include/bldc_driver.hpp index a465fbbc0..59daa9a63 100644 --- a/components/bldc_driver/include/bldc_driver.hpp +++ b/components/bldc_driver/include/bldc_driver.hpp @@ -68,13 +68,16 @@ class BldcDriver { * force level. */ void enable() { - logger_.info("Enabling"); - for (auto g : generators_) { - // remove force level, and don't hold it - mcpwm_generator_set_force_level(g, -1, false); + if (enabled_) { + return; } - gpio_set_level((gpio_num_t)gpio_en_, 1); + logger_.info("Enabling"); + mcpwm_timer_enable(timer_); + mcpwm_timer_start_stop(timer_, MCPWM_TIMER_START_NO_STOP); enabled_ = true; + if (gpio_en_ >= 0) { + gpio_set_level((gpio_num_t)gpio_en_, 1); + } } /** @@ -83,13 +86,13 @@ class BldcDriver { * low. */ void disable() { - logger_.info("Disabling"); - for (auto g : generators_) { - // set force level to 0 (gate off), and hold it - mcpwm_generator_set_force_level(g, 0, true); + if (!enabled_) { + return; } + logger_.info("Disabling"); + mcpwm_timer_start_stop(timer_, MCPWM_TIMER_STOP_FULL); + mcpwm_timer_disable(timer_); enabled_ = false; - std::lock_guard lock(en_mutex_); if (gpio_en_ >= 0) { gpio_set_level((gpio_num_t)gpio_en_, 0); } @@ -107,7 +110,6 @@ class BldcDriver { * @return True if the driver is faulted, false otherwise. */ bool is_faulted() { - std::lock_guard lock(fault_mutex_); if (gpio_fault_ < 0) { return false; } @@ -174,14 +176,6 @@ class BldcDriver { uint32_t b_ticks = (uint32_t)(duty_b * (float)(TICKS_PER_PERIOD / 2)); uint32_t c_ticks = (uint32_t)(duty_c * (float)(TICKS_PER_PERIOD / 2)); - static int log_counter = 0; - // log_counter++; - if (log_counter == 500) { - fmt::print("PWM (abc): {:.3f},{:.3f},{:.3f}\n", duty_a, duty_b, duty_c); - fmt::print("Ticks (abc): {},{},{}\n", a_ticks, b_ticks, c_ticks); - log_counter = 0; - } - mcpwm_comparator_set_compare_value(comparators_[0], a_ticks); mcpwm_comparator_set_compare_value(comparators_[1], b_ticks); mcpwm_comparator_set_compare_value(comparators_[2], c_ticks); @@ -223,16 +217,10 @@ class BldcDriver { configure_operators(); configure_comparators(); configure_generators(); - // start timer - logger_.info("starting timer"); - mcpwm_timer_enable(timer_); - mcpwm_timer_start_stop(timer_, MCPWM_TIMER_START_NO_STOP); - // enable enable(); } void configure_enable_gpio() { - std::lock_guard lock(en_mutex_); if (gpio_en_ < 0) { return; } @@ -246,7 +234,6 @@ class BldcDriver { } void configure_fault_gpio() { - std::lock_guard lock(fault_mutex_); if (gpio_fault_ < 0) { return; } @@ -347,9 +334,7 @@ class BldcDriver { gpio_num_t gpio_bl_; gpio_num_t gpio_ch_; gpio_num_t gpio_cl_; - std::mutex en_mutex_; int gpio_en_; - std::mutex fault_mutex_; int gpio_fault_; std::atomic power_supply_voltage_; std::atomic limit_voltage_; diff --git a/components/bldc_haptics/include/bldc_haptics.hpp b/components/bldc_haptics/include/bldc_haptics.hpp index 3fc76963b..c24fbebca 100644 --- a/components/bldc_haptics/include/bldc_haptics.hpp +++ b/components/bldc_haptics/include/bldc_haptics.hpp @@ -141,11 +141,42 @@ template class BldcHaptics { .log_level = Logger::Verbosity::WARN}); } + /// @brief Destructor for the haptic motor + /// @note This will stop the motor if it is running + ~BldcHaptics() { + // stop the motor if it is running + stop(); + } + + /// @brief Check if the haptic motor is running + /// @return True if the haptic motor is running, false otherwise + bool is_running() const { return motor_task_->is_running(); } + /// @brief Start the haptic motor - void start() { motor_task_->start(); } + void start() { + // enable the motor + { + std::unique_lock lk(motor_mutex_); + motor_.get().enable(); + } + if (is_running()) { + return; + } + motor_task_->start(); + } /// @brief Stop the haptic motor - void stop() { motor_task_->stop(); } + void stop() { + // disable the motor + { + std::unique_lock lk(motor_mutex_); + motor_.get().disable(); + } + if (!is_running()) { + return; + } + motor_task_->stop(); + } /// @brief Get the current position of the haptic motor /// @return Current position of the haptic motor diff --git a/components/bldc_motor/include/bldc_motor.hpp b/components/bldc_motor/include/bldc_motor.hpp index 5c6461d04..016173be5 100644 --- a/components/bldc_motor/include/bldc_motor.hpp +++ b/components/bldc_motor/include/bldc_motor.hpp @@ -169,8 +169,12 @@ class BldcMotor { // finish the rest of init init(); + // enable the motor for foc initialization + enable(); // then initialize the foc (calibration etc.) init_foc(config.zero_electric_offset, config.sensor_direction); + // disable the motor to put it back into a safe state + disable(); } /** @@ -179,12 +183,18 @@ class BldcMotor { */ ~BldcMotor() { disable(); } + /** + * @brief Check if the motor is enabled. + * @return True if the motor is enabled, false otherwise. + */ + bool is_enabled() const { return enabled_; } + /** * @brief Enable the controller and driver output. */ void enable() { - enabled_ = true; driver_->enable(); + enabled_ = true; } /** @@ -211,6 +221,10 @@ class BldcMotor { * @param el_angle current electrical angle of the motor */ void set_phase_voltage(float uq, float ud, float el_angle) { + if (!enabled_) { + return; + } + float center; int sector; float _ca, _sa; @@ -642,11 +656,7 @@ class BldcMotor { } protected: - void init() { - status_ = Status::INITIALIZING; - enable(); - status_ = Status::UNCALIBRATED; - } + void init() { status_ = Status::UNCALIBRATED; } void init_foc(float zero_electric_offset = 0, detail::SensorDirection sensor_direction = detail::SensorDirection::CLOCKWISE) { diff --git a/components/cli/include/cli.hpp b/components/cli/include/cli.hpp index 0fc4e54e6..16c184368 100644 --- a/components/cli/include/cli.hpp +++ b/components/cli/include/cli.hpp @@ -68,27 +68,26 @@ class Cli : private cli::CliSession { * correct while APB frequency is changing in light sleep mode. */ const uart_config_t uart_config = { - .baud_rate = CONFIG_ESP_CONSOLE_UART_BAUDRATE, - .data_bits = UART_DATA_8_BITS, - .parity = UART_PARITY_DISABLE, - .stop_bits = UART_STOP_BITS_1, + .baud_rate = CONFIG_ESP_CONSOLE_UART_BAUDRATE, + .data_bits = UART_DATA_8_BITS, + .parity = UART_PARITY_DISABLE, + .stop_bits = UART_STOP_BITS_1, #if CONFIG_IDF_TARGET_ESP32 || CONFIG_IDF_TARGET_ESP32S2 - .source_clk = UART_SCLK_REF_TICK, + .source_clk = UART_SCLK_REF_TICK, #else - .source_clk = UART_SCLK_XTAL, + .source_clk = UART_SCLK_XTAL, #endif }; /* Install UART driver for interrupt-driven reads and writes */ - ESP_ERROR_CHECK( uart_driver_install(CONFIG_ESP_CONSOLE_UART_NUM, - 256, 0, 0, NULL, 0) ); - ESP_ERROR_CHECK( uart_param_config(CONFIG_ESP_CONSOLE_UART_NUM, &uart_config) ); + ESP_ERROR_CHECK(uart_driver_install(CONFIG_ESP_CONSOLE_UART_NUM, 256, 0, 0, NULL, 0)); + ESP_ERROR_CHECK(uart_param_config(CONFIG_ESP_CONSOLE_UART_NUM, &uart_config)); /* Tell VFS to use UART driver */ esp_vfs_dev_uart_use_driver(CONFIG_ESP_CONSOLE_UART_NUM); /* Minicom, screen, idf_monitor send CR when ENTER key is pressed */ esp_vfs_dev_uart_port_set_rx_line_endings(CONFIG_ESP_CONSOLE_UART_NUM, ESP_LINE_ENDINGS_CR); /* Move the caret to the beginning of the next line on '\n' */ esp_vfs_dev_uart_port_set_tx_line_endings(CONFIG_ESP_CONSOLE_UART_NUM, ESP_LINE_ENDINGS_CRLF); -#else // CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG +#else // CONFIG_ESP_CONSOLE_USB_SERIAL_JTAG usb_serial_jtag_driver_config_t cfg = USB_SERIAL_JTAG_DRIVER_CONFIG_DEFAULT(); usb_serial_jtag_driver_install(&cfg); esp_vfs_usb_serial_jtag_use_driver(); diff --git a/components/rtsp/example/main/jpeg_image.hpp b/components/rtsp/example/main/jpeg_image.hpp index e3169ad73..ab5eb5423 100644 --- a/components/rtsp/example/main/jpeg_image.hpp +++ b/components/rtsp/example/main/jpeg_image.hpp @@ -1,3 +1,174 @@ #pragma once -static const char jpeg_data[] = {0xff, 0xd8, 0xff, 0xe0, 0x00, 0x10, 0x4a, 0x46, 0x49, 0x46, 0x00, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0xff, 0xdb, 0x00, 0x43, 0x00, 0x0f, 0x0a, 0x0b, 0x0d, 0x0b, 0x09, 0x0f, 0x0d, 0x0c, 0x0d, 0x11, 0x10, 0x0f, 0x12, 0x17, 0x26, 0x18, 0x17, 0x15, 0x15, 0x17, 0x2e, 0x21, 0x23, 0x1b, 0x26, 0x36, 0x30, 0x39, 0x38, 0x35, 0x30, 0x35, 0x34, 0x3c, 0x44, 0x56, 0x49, 0x3c, 0x40, 0x52, 0x41, 0x34, 0x35, 0x4b, 0x66, 0x4c, 0x52, 0x59, 0x5c, 0x61, 0x62, 0x61, 0x3a, 0x48, 0x6a, 0x71, 0x69, 0x5e, 0x71, 0x56, 0x5f, 0x61, 0x5d, 0xff, 0xdb, 0x00, 0x43, 0x01, 0x10, 0x11, 0x11, 0x17, 0x14, 0x17, 0x2c, 0x18, 0x18, 0x2c, 0x5d, 0x3e, 0x35, 0x3e, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0xff, 0xc4, 0x00, 0x1f, 0x00, 0x00, 0x01, 0x05, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x0a, 0x0b, 0xff, 0xc4, 0x00, 0xb5, 0x10, 0x00, 0x02, 0x01, 0x03, 0x03, 0x02, 0x04, 0x03, 0x05, 0x05, 0x04, 0x04, 0x00, 0x00, 0x01, 0x7d, 0x01, 0x02, 0x03, 0x00, 0x04, 0x11, 0x05, 0x12, 0x21, 0x31, 0x41, 0x06, 0x13, 0x51, 0x61, 0x07, 0x22, 0x71, 0x14, 0x32, 0x81, 0x91, 0xa1, 0x08, 0x23, 0x42, 0xb1, 0xc1, 0x15, 0x52, 0xd1, 0xf0, 0x24, 0x33, 0x62, 0x72, 0x82, 0x09, 0x0a, 0x16, 0x17, 0x18, 0x19, 0x1a, 0x25, 0x26, 0x27, 0x28, 0x29, 0x2a, 0x34, 0x35, 0x36, 0x37, 0x38, 0x39, 0x3a, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x4a, 0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x63, 0x64, 0x65, 0x66, 0x67, 0x68, 0x69, 0x6a, 0x73, 0x74, 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a, 0x83, 0x84, 0x85, 0x86, 0x87, 0x88, 0x89, 0x8a, 0x92, 0x93, 0x94, 0x95, 0x96, 0x97, 0x98, 0x99, 0x9a, 0xa2, 0xa3, 0xa4, 0xa5, 0xa6, 0xa7, 0xa8, 0xa9, 0xaa, 0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba, 0xc2, 0xc3, 0xc4, 0xc5, 0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xd2, 0xd3, 0xd4, 0xd5, 0xd6, 0xd7, 0xd8, 0xd9, 0xda, 0xe1, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7, 0xe8, 0xe9, 0xea, 0xf1, 0xf2, 0xf3, 0xf4, 0xf5, 0xf6, 0xf7, 0xf8, 0xf9, 0xfa, 0xff, 0xc4, 0x00, 0x1f, 0x01, 0x00, 0x03, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x0a, 0x0b, 0xff, 0xc4, 0x00, 0xb5, 0x11, 0x00, 0x02, 0x01, 0x02, 0x04, 0x04, 0x03, 0x04, 0x07, 0x05, 0x04, 0x04, 0x00, 0x01, 0x02, 0x77, 0x00, 0x01, 0x02, 0x03, 0x11, 0x04, 0x05, 0x21, 0x31, 0x06, 0x12, 0x41, 0x51, 0x07, 0x61, 0x71, 0x13, 0x22, 0x32, 0x81, 0x08, 0x14, 0x42, 0x91, 0xa1, 0xb1, 0xc1, 0x09, 0x23, 0x33, 0x52, 0xf0, 0x15, 0x62, 0x72, 0xd1, 0x0a, 0x16, 0x24, 0x34, 0xe1, 0x25, 0xf1, 0x17, 0x18, 0x19, 0x1a, 0x26, 0x27, 0x28, 0x29, 0x2a, 0x35, 0x36, 0x37, 0x38, 0x39, 0x3a, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x4a, 0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x63, 0x64, 0x65, 0x66, 0x67, 0x68, 0x69, 0x6a, 0x73, 0x74, 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a, 0x82, 0x83, 0x84, 0x85, 0x86, 0x87, 0x88, 0x89, 0x8a, 0x92, 0x93, 0x94, 0x95, 0x96, 0x97, 0x98, 0x99, 0x9a, 0xa2, 0xa3, 0xa4, 0xa5, 0xa6, 0xa7, 0xa8, 0xa9, 0xaa, 0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba, 0xc2, 0xc3, 0xc4, 0xc5, 0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xd2, 0xd3, 0xd4, 0xd5, 0xd6, 0xd7, 0xd8, 0xd9, 0xda, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7, 0xe8, 0xe9, 0xea, 0xf2, 0xf3, 0xf4, 0xf5, 0xf6, 0xf7, 0xf8, 0xf9, 0xfa, 0xff, 0xc0, 0x00, 0x11, 0x08, 0x00, 0xf0, 0x01, 0x40, 0x03, 0x01, 0x21, 0x00, 0x02, 0x11, 0x01, 0x03, 0x11, 0x01, 0xff, 0xda, 0x00, 0x0c, 0x03, 0x01, 0x00, 0x02, 0x11, 0x03, 0x11, 0x00, 0x3f, 0x00, 0xe0, 0x29, 0x2a, 0xa6, 0x42, 0x13, 0xbd, 0x0d, 0xd6, 0xa0, 0xa1, 0x28, 0xa0, 0x05, 0xa7, 0x50, 0x03, 0x96, 0xa4, 0x15, 0x22, 0x1f, 0x45, 0x00, 0x2d, 0x21, 0xa9, 0x18, 0x95, 0x22, 0x54, 0xb0, 0x1c, 0x69, 0x86, 0xa4, 0x63, 0x69, 0xb5, 0x42, 0x12, 0x92, 0x98, 0x05, 0x25, 0x30, 0x0a, 0x29, 0x80, 0x51, 0x40, 0x05, 0x14, 0x80, 0x29, 0x29, 0x88, 0x28, 0xa0, 0x02, 0x92, 0x80, 0x0a, 0x28, 0x10, 0x52, 0x53, 0x00, 0xa4, 0xad, 0x2a, 0x09, 0x0d, 0x3d, 0x69, 0x2a, 0x4b, 0x0a, 0x28, 0x01, 0xd4, 0xea, 0x00, 0x78, 0xa7, 0x8a, 0x91, 0x0e, 0xa5, 0xa4, 0x21, 0x69, 0x29, 0x14, 0x25, 0x48, 0xbd, 0x2a, 0x58, 0x01, 0xa6, 0x54, 0x80, 0xd3, 0x49, 0x56, 0x31, 0x29, 0x29, 0x88, 0x4a, 0x29, 0x80, 0x51, 0x40, 0x05, 0x25, 0x00, 0x14, 0xb4, 0x08, 0x29, 0x28, 0x00, 0xa2, 0x80, 0x0a, 0x28, 0x01, 0x28, 0xa0, 0x41, 0x49, 0x4c, 0x00, 0xd3, 0x7b, 0x56, 0xb5, 0x37, 0x12, 0x1b, 0x45, 0x49, 0x61, 0x4b, 0x48, 0x07, 0x53, 0x85, 0x20, 0x1e, 0x29, 0xf5, 0x24, 0x8b, 0x4a, 0x28, 0x01, 0x68, 0xa4, 0x30, 0xa7, 0x76, 0xa8, 0x63, 0x10, 0xd3, 0x68, 0x18, 0xca, 0x4a, 0xa0, 0x12, 0x8a, 0x62, 0x12, 0x8a, 0x00, 0x28, 0xa6, 0x01, 0x45, 0x00, 0x14, 0x94, 0x08, 0x5a, 0x4a, 0x40, 0x14, 0x53, 0x00, 0xa2, 0x80, 0x12, 0x8a, 0x04, 0x14, 0x94, 0x00, 0xa6, 0x90, 0x0c, 0x83, 0x5a, 0xd4, 0xdc, 0x48, 0x8e, 0x8a, 0x45, 0x85, 0x3a, 0x90, 0x0a, 0x29, 0xf4, 0x84, 0x3c, 0x0a, 0x76, 0x2a, 0x44, 0x2d, 0x14, 0x0c, 0x5a, 0x5a, 0x43, 0x0a, 0x7d, 0x43, 0x01, 0xa6, 0x99, 0x40, 0xc4, 0xa6, 0xd5, 0x08, 0x29, 0x29, 0x80, 0x52, 0x50, 0x01, 0x45, 0x30, 0x0a, 0x28, 0x00, 0xa2, 0x90, 0x05, 0x14, 0x00, 0x94, 0x53, 0x10, 0x51, 0x40, 0x09, 0x45, 0x00, 0x14, 0x50, 0x21, 0x1a, 0x97, 0xfe, 0x59, 0x9a, 0xd2, 0x7b, 0x82, 0x22, 0xa2, 0x82, 0x85, 0xa7, 0x52, 0x01, 0xc2, 0x9d, 0x48, 0x43, 0xc5, 0x3c, 0x54, 0x88, 0x28, 0xa0, 0x61, 0x4b, 0xda, 0x90, 0xc2, 0x9d, 0x50, 0xc0, 0x69, 0xa6, 0xd0, 0x31, 0x29, 0x2a, 0x84, 0x25, 0x25, 0x30, 0x0a, 0x28, 0x01, 0x28, 0xa0, 0x02, 0x8a, 0x60, 0x14, 0x50, 0x01, 0x45, 0x02, 0x0a, 0x4a, 0x00, 0x28, 0xa0, 0x04, 0xa2, 0x80, 0x0a, 0x28, 0x10, 0x8d, 0x48, 0x7e, 0xed, 0x69, 0x2d, 0xc1, 0x0c, 0xa2, 0x82, 0x87, 0x52, 0xd2, 0x01, 0xc2, 0xa4, 0x15, 0x22, 0x1c, 0x29, 0xf4, 0x84, 0x2d, 0x26, 0x29, 0x0c, 0x29, 0x09, 0xa0, 0x61, 0x8c, 0x8a, 0x5e, 0x40, 0xe9, 0x52, 0xc6, 0x37, 0x75, 0x25, 0x00, 0x14, 0xda, 0x60, 0x14, 0x94, 0xc4, 0x14, 0x50, 0x01, 0x49, 0x40, 0x05, 0x14, 0xc0, 0x28, 0xa0, 0x02, 0x8a, 0x04, 0x14, 0x94, 0x00, 0x51, 0x40, 0x05, 0x25, 0x00, 0x14, 0x50, 0x21, 0x0d, 0x0d, 0xf7, 0x6a, 0xde, 0xe3, 0x23, 0xa5, 0x14, 0x0c, 0x75, 0x2d, 0x20, 0x1e, 0x29, 0xf4, 0x84, 0x3c, 0x53, 0x85, 0x21, 0x0b, 0x45, 0x20, 0x12, 0x90, 0xa7, 0x34, 0x8a, 0x1c, 0x31, 0x41, 0xa8, 0x18, 0xd3, 0x4c, 0x20, 0x55, 0x00, 0x98, 0xa6, 0x9c, 0xd3, 0x00, 0x1d, 0x28, 0xa6, 0x20, 0xa2, 0x80, 0x0a, 0x28, 0x01, 0x28, 0xa6, 0x01, 0x45, 0x00, 0x14, 0x50, 0x20, 0xa2, 0x90, 0x09, 0x45, 0x30, 0x0a, 0x4a, 0x00, 0x28, 0xa0, 0x42, 0x77, 0xa1, 0xba, 0x55, 0x0c, 0x8e, 0x94, 0x53, 0x18, 0xea, 0x75, 0x20, 0x1e, 0x29, 0xe2, 0x90, 0x87, 0x8a, 0x75, 0x21, 0x05, 0x2d, 0x21, 0x89, 0x45, 0x21, 0x8a, 0x07, 0x14, 0xd2, 0xa2, 0xa0, 0x63, 0x71, 0xef, 0x4d, 0xe6, 0xa8, 0x04, 0xfc, 0x29, 0xac, 0x69, 0x80, 0x0e, 0x94, 0xb4, 0xc0, 0x4a, 0x28, 0x10, 0x51, 0x40, 0x09, 0x45, 0x00, 0x14, 0x53, 0x00, 0xa2, 0x90, 0x82, 0x8a, 0x00, 0x29, 0x29, 0x80, 0x51, 0x40, 0x09, 0x45, 0x02, 0x01, 0xd6, 0xa4, 0x23, 0x72, 0xf6, 0xa6, 0xc0, 0xad, 0x4e, 0x15, 0x45, 0x0e, 0x14, 0xea, 0x42, 0x1e, 0x2a, 0x41, 0x48, 0x43, 0x85, 0x3a, 0xa4, 0x05, 0xa2, 0x81, 0x89, 0x49, 0x52, 0x31, 0xc2, 0x9a, 0x6a, 0x06, 0x36, 0x9b, 0x56, 0x02, 0x53, 0x4f, 0x34, 0xc0, 0x28, 0xa6, 0x02, 0x51, 0x40, 0x82, 0x8a, 0x00, 0x28, 0xa0, 0x04, 0xa2, 0x80, 0x0a, 0x28, 0x00, 0xa2, 0x81, 0x09, 0x45, 0x00, 0x14, 0x94, 0xc0, 0x28, 0xa0, 0x42, 0x53, 0x81, 0x38, 0xa6, 0xc6, 0x46, 0x7a, 0xd2, 0x8a, 0xa1, 0x8e, 0x14, 0xfa, 0x91, 0x0e, 0x15, 0x20, 0xa4, 0x21, 0xf4, 0xb4, 0x80, 0x28, 0xa0, 0x61, 0x49, 0x52, 0x31, 0x69, 0x0d, 0x40, 0xc6, 0x53, 0x6a, 0xc0, 0x4a, 0x4a, 0x60, 0x25, 0x14, 0x00, 0x52, 0x53, 0x10, 0x51, 0x40, 0x05, 0x14, 0x00, 0x94, 0xb4, 0xc0, 0x28, 0xa4, 0x02, 0x51, 0x40, 0x82, 0x92, 0x98, 0x05, 0x14, 0x00, 0x94, 0x50, 0x21, 0x70, 0x36, 0x50, 0xbd, 0x28, 0x28, 0x47, 0x14, 0xd1, 0x54, 0x80, 0x75, 0x3e, 0x90, 0x87, 0x0a, 0x90, 0x52, 0x10, 0xfa, 0x5a, 0x40, 0x2d, 0x25, 0x03, 0x16, 0x92, 0xa4, 0x64, 0xf1, 0xdb, 0x4b, 0x28, 0x6f, 0x2e, 0x36, 0x7d, 0xab, 0xb8, 0xe0, 0x74, 0x15, 0x03, 0x54, 0x0c, 0x8e, 0x9b, 0x54, 0x02, 0x52, 0x55, 0x00, 0x52, 0x50, 0x01, 0x45, 0x31, 0x05, 0x25, 0x00, 0x14, 0x50, 0x01, 0x45, 0x00, 0x14, 0x50, 0x21, 0x28, 0xa0, 0x02, 0x92, 0x80, 0x0a, 0x29, 0x80, 0x52, 0x50, 0x21, 0xfd, 0x56, 0x85, 0xe9, 0x40, 0xc6, 0xc9, 0xd2, 0x99, 0x54, 0x86, 0x2e, 0x69, 0xe1, 0xa8, 0x10, 0xf0, 0x69, 0xf5, 0x22, 0x1d, 0xcd, 0x1c, 0xd2, 0x18, 0xb4, 0xb4, 0x80, 0x5a, 0x3b, 0xd2, 0x19, 0xd0, 0x68, 0x5a, 0x95, 0xbd, 0x95, 0xb5, 0xe9, 0x9b, 0xef, 0x34, 0x78, 0x45, 0xfe, 0xf5, 0x60, 0x48, 0x69, 0x0c, 0x88, 0xd3, 0x69, 0x80, 0x94, 0x94, 0xc0, 0x29, 0x28, 0x00, 0xa2, 0x98, 0x84, 0xa2, 0x80, 0x0a, 0x28, 0x00, 0xa2, 0x80, 0x0a, 0x28, 0x10, 0x52, 0x50, 0x01, 0x49, 0x4c, 0x02, 0x8a, 0x00, 0x29, 0x28, 0x11, 0x20, 0xa2, 0x81, 0x8c, 0x91, 0x87, 0x4a, 0x8c, 0x55, 0x21, 0x8e, 0xa5, 0xa0, 0x43, 0xa9, 0xea, 0x4d, 0x21, 0x12, 0x06, 0xa5, 0xde, 0x2a, 0x40, 0x4d, 0xd4, 0xea, 0x45, 0x0b, 0x45, 0x20, 0x17, 0x34, 0xd2, 0x6a, 0x46, 0x32, 0x92, 0xa8, 0x04, 0xa4, 0xa6, 0x01, 0x49, 0x40, 0x05, 0x14, 0xc0, 0x29, 0x28, 0x10, 0x51, 0x40, 0x05, 0x14, 0x00, 0x51, 0x40, 0x82, 0x92, 0x80, 0x0a, 0x28, 0x01, 0x28, 0xa6, 0x01, 0x49, 0x40, 0x89, 0x29, 0x8e, 0xf8, 0xe9, 0x40, 0xc8, 0xa8, 0xab, 0x18, 0xb4, 0xb4, 0x80, 0x76, 0xea, 0x70, 0x7a, 0x42, 0x1d, 0x9a, 0x75, 0x20, 0x1d, 0x4e, 0xa9, 0x18, 0xb4, 0x52, 0x00, 0xa6, 0xd2, 0x18, 0x94, 0x94, 0xc0, 0x4a, 0x4a, 0x60, 0x14, 0x94, 0x00, 0x51, 0x4c, 0x41, 0x45, 0x00, 0x25, 0x14, 0x00, 0x51, 0x40, 0x05, 0x14, 0x08, 0x29, 0x28, 0x00, 0xa2, 0x80, 0x12, 0x8a, 0x60, 0x14, 0x50, 0x20, 0x76, 0xc5, 0x43, 0x54, 0x8a, 0x0a, 0x5a, 0x60, 0x14, 0xb9, 0xa0, 0x07, 0x66, 0x96, 0x90, 0x0b, 0xc5, 0x38, 0x52, 0x01, 0xf4, 0xea, 0x80, 0x12, 0x9e, 0x29, 0x0c, 0x5a, 0x6d, 0x20, 0x12, 0x92, 0x98, 0x09, 0x45, 0x30, 0x12, 0x8a, 0x00, 0x4a, 0x29, 0x88, 0x28, 0xa0, 0x02, 0x92, 0x80, 0x16, 0x8a, 0x00, 0x29, 0x28, 0x10, 0x51, 0x40, 0x09, 0x45, 0x00, 0x14, 0x94, 0x00, 0x51, 0x4c, 0x44, 0x44, 0xe6, 0x92, 0xac, 0xa1, 0x68, 0xa0, 0x02, 0x96, 0x80, 0x0a, 0x75, 0x20, 0x1e, 0x29, 0xd5, 0x20, 0x3a, 0x8c, 0xd2, 0x18, 0x66, 0x9c, 0xb5, 0x2c, 0x07, 0x52, 0x52, 0x01, 0x29, 0x29, 0x88, 0x4a, 0x4a, 0x60, 0x14, 0x50, 0x02, 0x51, 0x4c, 0x02, 0x8a, 0x00, 0x29, 0x28, 0x01, 0x68, 0xa0, 0x02, 0x92, 0x81, 0x05, 0x14, 0x00, 0x94, 0x50, 0x02, 0x51, 0x4c, 0x41, 0x45, 0x00, 0x43, 0x45, 0x59, 0x42, 0xd1, 0x40, 0x05, 0x2d, 0x00, 0x2d, 0x2d, 0x20, 0x17, 0x34, 0xb9, 0xa4, 0x02, 0xee, 0xa5, 0xcd, 0x21, 0x8e, 0xa7, 0x0a, 0x90, 0x1d, 0x45, 0x21, 0x09, 0x49, 0x4c, 0x04, 0xa2, 0x80, 0x12, 0x8a, 0x00, 0x29, 0x29, 0x80, 0x51, 0x40, 0x05, 0x14, 0x00, 0x51, 0x48, 0x41, 0x49, 0x4c, 0x02, 0x8a, 0x00, 0x4a, 0x28, 0x00, 0xa2, 0x81, 0x09, 0x45, 0x30, 0x21, 0xa5, 0xab, 0x28, 0x28, 0xa0, 0x02, 0x96, 0x80, 0x16, 0x8a, 0x40, 0x2d, 0x14, 0x86, 0x38, 0x53, 0xd5, 0x69, 0x01, 0x25, 0x15, 0x00, 0x3a, 0x92, 0x90, 0x82, 0x92, 0xa8, 0x04, 0xa4, 0xa0, 0x04, 0xa2, 0x98, 0x05, 0x1d, 0xe9, 0x00, 0x37, 0x5a, 0x4a, 0x60, 0x14, 0x50, 0x01, 0x45, 0x21, 0x05, 0x25, 0x30, 0x0a, 0x28, 0x01, 0x28, 0xa0, 0x02, 0x8a, 0x04, 0x25, 0x14, 0xc0, 0x86, 0x96, 0xac, 0xa0, 0xa2, 0x80, 0x0a, 0x5a, 0x00, 0x29, 0x69, 0x0c, 0x29, 0xe0, 0x52, 0x11, 0x28, 0x14, 0xea, 0x90, 0x16, 0x8a, 0x90, 0x16, 0x8a, 0x00, 0x4a, 0x4a, 0x04, 0x25, 0x25, 0x30, 0x12, 0x8a, 0x63, 0x0a, 0x4a, 0x00, 0x28, 0xa0, 0x02, 0x8a, 0x00, 0x28, 0xa4, 0x01, 0x49, 0x4c, 0x41, 0x45, 0x00, 0x25, 0x14, 0x00, 0x51, 0x40, 0x84, 0xa2, 0x98, 0x10, 0xd2, 0xd5, 0x94, 0x25, 0x2d, 0x00, 0x14, 0xb4, 0x80, 0x29, 0x68, 0x01, 0xc2, 0x9e, 0x2a, 0x40, 0x78, 0xa5, 0xa4, 0x03, 0xc5, 0x23, 0x54, 0x8c, 0x29, 0x68, 0x24, 0x4a, 0x28, 0x01, 0x29, 0xb4, 0xc0, 0x4a, 0x29, 0x8c, 0x28, 0xa0, 0x02, 0x8a, 0x04, 0x14, 0x52, 0x01, 0x28, 0xa6, 0x01, 0x49, 0x40, 0x05, 0x14, 0x00, 0x94, 0x50, 0x01, 0x49, 0x40, 0x82, 0x8a, 0x60, 0x43, 0x45, 0x59, 0x61, 0x4b, 0x40, 0x82, 0x96, 0x90, 0x05, 0x2d, 0x00, 0x2d, 0x38, 0x52, 0x19, 0x20, 0xa7, 0x0a, 0x90, 0x1d, 0x48, 0xdd, 0x6a, 0x44, 0x28, 0xa5, 0xa0, 0x41, 0x49, 0x40, 0x09, 0x49, 0x40, 0x09, 0x45, 0x30, 0x12, 0x96, 0x80, 0x12, 0x8a, 0x00, 0x28, 0xa0, 0x04, 0xa2, 0x80, 0x0a, 0x4a, 0x60, 0x14, 0x50, 0x02, 0x51, 0x40, 0x05, 0x25, 0x02, 0x0a, 0x29, 0x81, 0x0d, 0x15, 0x65, 0x0b, 0x45, 0x00, 0x14, 0xb4, 0x80, 0x29, 0x68, 0x18, 0xb4, 0xe1, 0x48, 0x09, 0x05, 0x3a, 0xa0, 0x05, 0x14, 0x94, 0x08, 0x70, 0xa7, 0x50, 0x48, 0x52, 0x50, 0x02, 0x52, 0x50, 0x31, 0x28, 0xa0, 0x04, 0xa2, 0x80, 0x0a, 0x28, 0x01, 0x28, 0xa0, 0x02, 0x92, 0x80, 0x0a, 0x29, 0x80, 0x52, 0x50, 0x20, 0xa4, 0xa0, 0x02, 0x92, 0x98, 0x05, 0x14, 0x08, 0x86, 0x8a, 0xb2, 0xc2, 0x96, 0x80, 0x16, 0x8a, 0x40, 0x14, 0xb4, 0x00, 0xb4, 0xf1, 0x52, 0x03, 0xc5, 0x2d, 0x48, 0xc5, 0xed, 0x4d, 0x14, 0x08, 0x90, 0x53, 0xe8, 0x24, 0x4a, 0x4a, 0x04, 0x25, 0x25, 0x03, 0x0a, 0x4a, 0x06, 0x14, 0x94, 0x00, 0x51, 0x40, 0x05, 0x25, 0x00, 0x14, 0x50, 0x21, 0x28, 0xa6, 0x31, 0x28, 0xa0, 0x41, 0x49, 0x40, 0x05, 0x25, 0x30, 0x0a, 0x28, 0x11, 0x0d, 0x15, 0x65, 0x8b, 0x45, 0x00, 0x2d, 0x14, 0x80, 0x29, 0x68, 0x18, 0xe1, 0x4e, 0x15, 0x22, 0x1d, 0x4e, 0xa4, 0x31, 0xcd, 0xf7, 0x6a, 0x2a, 0x42, 0x25, 0x4a, 0x92, 0x82, 0x02, 0x92, 0x80, 0x12, 0x9b, 0x40, 0x05, 0x14, 0x0c, 0x29, 0x28, 0x00, 0xa2, 0x80, 0x0a, 0x28, 0x01, 0x29, 0x28, 0x00, 0xa4, 0xa6, 0x01, 0x49, 0x40, 0x05, 0x25, 0x00, 0x14, 0x94, 0xc0, 0x28, 0xa0, 0x44, 0x34, 0x55, 0x96, 0x2d, 0x14, 0x00, 0x52, 0xd2, 0x00, 0xa5, 0xa0, 0x62, 0x8a, 0x78, 0xa9, 0x01, 0xd4, 0xea, 0x42, 0x1c, 0x7e, 0xed, 0x45, 0x48, 0x07, 0x29, 0xc5, 0x4e, 0x28, 0x25, 0x85, 0x25, 0x02, 0x12, 0x92, 0x81, 0x85, 0x14, 0x00, 0x51, 0x40, 0x05, 0x14, 0x00, 0x94, 0x50, 0x21, 0x29, 0x28, 0x18, 0x94, 0x94, 0xc0, 0x28, 0xa4, 0x02, 0x52, 0x53, 0x00, 0xa2, 0x98, 0x84, 0xa2, 0x80, 0x21, 0xa2, 0xac, 0xb1, 0x68, 0xa0, 0x05, 0xa2, 0x90, 0x05, 0x2d, 0x00, 0x2d, 0x3a, 0xa4, 0x63, 0xa9, 0xc2, 0x90, 0x89, 0x1c, 0xe0, 0x0a, 0x8c, 0xd2, 0x10, 0xda, 0x96, 0x36, 0xa0, 0x19, 0x2d, 0x25, 0x04, 0x0d, 0xa4, 0xa0, 0x61, 0x45, 0x03, 0x16, 0x96, 0x81, 0x06, 0x29, 0x71, 0x40, 0x09, 0x8a, 0x4c, 0x50, 0x02, 0x62, 0x9b, 0x40, 0x09, 0x49, 0x4c, 0x04, 0xa2, 0x81, 0x89, 0x49, 0x4c, 0x02, 0x92, 0x81, 0x05, 0x14, 0x01, 0x0d, 0x15, 0x65, 0x8b, 0x45, 0x20, 0x16, 0x8a, 0x00, 0x29, 0x68, 0x01, 0x69, 0x69, 0x00, 0xf1, 0x52, 0x2d, 0x48, 0x04, 0xfc, 0x8a, 0x8d, 0x4e, 0xe5, 0xa0, 0x41, 0x40, 0x34, 0x01, 0x61, 0x4e, 0x45, 0x2d, 0x22, 0x06, 0xd2, 0x50, 0x30, 0xa5, 0xa0, 0x05, 0xa7, 0x50, 0x02, 0xd2, 0xe2, 0x98, 0x83, 0x14, 0xdc, 0x50, 0x03, 0x4d, 0x37, 0x14, 0x80, 0x6d, 0x25, 0x03, 0x12, 0x92, 0x98, 0xc4, 0xa4, 0xa6, 0x20, 0xa4, 0xa0, 0x02, 0x8a, 0x06, 0x43, 0x45, 0x59, 0x42, 0xd1, 0x48, 0x02, 0x96, 0x98, 0x05, 0x2d, 0x20, 0x14, 0x53, 0x85, 0x20, 0x1e, 0x2a, 0x44, 0xeb, 0x50, 0x03, 0x65, 0x6c, 0x49, 0x51, 0xfd, 0xc9, 0x3d, 0x8d, 0x50, 0x87, 0x9a, 0x6d, 0x20, 0x1e, 0x87, 0x15, 0x35, 0x22, 0x58, 0xda, 0x4a, 0x04, 0x14, 0xb4, 0x0c, 0x75, 0x3a, 0x81, 0x0e, 0xc5, 0x3b, 0x15, 0x43, 0x17, 0x6d, 0x37, 0x14, 0x00, 0xd2, 0x29, 0x86, 0x90, 0x88, 0xcd, 0x36, 0x90, 0xc4, 0xa4, 0xa6, 0x02, 0x52, 0x53, 0x00, 0xa4, 0xa4, 0x01, 0x49, 0x4c, 0x64, 0x54, 0x55, 0x94, 0x2d, 0x14, 0x80, 0x28, 0xa0, 0x05, 0xa2, 0x80, 0x14, 0x54, 0x8b, 0x52, 0xc0, 0x7d, 0x49, 0x1f, 0x5a, 0x90, 0x22, 0x9b, 0xef, 0x9a, 0x8f, 0xaa, 0xe3, 0xd2, 0xa9, 0x08, 0x91, 0x4e, 0xe4, 0xa4, 0xa4, 0x01, 0x52, 0xa3, 0x50, 0x26, 0x3a, 0x92, 0x91, 0x21, 0x4b, 0x40, 0xc7, 0x0a, 0x78, 0xa6, 0x22, 0x40, 0x2a, 0x55, 0x4c, 0xd3, 0x19, 0x2f, 0x92, 0x71, 0x50, 0xb2, 0x50, 0x22, 0x22, 0x2a, 0x33, 0x40, 0x11, 0x9a, 0x69, 0xa9, 0x01, 0xb4, 0xda, 0x63, 0x12, 0x8a, 0x00, 0x4a, 0x28, 0x01, 0x29, 0x29, 0x8c, 0x8a, 0x96, 0xac, 0xa0, 0xa2, 0x80, 0x0a, 0x28, 0x01, 0x68, 0xa4, 0x31, 0xc0, 0x54, 0xa2, 0x90, 0x0e, 0xc5, 0x3e, 0x3e, 0xb5, 0x36, 0x0b, 0x10, 0x4d, 0xf7, 0xcd, 0x31, 0x4e, 0x1b, 0x35, 0x42, 0x1f, 0xf7, 0x24, 0xf6, 0x34, 0xf2, 0x28, 0x60, 0x36, 0x95, 0x4e, 0x29, 0x0a, 0xc4, 0xa2, 0x8a, 0x2c, 0x2b, 0x05, 0x28, 0xa2, 0xc3, 0xb0, 0xf1, 0x52, 0x0a, 0x76, 0x15, 0x89, 0x54, 0x55, 0xfb, 0x38, 0xb7, 0xb8, 0x14, 0xec, 0x1c, 0xa7, 0xa0, 0x36, 0x83, 0x64, 0xf6, 0x3f, 0x67, 0x11, 0x28, 0x38, 0xfb, 0xf8, 0xe7, 0x35, 0xc3, 0x6a, 0x96, 0x0d, 0x69, 0x3b, 0x46, 0xdd, 0x45, 0x0e, 0x16, 0x2a, 0x50, 0x32, 0x9d, 0x6a, 0x16, 0x14, 0x58, 0x9b, 0x11, 0x11, 0x4c, 0x22, 0xa6, 0xc1, 0x61, 0x94, 0x94, 0xec, 0x02, 0x52, 0x52, 0x10, 0x94, 0x50, 0x31, 0x29, 0x29, 0x81, 0xff, 0xd9}; +static const char jpeg_data[] = { + 0xff, 0xd8, 0xff, 0xe0, 0x00, 0x10, 0x4a, 0x46, 0x49, 0x46, 0x00, 0x01, 0x01, 0x01, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0xff, 0xdb, 0x00, 0x43, 0x00, 0x0f, 0x0a, 0x0b, 0x0d, 0x0b, 0x09, 0x0f, + 0x0d, 0x0c, 0x0d, 0x11, 0x10, 0x0f, 0x12, 0x17, 0x26, 0x18, 0x17, 0x15, 0x15, 0x17, 0x2e, 0x21, + 0x23, 0x1b, 0x26, 0x36, 0x30, 0x39, 0x38, 0x35, 0x30, 0x35, 0x34, 0x3c, 0x44, 0x56, 0x49, 0x3c, + 0x40, 0x52, 0x41, 0x34, 0x35, 0x4b, 0x66, 0x4c, 0x52, 0x59, 0x5c, 0x61, 0x62, 0x61, 0x3a, 0x48, + 0x6a, 0x71, 0x69, 0x5e, 0x71, 0x56, 0x5f, 0x61, 0x5d, 0xff, 0xdb, 0x00, 0x43, 0x01, 0x10, 0x11, + 0x11, 0x17, 0x14, 0x17, 0x2c, 0x18, 0x18, 0x2c, 0x5d, 0x3e, 0x35, 0x3e, 0x5d, 0x5d, 0x5d, 0x5d, + 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, + 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, + 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0x5d, 0xff, 0xc4, + 0x00, 0x1f, 0x00, 0x00, 0x01, 0x05, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, + 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x0a, 0x0b, 0xff, + 0xc4, 0x00, 0xb5, 0x10, 0x00, 0x02, 0x01, 0x03, 0x03, 0x02, 0x04, 0x03, 0x05, 0x05, 0x04, 0x04, + 0x00, 0x00, 0x01, 0x7d, 0x01, 0x02, 0x03, 0x00, 0x04, 0x11, 0x05, 0x12, 0x21, 0x31, 0x41, 0x06, + 0x13, 0x51, 0x61, 0x07, 0x22, 0x71, 0x14, 0x32, 0x81, 0x91, 0xa1, 0x08, 0x23, 0x42, 0xb1, 0xc1, + 0x15, 0x52, 0xd1, 0xf0, 0x24, 0x33, 0x62, 0x72, 0x82, 0x09, 0x0a, 0x16, 0x17, 0x18, 0x19, 0x1a, + 0x25, 0x26, 0x27, 0x28, 0x29, 0x2a, 0x34, 0x35, 0x36, 0x37, 0x38, 0x39, 0x3a, 0x43, 0x44, 0x45, + 0x46, 0x47, 0x48, 0x49, 0x4a, 0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x63, 0x64, 0x65, + 0x66, 0x67, 0x68, 0x69, 0x6a, 0x73, 0x74, 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a, 0x83, 0x84, 0x85, + 0x86, 0x87, 0x88, 0x89, 0x8a, 0x92, 0x93, 0x94, 0x95, 0x96, 0x97, 0x98, 0x99, 0x9a, 0xa2, 0xa3, + 0xa4, 0xa5, 0xa6, 0xa7, 0xa8, 0xa9, 0xaa, 0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba, + 0xc2, 0xc3, 0xc4, 0xc5, 0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xd2, 0xd3, 0xd4, 0xd5, 0xd6, 0xd7, 0xd8, + 0xd9, 0xda, 0xe1, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7, 0xe8, 0xe9, 0xea, 0xf1, 0xf2, 0xf3, 0xf4, + 0xf5, 0xf6, 0xf7, 0xf8, 0xf9, 0xfa, 0xff, 0xc4, 0x00, 0x1f, 0x01, 0x00, 0x03, 0x01, 0x01, 0x01, + 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, + 0x05, 0x06, 0x07, 0x08, 0x09, 0x0a, 0x0b, 0xff, 0xc4, 0x00, 0xb5, 0x11, 0x00, 0x02, 0x01, 0x02, + 0x04, 0x04, 0x03, 0x04, 0x07, 0x05, 0x04, 0x04, 0x00, 0x01, 0x02, 0x77, 0x00, 0x01, 0x02, 0x03, + 0x11, 0x04, 0x05, 0x21, 0x31, 0x06, 0x12, 0x41, 0x51, 0x07, 0x61, 0x71, 0x13, 0x22, 0x32, 0x81, + 0x08, 0x14, 0x42, 0x91, 0xa1, 0xb1, 0xc1, 0x09, 0x23, 0x33, 0x52, 0xf0, 0x15, 0x62, 0x72, 0xd1, + 0x0a, 0x16, 0x24, 0x34, 0xe1, 0x25, 0xf1, 0x17, 0x18, 0x19, 0x1a, 0x26, 0x27, 0x28, 0x29, 0x2a, + 0x35, 0x36, 0x37, 0x38, 0x39, 0x3a, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x4a, 0x53, 0x54, + 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x63, 0x64, 0x65, 0x66, 0x67, 0x68, 0x69, 0x6a, 0x73, 0x74, + 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a, 0x82, 0x83, 0x84, 0x85, 0x86, 0x87, 0x88, 0x89, 0x8a, 0x92, + 0x93, 0x94, 0x95, 0x96, 0x97, 0x98, 0x99, 0x9a, 0xa2, 0xa3, 0xa4, 0xa5, 0xa6, 0xa7, 0xa8, 0xa9, + 0xaa, 0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba, 0xc2, 0xc3, 0xc4, 0xc5, 0xc6, 0xc7, + 0xc8, 0xc9, 0xca, 0xd2, 0xd3, 0xd4, 0xd5, 0xd6, 0xd7, 0xd8, 0xd9, 0xda, 0xe2, 0xe3, 0xe4, 0xe5, + 0xe6, 0xe7, 0xe8, 0xe9, 0xea, 0xf2, 0xf3, 0xf4, 0xf5, 0xf6, 0xf7, 0xf8, 0xf9, 0xfa, 0xff, 0xc0, + 0x00, 0x11, 0x08, 0x00, 0xf0, 0x01, 0x40, 0x03, 0x01, 0x21, 0x00, 0x02, 0x11, 0x01, 0x03, 0x11, + 0x01, 0xff, 0xda, 0x00, 0x0c, 0x03, 0x01, 0x00, 0x02, 0x11, 0x03, 0x11, 0x00, 0x3f, 0x00, 0xe0, + 0x29, 0x2a, 0xa6, 0x42, 0x13, 0xbd, 0x0d, 0xd6, 0xa0, 0xa1, 0x28, 0xa0, 0x05, 0xa7, 0x50, 0x03, + 0x96, 0xa4, 0x15, 0x22, 0x1f, 0x45, 0x00, 0x2d, 0x21, 0xa9, 0x18, 0x95, 0x22, 0x54, 0xb0, 0x1c, + 0x69, 0x86, 0xa4, 0x63, 0x69, 0xb5, 0x42, 0x12, 0x92, 0x98, 0x05, 0x25, 0x30, 0x0a, 0x29, 0x80, + 0x51, 0x40, 0x05, 0x14, 0x80, 0x29, 0x29, 0x88, 0x28, 0xa0, 0x02, 0x92, 0x80, 0x0a, 0x28, 0x10, + 0x52, 0x53, 0x00, 0xa4, 0xad, 0x2a, 0x09, 0x0d, 0x3d, 0x69, 0x2a, 0x4b, 0x0a, 0x28, 0x01, 0xd4, + 0xea, 0x00, 0x78, 0xa7, 0x8a, 0x91, 0x0e, 0xa5, 0xa4, 0x21, 0x69, 0x29, 0x14, 0x25, 0x48, 0xbd, + 0x2a, 0x58, 0x01, 0xa6, 0x54, 0x80, 0xd3, 0x49, 0x56, 0x31, 0x29, 0x29, 0x88, 0x4a, 0x29, 0x80, + 0x51, 0x40, 0x05, 0x25, 0x00, 0x14, 0xb4, 0x08, 0x29, 0x28, 0x00, 0xa2, 0x80, 0x0a, 0x28, 0x01, + 0x28, 0xa0, 0x41, 0x49, 0x4c, 0x00, 0xd3, 0x7b, 0x56, 0xb5, 0x37, 0x12, 0x1b, 0x45, 0x49, 0x61, + 0x4b, 0x48, 0x07, 0x53, 0x85, 0x20, 0x1e, 0x29, 0xf5, 0x24, 0x8b, 0x4a, 0x28, 0x01, 0x68, 0xa4, + 0x30, 0xa7, 0x76, 0xa8, 0x63, 0x10, 0xd3, 0x68, 0x18, 0xca, 0x4a, 0xa0, 0x12, 0x8a, 0x62, 0x12, + 0x8a, 0x00, 0x28, 0xa6, 0x01, 0x45, 0x00, 0x14, 0x94, 0x08, 0x5a, 0x4a, 0x40, 0x14, 0x53, 0x00, + 0xa2, 0x80, 0x12, 0x8a, 0x04, 0x14, 0x94, 0x00, 0xa6, 0x90, 0x0c, 0x83, 0x5a, 0xd4, 0xdc, 0x48, + 0x8e, 0x8a, 0x45, 0x85, 0x3a, 0x90, 0x0a, 0x29, 0xf4, 0x84, 0x3c, 0x0a, 0x76, 0x2a, 0x44, 0x2d, + 0x14, 0x0c, 0x5a, 0x5a, 0x43, 0x0a, 0x7d, 0x43, 0x01, 0xa6, 0x99, 0x40, 0xc4, 0xa6, 0xd5, 0x08, + 0x29, 0x29, 0x80, 0x52, 0x50, 0x01, 0x45, 0x30, 0x0a, 0x28, 0x00, 0xa2, 0x90, 0x05, 0x14, 0x00, + 0x94, 0x53, 0x10, 0x51, 0x40, 0x09, 0x45, 0x00, 0x14, 0x50, 0x21, 0x1a, 0x97, 0xfe, 0x59, 0x9a, + 0xd2, 0x7b, 0x82, 0x22, 0xa2, 0x82, 0x85, 0xa7, 0x52, 0x01, 0xc2, 0x9d, 0x48, 0x43, 0xc5, 0x3c, + 0x54, 0x88, 0x28, 0xa0, 0x61, 0x4b, 0xda, 0x90, 0xc2, 0x9d, 0x50, 0xc0, 0x69, 0xa6, 0xd0, 0x31, + 0x29, 0x2a, 0x84, 0x25, 0x25, 0x30, 0x0a, 0x28, 0x01, 0x28, 0xa0, 0x02, 0x8a, 0x60, 0x14, 0x50, + 0x01, 0x45, 0x02, 0x0a, 0x4a, 0x00, 0x28, 0xa0, 0x04, 0xa2, 0x80, 0x0a, 0x28, 0x10, 0x8d, 0x48, + 0x7e, 0xed, 0x69, 0x2d, 0xc1, 0x0c, 0xa2, 0x82, 0x87, 0x52, 0xd2, 0x01, 0xc2, 0xa4, 0x15, 0x22, + 0x1c, 0x29, 0xf4, 0x84, 0x2d, 0x26, 0x29, 0x0c, 0x29, 0x09, 0xa0, 0x61, 0x8c, 0x8a, 0x5e, 0x40, + 0xe9, 0x52, 0xc6, 0x37, 0x75, 0x25, 0x00, 0x14, 0xda, 0x60, 0x14, 0x94, 0xc4, 0x14, 0x50, 0x01, + 0x49, 0x40, 0x05, 0x14, 0xc0, 0x28, 0xa0, 0x02, 0x8a, 0x04, 0x14, 0x94, 0x00, 0x51, 0x40, 0x05, + 0x25, 0x00, 0x14, 0x50, 0x21, 0x0d, 0x0d, 0xf7, 0x6a, 0xde, 0xe3, 0x23, 0xa5, 0x14, 0x0c, 0x75, + 0x2d, 0x20, 0x1e, 0x29, 0xf4, 0x84, 0x3c, 0x53, 0x85, 0x21, 0x0b, 0x45, 0x20, 0x12, 0x90, 0xa7, + 0x34, 0x8a, 0x1c, 0x31, 0x41, 0xa8, 0x18, 0xd3, 0x4c, 0x20, 0x55, 0x00, 0x98, 0xa6, 0x9c, 0xd3, + 0x00, 0x1d, 0x28, 0xa6, 0x20, 0xa2, 0x80, 0x0a, 0x28, 0x01, 0x28, 0xa6, 0x01, 0x45, 0x00, 0x14, + 0x50, 0x20, 0xa2, 0x90, 0x09, 0x45, 0x30, 0x0a, 0x4a, 0x00, 0x28, 0xa0, 0x42, 0x77, 0xa1, 0xba, + 0x55, 0x0c, 0x8e, 0x94, 0x53, 0x18, 0xea, 0x75, 0x20, 0x1e, 0x29, 0xe2, 0x90, 0x87, 0x8a, 0x75, + 0x21, 0x05, 0x2d, 0x21, 0x89, 0x45, 0x21, 0x8a, 0x07, 0x14, 0xd2, 0xa2, 0xa0, 0x63, 0x71, 0xef, + 0x4d, 0xe6, 0xa8, 0x04, 0xfc, 0x29, 0xac, 0x69, 0x80, 0x0e, 0x94, 0xb4, 0xc0, 0x4a, 0x28, 0x10, + 0x51, 0x40, 0x09, 0x45, 0x00, 0x14, 0x53, 0x00, 0xa2, 0x90, 0x82, 0x8a, 0x00, 0x29, 0x29, 0x80, + 0x51, 0x40, 0x09, 0x45, 0x02, 0x01, 0xd6, 0xa4, 0x23, 0x72, 0xf6, 0xa6, 0xc0, 0xad, 0x4e, 0x15, + 0x45, 0x0e, 0x14, 0xea, 0x42, 0x1e, 0x2a, 0x41, 0x48, 0x43, 0x85, 0x3a, 0xa4, 0x05, 0xa2, 0x81, + 0x89, 0x49, 0x52, 0x31, 0xc2, 0x9a, 0x6a, 0x06, 0x36, 0x9b, 0x56, 0x02, 0x53, 0x4f, 0x34, 0xc0, + 0x28, 0xa6, 0x02, 0x51, 0x40, 0x82, 0x8a, 0x00, 0x28, 0xa0, 0x04, 0xa2, 0x80, 0x0a, 0x28, 0x00, + 0xa2, 0x81, 0x09, 0x45, 0x00, 0x14, 0x94, 0xc0, 0x28, 0xa0, 0x42, 0x53, 0x81, 0x38, 0xa6, 0xc6, + 0x46, 0x7a, 0xd2, 0x8a, 0xa1, 0x8e, 0x14, 0xfa, 0x91, 0x0e, 0x15, 0x20, 0xa4, 0x21, 0xf4, 0xb4, + 0x80, 0x28, 0xa0, 0x61, 0x49, 0x52, 0x31, 0x69, 0x0d, 0x40, 0xc6, 0x53, 0x6a, 0xc0, 0x4a, 0x4a, + 0x60, 0x25, 0x14, 0x00, 0x52, 0x53, 0x10, 0x51, 0x40, 0x05, 0x14, 0x00, 0x94, 0xb4, 0xc0, 0x28, + 0xa4, 0x02, 0x51, 0x40, 0x82, 0x92, 0x98, 0x05, 0x14, 0x00, 0x94, 0x50, 0x21, 0x70, 0x36, 0x50, + 0xbd, 0x28, 0x28, 0x47, 0x14, 0xd1, 0x54, 0x80, 0x75, 0x3e, 0x90, 0x87, 0x0a, 0x90, 0x52, 0x10, + 0xfa, 0x5a, 0x40, 0x2d, 0x25, 0x03, 0x16, 0x92, 0xa4, 0x64, 0xf1, 0xdb, 0x4b, 0x28, 0x6f, 0x2e, + 0x36, 0x7d, 0xab, 0xb8, 0xe0, 0x74, 0x15, 0x03, 0x54, 0x0c, 0x8e, 0x9b, 0x54, 0x02, 0x52, 0x55, + 0x00, 0x52, 0x50, 0x01, 0x45, 0x31, 0x05, 0x25, 0x00, 0x14, 0x50, 0x01, 0x45, 0x00, 0x14, 0x50, + 0x21, 0x28, 0xa0, 0x02, 0x92, 0x80, 0x0a, 0x29, 0x80, 0x52, 0x50, 0x21, 0xfd, 0x56, 0x85, 0xe9, + 0x40, 0xc6, 0xc9, 0xd2, 0x99, 0x54, 0x86, 0x2e, 0x69, 0xe1, 0xa8, 0x10, 0xf0, 0x69, 0xf5, 0x22, + 0x1d, 0xcd, 0x1c, 0xd2, 0x18, 0xb4, 0xb4, 0x80, 0x5a, 0x3b, 0xd2, 0x19, 0xd0, 0x68, 0x5a, 0x95, + 0xbd, 0x95, 0xb5, 0xe9, 0x9b, 0xef, 0x34, 0x78, 0x45, 0xfe, 0xf5, 0x60, 0x48, 0x69, 0x0c, 0x88, + 0xd3, 0x69, 0x80, 0x94, 0x94, 0xc0, 0x29, 0x28, 0x00, 0xa2, 0x98, 0x84, 0xa2, 0x80, 0x0a, 0x28, + 0x00, 0xa2, 0x80, 0x0a, 0x28, 0x10, 0x52, 0x50, 0x01, 0x49, 0x4c, 0x02, 0x8a, 0x00, 0x29, 0x28, + 0x11, 0x20, 0xa2, 0x81, 0x8c, 0x91, 0x87, 0x4a, 0x8c, 0x55, 0x21, 0x8e, 0xa5, 0xa0, 0x43, 0xa9, + 0xea, 0x4d, 0x21, 0x12, 0x06, 0xa5, 0xde, 0x2a, 0x40, 0x4d, 0xd4, 0xea, 0x45, 0x0b, 0x45, 0x20, + 0x17, 0x34, 0xd2, 0x6a, 0x46, 0x32, 0x92, 0xa8, 0x04, 0xa4, 0xa6, 0x01, 0x49, 0x40, 0x05, 0x14, + 0xc0, 0x29, 0x28, 0x10, 0x51, 0x40, 0x05, 0x14, 0x00, 0x51, 0x40, 0x82, 0x92, 0x80, 0x0a, 0x28, + 0x01, 0x28, 0xa6, 0x01, 0x49, 0x40, 0x89, 0x29, 0x8e, 0xf8, 0xe9, 0x40, 0xc8, 0xa8, 0xab, 0x18, + 0xb4, 0xb4, 0x80, 0x76, 0xea, 0x70, 0x7a, 0x42, 0x1d, 0x9a, 0x75, 0x20, 0x1d, 0x4e, 0xa9, 0x18, + 0xb4, 0x52, 0x00, 0xa6, 0xd2, 0x18, 0x94, 0x94, 0xc0, 0x4a, 0x4a, 0x60, 0x14, 0x94, 0x00, 0x51, + 0x4c, 0x41, 0x45, 0x00, 0x25, 0x14, 0x00, 0x51, 0x40, 0x05, 0x14, 0x08, 0x29, 0x28, 0x00, 0xa2, + 0x80, 0x12, 0x8a, 0x60, 0x14, 0x50, 0x20, 0x76, 0xc5, 0x43, 0x54, 0x8a, 0x0a, 0x5a, 0x60, 0x14, + 0xb9, 0xa0, 0x07, 0x66, 0x96, 0x90, 0x0b, 0xc5, 0x38, 0x52, 0x01, 0xf4, 0xea, 0x80, 0x12, 0x9e, + 0x29, 0x0c, 0x5a, 0x6d, 0x20, 0x12, 0x92, 0x98, 0x09, 0x45, 0x30, 0x12, 0x8a, 0x00, 0x4a, 0x29, + 0x88, 0x28, 0xa0, 0x02, 0x92, 0x80, 0x16, 0x8a, 0x00, 0x29, 0x28, 0x10, 0x51, 0x40, 0x09, 0x45, + 0x00, 0x14, 0x94, 0x00, 0x51, 0x4c, 0x44, 0x44, 0xe6, 0x92, 0xac, 0xa1, 0x68, 0xa0, 0x02, 0x96, + 0x80, 0x0a, 0x75, 0x20, 0x1e, 0x29, 0xd5, 0x20, 0x3a, 0x8c, 0xd2, 0x18, 0x66, 0x9c, 0xb5, 0x2c, + 0x07, 0x52, 0x52, 0x01, 0x29, 0x29, 0x88, 0x4a, 0x4a, 0x60, 0x14, 0x50, 0x02, 0x51, 0x4c, 0x02, + 0x8a, 0x00, 0x29, 0x28, 0x01, 0x68, 0xa0, 0x02, 0x92, 0x81, 0x05, 0x14, 0x00, 0x94, 0x50, 0x02, + 0x51, 0x4c, 0x41, 0x45, 0x00, 0x43, 0x45, 0x59, 0x42, 0xd1, 0x40, 0x05, 0x2d, 0x00, 0x2d, 0x2d, + 0x20, 0x17, 0x34, 0xb9, 0xa4, 0x02, 0xee, 0xa5, 0xcd, 0x21, 0x8e, 0xa7, 0x0a, 0x90, 0x1d, 0x45, + 0x21, 0x09, 0x49, 0x4c, 0x04, 0xa2, 0x80, 0x12, 0x8a, 0x00, 0x29, 0x29, 0x80, 0x51, 0x40, 0x05, + 0x14, 0x00, 0x51, 0x48, 0x41, 0x49, 0x4c, 0x02, 0x8a, 0x00, 0x4a, 0x28, 0x00, 0xa2, 0x81, 0x09, + 0x45, 0x30, 0x21, 0xa5, 0xab, 0x28, 0x28, 0xa0, 0x02, 0x96, 0x80, 0x16, 0x8a, 0x40, 0x2d, 0x14, + 0x86, 0x38, 0x53, 0xd5, 0x69, 0x01, 0x25, 0x15, 0x00, 0x3a, 0x92, 0x90, 0x82, 0x92, 0xa8, 0x04, + 0xa4, 0xa0, 0x04, 0xa2, 0x98, 0x05, 0x1d, 0xe9, 0x00, 0x37, 0x5a, 0x4a, 0x60, 0x14, 0x50, 0x01, + 0x45, 0x21, 0x05, 0x25, 0x30, 0x0a, 0x28, 0x01, 0x28, 0xa0, 0x02, 0x8a, 0x04, 0x25, 0x14, 0xc0, + 0x86, 0x96, 0xac, 0xa0, 0xa2, 0x80, 0x0a, 0x5a, 0x00, 0x29, 0x69, 0x0c, 0x29, 0xe0, 0x52, 0x11, + 0x28, 0x14, 0xea, 0x90, 0x16, 0x8a, 0x90, 0x16, 0x8a, 0x00, 0x4a, 0x4a, 0x04, 0x25, 0x25, 0x30, + 0x12, 0x8a, 0x63, 0x0a, 0x4a, 0x00, 0x28, 0xa0, 0x02, 0x8a, 0x00, 0x28, 0xa4, 0x01, 0x49, 0x4c, + 0x41, 0x45, 0x00, 0x25, 0x14, 0x00, 0x51, 0x40, 0x84, 0xa2, 0x98, 0x10, 0xd2, 0xd5, 0x94, 0x25, + 0x2d, 0x00, 0x14, 0xb4, 0x80, 0x29, 0x68, 0x01, 0xc2, 0x9e, 0x2a, 0x40, 0x78, 0xa5, 0xa4, 0x03, + 0xc5, 0x23, 0x54, 0x8c, 0x29, 0x68, 0x24, 0x4a, 0x28, 0x01, 0x29, 0xb4, 0xc0, 0x4a, 0x29, 0x8c, + 0x28, 0xa0, 0x02, 0x8a, 0x04, 0x14, 0x52, 0x01, 0x28, 0xa6, 0x01, 0x49, 0x40, 0x05, 0x14, 0x00, + 0x94, 0x50, 0x01, 0x49, 0x40, 0x82, 0x8a, 0x60, 0x43, 0x45, 0x59, 0x61, 0x4b, 0x40, 0x82, 0x96, + 0x90, 0x05, 0x2d, 0x00, 0x2d, 0x38, 0x52, 0x19, 0x20, 0xa7, 0x0a, 0x90, 0x1d, 0x48, 0xdd, 0x6a, + 0x44, 0x28, 0xa5, 0xa0, 0x41, 0x49, 0x40, 0x09, 0x49, 0x40, 0x09, 0x45, 0x30, 0x12, 0x96, 0x80, + 0x12, 0x8a, 0x00, 0x28, 0xa0, 0x04, 0xa2, 0x80, 0x0a, 0x4a, 0x60, 0x14, 0x50, 0x02, 0x51, 0x40, + 0x05, 0x25, 0x02, 0x0a, 0x29, 0x81, 0x0d, 0x15, 0x65, 0x0b, 0x45, 0x00, 0x14, 0xb4, 0x80, 0x29, + 0x68, 0x18, 0xb4, 0xe1, 0x48, 0x09, 0x05, 0x3a, 0xa0, 0x05, 0x14, 0x94, 0x08, 0x70, 0xa7, 0x50, + 0x48, 0x52, 0x50, 0x02, 0x52, 0x50, 0x31, 0x28, 0xa0, 0x04, 0xa2, 0x80, 0x0a, 0x28, 0x01, 0x28, + 0xa0, 0x02, 0x92, 0x80, 0x0a, 0x29, 0x80, 0x52, 0x50, 0x20, 0xa4, 0xa0, 0x02, 0x92, 0x98, 0x05, + 0x14, 0x08, 0x86, 0x8a, 0xb2, 0xc2, 0x96, 0x80, 0x16, 0x8a, 0x40, 0x14, 0xb4, 0x00, 0xb4, 0xf1, + 0x52, 0x03, 0xc5, 0x2d, 0x48, 0xc5, 0xed, 0x4d, 0x14, 0x08, 0x90, 0x53, 0xe8, 0x24, 0x4a, 0x4a, + 0x04, 0x25, 0x25, 0x03, 0x0a, 0x4a, 0x06, 0x14, 0x94, 0x00, 0x51, 0x40, 0x05, 0x25, 0x00, 0x14, + 0x50, 0x21, 0x28, 0xa6, 0x31, 0x28, 0xa0, 0x41, 0x49, 0x40, 0x05, 0x25, 0x30, 0x0a, 0x28, 0x11, + 0x0d, 0x15, 0x65, 0x8b, 0x45, 0x00, 0x2d, 0x14, 0x80, 0x29, 0x68, 0x18, 0xe1, 0x4e, 0x15, 0x22, + 0x1d, 0x4e, 0xa4, 0x31, 0xcd, 0xf7, 0x6a, 0x2a, 0x42, 0x25, 0x4a, 0x92, 0x82, 0x02, 0x92, 0x80, + 0x12, 0x9b, 0x40, 0x05, 0x14, 0x0c, 0x29, 0x28, 0x00, 0xa2, 0x80, 0x0a, 0x28, 0x01, 0x29, 0x28, + 0x00, 0xa4, 0xa6, 0x01, 0x49, 0x40, 0x05, 0x25, 0x00, 0x14, 0x94, 0xc0, 0x28, 0xa0, 0x44, 0x34, + 0x55, 0x96, 0x2d, 0x14, 0x00, 0x52, 0xd2, 0x00, 0xa5, 0xa0, 0x62, 0x8a, 0x78, 0xa9, 0x01, 0xd4, + 0xea, 0x42, 0x1c, 0x7e, 0xed, 0x45, 0x48, 0x07, 0x29, 0xc5, 0x4e, 0x28, 0x25, 0x85, 0x25, 0x02, + 0x12, 0x92, 0x81, 0x85, 0x14, 0x00, 0x51, 0x40, 0x05, 0x14, 0x00, 0x94, 0x50, 0x21, 0x29, 0x28, + 0x18, 0x94, 0x94, 0xc0, 0x28, 0xa4, 0x02, 0x52, 0x53, 0x00, 0xa2, 0x98, 0x84, 0xa2, 0x80, 0x21, + 0xa2, 0xac, 0xb1, 0x68, 0xa0, 0x05, 0xa2, 0x90, 0x05, 0x2d, 0x00, 0x2d, 0x3a, 0xa4, 0x63, 0xa9, + 0xc2, 0x90, 0x89, 0x1c, 0xe0, 0x0a, 0x8c, 0xd2, 0x10, 0xda, 0x96, 0x36, 0xa0, 0x19, 0x2d, 0x25, + 0x04, 0x0d, 0xa4, 0xa0, 0x61, 0x45, 0x03, 0x16, 0x96, 0x81, 0x06, 0x29, 0x71, 0x40, 0x09, 0x8a, + 0x4c, 0x50, 0x02, 0x62, 0x9b, 0x40, 0x09, 0x49, 0x4c, 0x04, 0xa2, 0x81, 0x89, 0x49, 0x4c, 0x02, + 0x92, 0x81, 0x05, 0x14, 0x01, 0x0d, 0x15, 0x65, 0x8b, 0x45, 0x20, 0x16, 0x8a, 0x00, 0x29, 0x68, + 0x01, 0x69, 0x69, 0x00, 0xf1, 0x52, 0x2d, 0x48, 0x04, 0xfc, 0x8a, 0x8d, 0x4e, 0xe5, 0xa0, 0x41, + 0x40, 0x34, 0x01, 0x61, 0x4e, 0x45, 0x2d, 0x22, 0x06, 0xd2, 0x50, 0x30, 0xa5, 0xa0, 0x05, 0xa7, + 0x50, 0x02, 0xd2, 0xe2, 0x98, 0x83, 0x14, 0xdc, 0x50, 0x03, 0x4d, 0x37, 0x14, 0x80, 0x6d, 0x25, + 0x03, 0x12, 0x92, 0x98, 0xc4, 0xa4, 0xa6, 0x20, 0xa4, 0xa0, 0x02, 0x8a, 0x06, 0x43, 0x45, 0x59, + 0x42, 0xd1, 0x48, 0x02, 0x96, 0x98, 0x05, 0x2d, 0x20, 0x14, 0x53, 0x85, 0x20, 0x1e, 0x2a, 0x44, + 0xeb, 0x50, 0x03, 0x65, 0x6c, 0x49, 0x51, 0xfd, 0xc9, 0x3d, 0x8d, 0x50, 0x87, 0x9a, 0x6d, 0x20, + 0x1e, 0x87, 0x15, 0x35, 0x22, 0x58, 0xda, 0x4a, 0x04, 0x14, 0xb4, 0x0c, 0x75, 0x3a, 0x81, 0x0e, + 0xc5, 0x3b, 0x15, 0x43, 0x17, 0x6d, 0x37, 0x14, 0x00, 0xd2, 0x29, 0x86, 0x90, 0x88, 0xcd, 0x36, + 0x90, 0xc4, 0xa4, 0xa6, 0x02, 0x52, 0x53, 0x00, 0xa4, 0xa4, 0x01, 0x49, 0x4c, 0x64, 0x54, 0x55, + 0x94, 0x2d, 0x14, 0x80, 0x28, 0xa0, 0x05, 0xa2, 0x80, 0x14, 0x54, 0x8b, 0x52, 0xc0, 0x7d, 0x49, + 0x1f, 0x5a, 0x90, 0x22, 0x9b, 0xef, 0x9a, 0x8f, 0xaa, 0xe3, 0xd2, 0xa9, 0x08, 0x91, 0x4e, 0xe4, + 0xa4, 0xa4, 0x01, 0x52, 0xa3, 0x50, 0x26, 0x3a, 0x92, 0x91, 0x21, 0x4b, 0x40, 0xc7, 0x0a, 0x78, + 0xa6, 0x22, 0x40, 0x2a, 0x55, 0x4c, 0xd3, 0x19, 0x2f, 0x92, 0x71, 0x50, 0xb2, 0x50, 0x22, 0x22, + 0x2a, 0x33, 0x40, 0x11, 0x9a, 0x69, 0xa9, 0x01, 0xb4, 0xda, 0x63, 0x12, 0x8a, 0x00, 0x4a, 0x28, + 0x01, 0x29, 0x29, 0x8c, 0x8a, 0x96, 0xac, 0xa0, 0xa2, 0x80, 0x0a, 0x28, 0x01, 0x68, 0xa4, 0x31, + 0xc0, 0x54, 0xa2, 0x90, 0x0e, 0xc5, 0x3e, 0x3e, 0xb5, 0x36, 0x0b, 0x10, 0x4d, 0xf7, 0xcd, 0x31, + 0x4e, 0x1b, 0x35, 0x42, 0x1f, 0xf7, 0x24, 0xf6, 0x34, 0xf2, 0x28, 0x60, 0x36, 0x95, 0x4e, 0x29, + 0x0a, 0xc4, 0xa2, 0x8a, 0x2c, 0x2b, 0x05, 0x28, 0xa2, 0xc3, 0xb0, 0xf1, 0x52, 0x0a, 0x76, 0x15, + 0x89, 0x54, 0x55, 0xfb, 0x38, 0xb7, 0xb8, 0x14, 0xec, 0x1c, 0xa7, 0xa0, 0x36, 0x83, 0x64, 0xf6, + 0x3f, 0x67, 0x11, 0x28, 0x38, 0xfb, 0xf8, 0xe7, 0x35, 0xc3, 0x6a, 0x96, 0x0d, 0x69, 0x3b, 0x46, + 0xdd, 0x45, 0x0e, 0x16, 0x2a, 0x50, 0x32, 0x9d, 0x6a, 0x16, 0x14, 0x58, 0x9b, 0x11, 0x11, 0x4c, + 0x22, 0xa6, 0xc1, 0x61, 0x94, 0x94, 0xec, 0x02, 0x52, 0x52, 0x10, 0x94, 0x50, 0x31, 0x29, 0x29, + 0x81, 0xff, 0xd9}; diff --git a/components/rtsp/example/main/rtsp_example.cpp b/components/rtsp/example/main/rtsp_example.cpp index 88ffc4f18..ce5bd1b1e 100644 --- a/components/rtsp/example/main/rtsp_example.cpp +++ b/components/rtsp/example/main/rtsp_example.cpp @@ -14,8 +14,8 @@ #include "task.hpp" #include "wifi_sta.hpp" -#include "rtsp_server.hpp" #include "rtsp_client.hpp" +#include "rtsp_server.hpp" #include "jpeg_image.hpp" @@ -64,7 +64,7 @@ extern "C" void app_main(void) { .port = server_port, .path = "/mjpeg/1", .log_level = espp::Logger::Verbosity::INFO, - }); + }); rtsp_server.start(); espp::JpegFrame jpeg_frame(jpeg_data, sizeof(jpeg_data)); @@ -77,13 +77,15 @@ extern "C" void app_main(void) { //! [rtsp_client_example] espp::RtspClient rtsp_client({ .server_address = ip_address, // string of the form {}.{}.{}.{} - .rtsp_port = CONFIG_RTSP_SERVER_PORT, - .path = "/mjpeg/1", - .on_jpeg_frame = [](std::unique_ptr jpeg_frame) { - fmt::print("Got JPEG frame of size {}x{}\n", jpeg_frame->get_width(), jpeg_frame->get_height()); - }, - .log_level = espp::Logger::Verbosity::ERROR, - }); + .rtsp_port = CONFIG_RTSP_SERVER_PORT, + .path = "/mjpeg/1", + .on_jpeg_frame = + [](std::unique_ptr jpeg_frame) { + fmt::print("Got JPEG frame of size {}x{}\n", jpeg_frame->get_width(), + jpeg_frame->get_height()); + }, + .log_level = espp::Logger::Verbosity::ERROR, + }); std::error_code ec; diff --git a/components/rtsp/include/jpeg_frame.hpp b/components/rtsp/include/jpeg_frame.hpp index d59a122d6..82292fbee 100644 --- a/components/rtsp/include/jpeg_frame.hpp +++ b/components/rtsp/include/jpeg_frame.hpp @@ -1,138 +1,124 @@ #pragma once -#include "rtp_jpeg_packet.hpp" #include "jpeg_header.hpp" +#include "rtp_jpeg_packet.hpp" namespace espp { - /// A class that represents a complete JPEG frame. +/// A class that represents a complete JPEG frame. +/// +/// This class is used to collect the JPEG scans that are received in RTP +/// packets and to serialize them into a complete JPEG frame. +class JpegFrame { +public: + /// Construct a JpegFrame from a RtpJpegPacket. /// - /// This class is used to collect the JPEG scans that are received in RTP - /// packets and to serialize them into a complete JPEG frame. - class JpegFrame { - public: - - /// Construct a JpegFrame from a RtpJpegPacket. - /// - /// This constructor will parse the header of the packet and add the JPEG - /// data to the frame. - /// - /// @param packet The packet to parse. - explicit JpegFrame(const RtpJpegPacket& packet) - : header_(packet.get_width(), packet.get_height(), packet.get_q_table(0), packet.get_q_table(1)) { - // add the jpeg header - serialize_header(); - // add the jpeg data - add_scan(packet); - } - - /// Construct a JpegFrame from buffer of jpeg data - /// @param data The buffer containing the jpeg data. - /// @param size The size of the buffer. - explicit JpegFrame(const char* data, size_t size) - : data_(data, data + size) - , header_(std::string_view(data_.data(), size)) { - } - - /// Get a reference to the header. - /// @return A reference to the header. - const JpegHeader& get_header() const { - return header_; - } - - /// Get the width of the frame. - /// @return The width of the frame. - int get_width() const { - return header_.get_width(); - } - - /// Get the height of the frame. - /// @return The height of the frame. - int get_height() const { - return header_.get_height(); - } - - /// Check if the frame is complete. - /// @return True if the frame is complete, false otherwise. - bool is_complete() const { - return finalized_; - } - - /// Append a RtpJpegPacket to the frame. - /// This will add the JPEG data to the frame. - /// @param packet The packet containing the scan to append. - void append(const RtpJpegPacket& packet) { - add_scan(packet); - } - - /// Append a JPEG scan to the frame. - /// This will add the JPEG data to the frame. - /// @note If the packet contains the EOI marker, the frame will be - /// finalized, and no further scans can be added. - /// @param packet The packet containing the scan to append. - void add_scan(const RtpJpegPacket& packet) { - add_scan(packet.get_jpeg_data()); - if (packet.get_marker()) { - finalize(); - } - } - - /// Get the serialized data. - /// This will return the serialized data. - /// @return The serialized data. - std::string_view get_data() const { - return std::string_view(data_.data(), data_.size()); - } - - /// Get the scan data. - /// This will return the scan data. - /// @return The scan data. - std::string_view get_scan_data() const { - auto header_data = header_.get_data(); - size_t header_size = header_data.size(); - return std::string_view(data_.data() + header_size, data_.size() - header_size); - } - - protected: - /// Serialize the header. - void serialize_header() { - auto header_data = header_.get_data(); - data_.resize(header_data.size()); - memcpy(data_.data(), header_data.data(), header_data.size()); + /// This constructor will parse the header of the packet and add the JPEG + /// data to the frame. + /// + /// @param packet The packet to parse. + explicit JpegFrame(const RtpJpegPacket &packet) + : header_(packet.get_width(), packet.get_height(), packet.get_q_table(0), + packet.get_q_table(1)) { + // add the jpeg header + serialize_header(); + // add the jpeg data + add_scan(packet); + } + + /// Construct a JpegFrame from buffer of jpeg data + /// @param data The buffer containing the jpeg data. + /// @param size The size of the buffer. + explicit JpegFrame(const char *data, size_t size) + : data_(data, data + size), header_(std::string_view(data_.data(), size)) {} + + /// Get a reference to the header. + /// @return A reference to the header. + const JpegHeader &get_header() const { return header_; } + + /// Get the width of the frame. + /// @return The width of the frame. + int get_width() const { return header_.get_width(); } + + /// Get the height of the frame. + /// @return The height of the frame. + int get_height() const { return header_.get_height(); } + + /// Check if the frame is complete. + /// @return True if the frame is complete, false otherwise. + bool is_complete() const { return finalized_; } + + /// Append a RtpJpegPacket to the frame. + /// This will add the JPEG data to the frame. + /// @param packet The packet containing the scan to append. + void append(const RtpJpegPacket &packet) { add_scan(packet); } + + /// Append a JPEG scan to the frame. + /// This will add the JPEG data to the frame. + /// @note If the packet contains the EOI marker, the frame will be + /// finalized, and no further scans can be added. + /// @param packet The packet containing the scan to append. + void add_scan(const RtpJpegPacket &packet) { + add_scan(packet.get_jpeg_data()); + if (packet.get_marker()) { + finalize(); } - - /// Append a JPEG scan to the frame. - /// This will add the JPEG data to the frame. - /// @param scan The jpeg scan to append. - void add_scan(std::string_view scan) { - if (finalized_) { - // TODO: handle this error - return; - } - data_.insert(std::end(data_), std::begin(scan), std::end(scan)); + } + + /// Get the serialized data. + /// This will return the serialized data. + /// @return The serialized data. + std::string_view get_data() const { return std::string_view(data_.data(), data_.size()); } + + /// Get the scan data. + /// This will return the scan data. + /// @return The scan data. + std::string_view get_scan_data() const { + auto header_data = header_.get_data(); + size_t header_size = header_data.size(); + return std::string_view(data_.data() + header_size, data_.size() - header_size); + } + +protected: + /// Serialize the header. + void serialize_header() { + auto header_data = header_.get_data(); + data_.resize(header_data.size()); + memcpy(data_.data(), header_data.data(), header_data.size()); + } + + /// Append a JPEG scan to the frame. + /// This will add the JPEG data to the frame. + /// @param scan The jpeg scan to append. + void add_scan(std::string_view scan) { + if (finalized_) { + // TODO: handle this error + return; } - - /// Add the EOI marker to the frame. - /// This will add the EOI marker to the frame. This must be called before - /// calling get_data(). - /// @note This will prevent any further scans from being added to the frame. - void finalize() { - if (!finalized_) { - finalized_ = true; - // add_eoi(); - } else { - // TODO: handle this error - // already finalized - } + data_.insert(std::end(data_), std::begin(scan), std::end(scan)); + } + + /// Add the EOI marker to the frame. + /// This will add the EOI marker to the frame. This must be called before + /// calling get_data(). + /// @note This will prevent any further scans from being added to the frame. + void finalize() { + if (!finalized_) { + finalized_ = true; + // add_eoi(); + } else { + // TODO: handle this error + // already finalized } - - /// Add the EOI marker to the frame. - void add_eoi() { - data_.push_back(0xFF); - data_.push_back(0xD9); - } - - std::vector data_; - JpegHeader header_; - bool finalized_ = false; - }; + } + + /// Add the EOI marker to the frame. + void add_eoi() { + data_.push_back(0xFF); + data_.push_back(0xD9); + } + + std::vector data_; + JpegHeader header_; + bool finalized_ = false; +}; } // namespace espp diff --git a/components/rtsp/include/jpeg_header.hpp b/components/rtsp/include/jpeg_header.hpp index c341cb83d..8c25ea4ab 100644 --- a/components/rtsp/include/jpeg_header.hpp +++ b/components/rtsp/include/jpeg_header.hpp @@ -1,359 +1,763 @@ -# pragma once +#pragma once #include #include #include namespace espp { - /// A class to generate a JPEG header for a given image size and quantization tables. - /// The header is generated once and then cached for future use. - /// The header is generated according to the JPEG standard and is compatible with - /// the ESP32 camera driver. - class JpegHeader { - public: - /// Create a JPEG header for a given image size and quantization tables. - /// @param width The image width in pixels. - /// @param height The image height in pixels. - /// @param q0_table The quantization table for the Y channel. - /// @param q1_table The quantization table for the Cb and Cr channels. - explicit JpegHeader(int width, int height, std::string_view q0_table, std::string_view q1_table) +/// A class to generate a JPEG header for a given image size and quantization tables. +/// The header is generated once and then cached for future use. +/// The header is generated according to the JPEG standard and is compatible with +/// the ESP32 camera driver. +class JpegHeader { +public: + /// Create a JPEG header for a given image size and quantization tables. + /// @param width The image width in pixels. + /// @param height The image height in pixels. + /// @param q0_table The quantization table for the Y channel. + /// @param q1_table The quantization table for the Cb and Cr channels. + explicit JpegHeader(int width, int height, std::string_view q0_table, std::string_view q1_table) : width_(width), height_(height), q0_table_(q0_table), q1_table_(q1_table) { - serialize(); - } - - /// Create a JPEG header from a given JPEG header data. - explicit JpegHeader(std::string_view data) - : data_(data.data(), data.data() + data.size()) { - parse(); - } + serialize(); + } - ~JpegHeader() {} + /// Create a JPEG header from a given JPEG header data. + explicit JpegHeader(std::string_view data) : data_(data.data(), data.data() + data.size()) { + parse(); + } - /// Get the image width. - /// @return The image width in pixels. - int get_width() const { - return width_; - } + ~JpegHeader() {} - /// Get the image height. - /// @return The image height in pixels. - int get_height() const { - return height_; - } + /// Get the image width. + /// @return The image width in pixels. + int get_width() const { return width_; } - /// Get the JPEG header data. - /// @return The JPEG header data. - std::string_view get_data() const { - return std::string_view(data_.data(), data_.size()); - } + /// Get the image height. + /// @return The image height in pixels. + int get_height() const { return height_; } - /// Get the Quantization table at the index. - /// @param index The index of the quantization table. - /// @return The quantization table. - std::string_view get_quantization_table(int index) const { - return index == 0 ? q0_table_ : q1_table_; - } + /// Get the JPEG header data. + /// @return The JPEG header data. + std::string_view get_data() const { return std::string_view(data_.data(), data_.size()); } - protected: + /// Get the Quantization table at the index. + /// @param index The index of the quantization table. + /// @return The quantization table. + std::string_view get_quantization_table(int index) const { + return index == 0 ? q0_table_ : q1_table_; + } - static constexpr int SOF0_SIZE = 19; - static constexpr int DQT_HEADER_SIZE = 5; +protected: + static constexpr int SOF0_SIZE = 19; + static constexpr int DQT_HEADER_SIZE = 5; - // JFIF APP0 Marker for version 1.2 with 72 DPI and no thumbnail - static constexpr char JFIF_APP0_DATA[] = { - 0xFF, 0xE0, // APP0 marker - 0x00, 0x10, // Length of APP0 data (16 bytes) + // JFIF APP0 Marker for version 1.2 with 72 DPI and no thumbnail + static constexpr char JFIF_APP0_DATA[] = { + 0xFF, 0xE0, // APP0 marker + 0x00, 0x10, // Length of APP0 data (16 bytes) 0x4A, 0x46, 0x49, 0x46, 0x00, // Identifier: ASCII "JFIF\0" - 0x01, 0x01, // Version number (1.1) - 0x01, // Units: 1 = dots per inch - 0x00, 0x00, // X density - 0x00, 0x00, // Y density - 0x00, 0x00 // No thumbnail - }; + 0x01, 0x01, // Version number (1.1) + 0x01, // Units: 1 = dots per inch + 0x00, 0x00, // X density + 0x00, 0x00, // Y density + 0x00, 0x00 // No thumbnail + }; - static constexpr char HUFFMAN_TABLES[] = { + static constexpr char HUFFMAN_TABLES[] = { // Huffman table DC (luminance) - 0xff, 0xc4, - 0x00, 0x1f, 0x00, - 0x00, 0x01, 0x05, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x0a, 0x0b, + 0xff, + 0xc4, + 0x00, + 0x1f, + 0x00, + 0x00, + 0x01, + 0x05, + 0x01, + 0x01, + 0x01, + 0x01, + 0x01, + 0x01, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x01, + 0x02, + 0x03, + 0x04, + 0x05, + 0x06, + 0x07, + 0x08, + 0x09, + 0x0a, + 0x0b, // Huffman table AC (luminance) - 0xff, 0xc4, - 0x00, 0xb5, 0x10, - 0x00, 0x02, 0x01, 0x03, 0x03, 0x02, 0x04, 0x03, 0x05, 0x05, 0x04, 0x04, 0x00, 0x00, 0x01, 0x7d, 0x01, 0x02, 0x03, 0x00, 0x04, 0x11, 0x05, 0x12, 0x21, 0x31, 0x41, 0x06, 0x13, 0x51, 0x61, 0x07, 0x22, 0x71, 0x14, 0x32, 0x81, 0x91, 0xa1, 0x08, 0x23, 0x42, 0xb1, 0xc1, 0x15, 0x52, 0xd1, 0xf0, 0x24, 0x33, 0x62, 0x72, 0x82, 0x09, 0x0a, 0x16, 0x17, 0x18, 0x19, 0x1a, 0x25, 0x26, 0x27, 0x28, 0x29, 0x2a, 0x34, 0x35, 0x36, 0x37, 0x38, 0x39, 0x3a, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x4a, 0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x63, 0x64, 0x65, 0x66, 0x67, 0x68, 0x69, 0x6a, 0x73, 0x74, 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a, 0x83, 0x84, 0x85, 0x86, 0x87, 0x88, 0x89, 0x8a, 0x92, 0x93, 0x94, 0x95, 0x96, 0x97, 0x98, 0x99, 0x9a, 0xa2, 0xa3, 0xa4, 0xa5, 0xa6, 0xa7, 0xa8, 0xa9, 0xaa, 0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba, 0xc2, 0xc3, 0xc4, 0xc5, 0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xd2, 0xd3, 0xd4, 0xd5, 0xd6, 0xd7, 0xd8, 0xd9, 0xda, 0xe1, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7, 0xe8, 0xe9, 0xea, 0xf1, 0xf2, 0xf3, 0xf4, 0xf5, 0xf6, 0xf7, 0xf8, 0xf9, 0xfa, + 0xff, + 0xc4, + 0x00, + 0xb5, + 0x10, + 0x00, + 0x02, + 0x01, + 0x03, + 0x03, + 0x02, + 0x04, + 0x03, + 0x05, + 0x05, + 0x04, + 0x04, + 0x00, + 0x00, + 0x01, + 0x7d, + 0x01, + 0x02, + 0x03, + 0x00, + 0x04, + 0x11, + 0x05, + 0x12, + 0x21, + 0x31, + 0x41, + 0x06, + 0x13, + 0x51, + 0x61, + 0x07, + 0x22, + 0x71, + 0x14, + 0x32, + 0x81, + 0x91, + 0xa1, + 0x08, + 0x23, + 0x42, + 0xb1, + 0xc1, + 0x15, + 0x52, + 0xd1, + 0xf0, + 0x24, + 0x33, + 0x62, + 0x72, + 0x82, + 0x09, + 0x0a, + 0x16, + 0x17, + 0x18, + 0x19, + 0x1a, + 0x25, + 0x26, + 0x27, + 0x28, + 0x29, + 0x2a, + 0x34, + 0x35, + 0x36, + 0x37, + 0x38, + 0x39, + 0x3a, + 0x43, + 0x44, + 0x45, + 0x46, + 0x47, + 0x48, + 0x49, + 0x4a, + 0x53, + 0x54, + 0x55, + 0x56, + 0x57, + 0x58, + 0x59, + 0x5a, + 0x63, + 0x64, + 0x65, + 0x66, + 0x67, + 0x68, + 0x69, + 0x6a, + 0x73, + 0x74, + 0x75, + 0x76, + 0x77, + 0x78, + 0x79, + 0x7a, + 0x83, + 0x84, + 0x85, + 0x86, + 0x87, + 0x88, + 0x89, + 0x8a, + 0x92, + 0x93, + 0x94, + 0x95, + 0x96, + 0x97, + 0x98, + 0x99, + 0x9a, + 0xa2, + 0xa3, + 0xa4, + 0xa5, + 0xa6, + 0xa7, + 0xa8, + 0xa9, + 0xaa, + 0xb2, + 0xb3, + 0xb4, + 0xb5, + 0xb6, + 0xb7, + 0xb8, + 0xb9, + 0xba, + 0xc2, + 0xc3, + 0xc4, + 0xc5, + 0xc6, + 0xc7, + 0xc8, + 0xc9, + 0xca, + 0xd2, + 0xd3, + 0xd4, + 0xd5, + 0xd6, + 0xd7, + 0xd8, + 0xd9, + 0xda, + 0xe1, + 0xe2, + 0xe3, + 0xe4, + 0xe5, + 0xe6, + 0xe7, + 0xe8, + 0xe9, + 0xea, + 0xf1, + 0xf2, + 0xf3, + 0xf4, + 0xf5, + 0xf6, + 0xf7, + 0xf8, + 0xf9, + 0xfa, // Huffman table DC (chrominance) - 0xff, 0xc4, - 0x00, 0x1f, 0x01, - 0x00, 0x03, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x01, 0x00, 0x00, 0x00, 0x00, 0x00, 0x00, 0x01, 0x02, 0x03, 0x04, 0x05, 0x06, 0x07, 0x08, 0x09, 0x0a, 0x0b, + 0xff, + 0xc4, + 0x00, + 0x1f, + 0x01, + 0x00, + 0x03, + 0x01, + 0x01, + 0x01, + 0x01, + 0x01, + 0x01, + 0x01, + 0x01, + 0x01, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x00, + 0x01, + 0x02, + 0x03, + 0x04, + 0x05, + 0x06, + 0x07, + 0x08, + 0x09, + 0x0a, + 0x0b, // Huffman table AC (chrominance) - 0xff, 0xc4, - 0x00, 0xb5, 0x11, - 0x00, 0x02, 0x01, 0x02, 0x04, 0x04, 0x03, 0x04, 0x07, 0x05, 0x04, 0x04, 0x00, 0x01, 0x02, 0x77, 0x00, 0x01, 0x02, 0x03, 0x11, 0x04, 0x05, 0x21, 0x31, 0x06, 0x12, 0x41, 0x51, 0x07, 0x61, 0x71, 0x13, 0x22, 0x32, 0x81, 0x08, 0x14, 0x42, 0x91, 0xa1, 0xb1, 0xc1, 0x09, 0x23, 0x33, 0x52, 0xf0, 0x15, 0x62, 0x72, 0xd1, 0x0a, 0x16, 0x24, 0x34, 0xe1, 0x25, 0xf1, 0x17, 0x18, 0x19, 0x1a, 0x26, 0x27, 0x28, 0x29, 0x2a, 0x35, 0x36, 0x37, 0x38, 0x39, 0x3a, 0x43, 0x44, 0x45, 0x46, 0x47, 0x48, 0x49, 0x4a, 0x53, 0x54, 0x55, 0x56, 0x57, 0x58, 0x59, 0x5a, 0x63, 0x64, 0x65, 0x66, 0x67, 0x68, 0x69, 0x6a, 0x73, 0x74, 0x75, 0x76, 0x77, 0x78, 0x79, 0x7a, 0x82, 0x83, 0x84, 0x85, 0x86, 0x87, 0x88, 0x89, 0x8a, 0x92, 0x93, 0x94, 0x95, 0x96, 0x97, 0x98, 0x99, 0x9a, 0xa2, 0xa3, 0xa4, 0xa5, 0xa6, 0xa7, 0xa8, 0xa9, 0xaa, 0xb2, 0xb3, 0xb4, 0xb5, 0xb6, 0xb7, 0xb8, 0xb9, 0xba, 0xc2, 0xc3, 0xc4, 0xc5, 0xc6, 0xc7, 0xc8, 0xc9, 0xca, 0xd2, 0xd3, 0xd4, 0xd5, 0xd6, 0xd7, 0xd8, 0xd9, 0xda, 0xe2, 0xe3, 0xe4, 0xe5, 0xe6, 0xe7, 0xe8, 0xe9, 0xea, 0xf2, 0xf3, 0xf4, 0xf5, 0xf6, 0xf7, 0xf8, 0xf9, 0xfa, - }; + 0xff, + 0xc4, + 0x00, + 0xb5, + 0x11, + 0x00, + 0x02, + 0x01, + 0x02, + 0x04, + 0x04, + 0x03, + 0x04, + 0x07, + 0x05, + 0x04, + 0x04, + 0x00, + 0x01, + 0x02, + 0x77, + 0x00, + 0x01, + 0x02, + 0x03, + 0x11, + 0x04, + 0x05, + 0x21, + 0x31, + 0x06, + 0x12, + 0x41, + 0x51, + 0x07, + 0x61, + 0x71, + 0x13, + 0x22, + 0x32, + 0x81, + 0x08, + 0x14, + 0x42, + 0x91, + 0xa1, + 0xb1, + 0xc1, + 0x09, + 0x23, + 0x33, + 0x52, + 0xf0, + 0x15, + 0x62, + 0x72, + 0xd1, + 0x0a, + 0x16, + 0x24, + 0x34, + 0xe1, + 0x25, + 0xf1, + 0x17, + 0x18, + 0x19, + 0x1a, + 0x26, + 0x27, + 0x28, + 0x29, + 0x2a, + 0x35, + 0x36, + 0x37, + 0x38, + 0x39, + 0x3a, + 0x43, + 0x44, + 0x45, + 0x46, + 0x47, + 0x48, + 0x49, + 0x4a, + 0x53, + 0x54, + 0x55, + 0x56, + 0x57, + 0x58, + 0x59, + 0x5a, + 0x63, + 0x64, + 0x65, + 0x66, + 0x67, + 0x68, + 0x69, + 0x6a, + 0x73, + 0x74, + 0x75, + 0x76, + 0x77, + 0x78, + 0x79, + 0x7a, + 0x82, + 0x83, + 0x84, + 0x85, + 0x86, + 0x87, + 0x88, + 0x89, + 0x8a, + 0x92, + 0x93, + 0x94, + 0x95, + 0x96, + 0x97, + 0x98, + 0x99, + 0x9a, + 0xa2, + 0xa3, + 0xa4, + 0xa5, + 0xa6, + 0xa7, + 0xa8, + 0xa9, + 0xaa, + 0xb2, + 0xb3, + 0xb4, + 0xb5, + 0xb6, + 0xb7, + 0xb8, + 0xb9, + 0xba, + 0xc2, + 0xc3, + 0xc4, + 0xc5, + 0xc6, + 0xc7, + 0xc8, + 0xc9, + 0xca, + 0xd2, + 0xd3, + 0xd4, + 0xd5, + 0xd6, + 0xd7, + 0xd8, + 0xd9, + 0xda, + 0xe2, + 0xe3, + 0xe4, + 0xe5, + 0xe6, + 0xe7, + 0xe8, + 0xe9, + 0xea, + 0xf2, + 0xf3, + 0xf4, + 0xf5, + 0xf6, + 0xf7, + 0xf8, + 0xf9, + 0xfa, + }; - // Scan header (SOS) - static constexpr char SOS[] = { - 0xFF, 0xDA, // SOS marker - 0x00, 0x0C, // length - 0x03, // number of components - 0x01, 0x00, // component IDs and Huffman tables - 0x02, 0x11, // component IDs and Huffman tables - 0x03, 0x11, // component IDs and Huffman tables + // Scan header (SOS) + static constexpr char SOS[] = { + 0xFF, 0xDA, // SOS marker + 0x00, 0x0C, // length + 0x03, // number of components + 0x01, 0x00, // component IDs and Huffman tables + 0x02, 0x11, // component IDs and Huffman tables + 0x03, 0x11, // component IDs and Huffman tables 0x00, 0x3F, 0x00 // Ss, Se, Ah/Al - }; + }; + int add_sof0(int offset) { + // add the SOF0 marker + data_[offset++] = 0xFF; + data_[offset++] = 0xC0; + // add the length of the marker + data_[offset++] = 0x00; + data_[offset++] = 0x11; + // add the precision + data_[offset++] = 0x08; + // add the height + data_[offset++] = (height_ >> 8) & 0xFF; + data_[offset++] = height_ & 0xFF; + // add the width + data_[offset++] = (width_ >> 8) & 0xFF; + data_[offset++] = width_ & 0xFF; + // add the number of components + data_[offset++] = 0x03; + // add the Y component + data_[offset++] = 0x01; + data_[offset++] = 0x21; + data_[offset++] = 0x00; + // add the Cb component + data_[offset++] = 0x02; + data_[offset++] = 0x11; + data_[offset++] = 0x01; + // add the Cr component + data_[offset++] = 0x03; + data_[offset++] = 0x11; + data_[offset++] = 0x01; + return offset; + } - int add_sof0(int offset) { - // add the SOF0 marker - data_[offset++] = 0xFF; - data_[offset++] = 0xC0; - // add the length of the marker - data_[offset++] = 0x00; - data_[offset++] = 0x11; - // add the precision - data_[offset++] = 0x08; - // add the height - data_[offset++] = (height_ >> 8) & 0xFF; - data_[offset++] = height_ & 0xFF; - // add the width - data_[offset++] = (width_ >> 8) & 0xFF; - data_[offset++] = width_ & 0xFF; - // add the number of components - data_[offset++] = 0x03; - // add the Y component - data_[offset++] = 0x01; - data_[offset++] = 0x21; - data_[offset++] = 0x00; - // add the Cb component - data_[offset++] = 0x02; - data_[offset++] = 0x11; - data_[offset++] = 0x01; - // add the Cr component - data_[offset++] = 0x03; - data_[offset++] = 0x11; - data_[offset++] = 0x01; - return offset; - } + void serialize() { + int header_size = 2 + sizeof(JFIF_APP0_DATA) + DQT_HEADER_SIZE + q0_table_.size() + + DQT_HEADER_SIZE + q1_table_.size() + sizeof(HUFFMAN_TABLES) + SOF0_SIZE + + sizeof(SOS); + // serialize the jpeg header to the data_ vector + data_.resize(header_size); + int offset = 0; - void serialize() { - int header_size = - 2 + - sizeof(JFIF_APP0_DATA) + - DQT_HEADER_SIZE + - q0_table_.size() + - DQT_HEADER_SIZE + - q1_table_.size() + - sizeof(HUFFMAN_TABLES) + - SOF0_SIZE + - sizeof(SOS); - // serialize the jpeg header to the data_ vector - data_.resize(header_size); - int offset = 0; + // add the SOI marker + data_[offset++] = 0xFF; + data_[offset++] = 0xD8; - // add the SOI marker - data_[offset++] = 0xFF; - data_[offset++] = 0xD8; + // add the JFIF APP0 marker + memcpy(data_.data() + offset, JFIF_APP0_DATA, sizeof(JFIF_APP0_DATA)); + offset += sizeof(JFIF_APP0_DATA); - // add the JFIF APP0 marker - memcpy(data_.data() + offset, JFIF_APP0_DATA, sizeof(JFIF_APP0_DATA)); - offset += sizeof(JFIF_APP0_DATA); + // add the DQT marker for luminance + data_[offset++] = 0xFF; + data_[offset++] = 0xDB; + data_[offset++] = 0x00; + data_[offset++] = 0x43; + data_[offset++] = 0x00; + memcpy(data_.data() + offset, q0_table_.data(), q0_table_.size()); + offset += q0_table_.size(); - // add the DQT marker for luminance - data_[offset++] = 0xFF; - data_[offset++] = 0xDB; - data_[offset++] = 0x00; - data_[offset++] = 0x43; - data_[offset++] = 0x00; - memcpy(data_.data() + offset, q0_table_.data(), q0_table_.size()); - offset += q0_table_.size(); + // add the DQT marker for chrominance + data_[offset++] = 0xFF; + data_[offset++] = 0xDB; + data_[offset++] = 0x00; + data_[offset++] = 0x43; + data_[offset++] = 0x01; + memcpy(data_.data() + offset, q1_table_.data(), q1_table_.size()); + offset += q1_table_.size(); - // add the DQT marker for chrominance - data_[offset++] = 0xFF; - data_[offset++] = 0xDB; - data_[offset++] = 0x00; - data_[offset++] = 0x43; - data_[offset++] = 0x01; - memcpy(data_.data() + offset, q1_table_.data(), q1_table_.size()); - offset += q1_table_.size(); + // add huffman tables + memcpy(data_.data() + offset, HUFFMAN_TABLES, sizeof(HUFFMAN_TABLES)); + offset += sizeof(HUFFMAN_TABLES); - // add huffman tables - memcpy(data_.data() + offset, HUFFMAN_TABLES, sizeof(HUFFMAN_TABLES)); - offset += sizeof(HUFFMAN_TABLES); + // add the SOF0 + offset = add_sof0(offset); - // add the SOF0 - offset = add_sof0(offset); + // add the SOS marker + memcpy(data_.data() + offset, SOS, sizeof(SOS)); + offset += sizeof(SOS); + } - // add the SOS marker - memcpy(data_.data() + offset, SOS, sizeof(SOS)); - offset += sizeof(SOS); + void parse() { + // parse the jpeg header from the data_ vector + int offset = 0; + // check the SOI marker + if (data_[offset++] != 0xFF || data_[offset++] != 0xD8) { + fmt::print("Invalid SOI marker\n"); + return; } - - void parse() { - // parse the jpeg header from the data_ vector - int offset = 0; - // check the SOI marker - if (data_[offset++] != 0xFF || data_[offset++] != 0xD8) { - fmt::print("Invalid SOI marker\n"); - return; - } - // check the JFIF APP0 marker - if (memcmp(data_.data() + offset, JFIF_APP0_DATA, sizeof(JFIF_APP0_DATA)) != 0) { - fmt::print("Invalid JFIF APP0 marker\n"); - return; - } - offset += sizeof(JFIF_APP0_DATA); - // check the DQT marker for luminance - if (data_[offset++] != 0xFF || data_[offset++] != 0xDB) { - fmt::print("Invalid DQT marker\n"); - return; - } - if (data_[offset++] != 0x00 || data_[offset++] != 0x43) { - fmt::print("Invalid DQT marker\n"); - return; - } - if (data_[offset++] != 0x00) { - fmt::print("Invalid DQT marker\n"); - return; - } - q0_table_ = std::string_view(data_.data() + offset, 64); - offset += 64; - // check the DQT marker for chrominance - if (data_[offset++] != 0xFF || data_[offset++] != 0xDB) { - fmt::print("Invalid DQT marker\n"); - return; - } - if (data_[offset++] != 0x00 || data_[offset++] != 0x43) { - fmt::print("Invalid DQT marker\n"); - return; - } - if (data_[offset++] != 0x01) { - fmt::print("Invalid DQT marker\n"); - return; - } - q1_table_ = std::string_view(data_.data() + offset, 64); - offset += 64; - // check huffman tables - if (data_[offset++] != 0xFF || data_[offset++] != 0xC4) { - fmt::print("Invalid huffman tables marker\n"); - return; - } - if (data_[offset++] != 0x00 || data_[offset++] != 0x1f || data_[offset++] != 0x00) { - fmt::print("Invalid huffman tables marker\n"); - return; - } - offset += sizeof(HUFFMAN_TABLES) - 5; - // check the SOF0 marker - if (data_[offset++] != 0xFF || data_[offset++] != 0xC0) { - fmt::print("Invalid SOF0 marker\n"); - return; - } - if (data_[offset++] != 0x00 || data_[offset++] != 0x11) { - fmt::print("Invalid SOF0 marker\n"); - return; - } - // skip the precision - offset++; - // get the height and width - height_ = (data_[offset] << 8) | data_[offset+1]; - offset += 2; - width_ = (data_[offset] << 8) | data_[offset+1]; - offset += 2; - if (data_[offset++] != 0x03) { - fmt::print("Invalid SOF0 marker\n"); - return; - } - if (data_[offset++] != 0x01) { - fmt::print("Invalid SOF0 marker\n"); - return; - } - if (data_[offset++] != 0x21) { - fmt::print("Invalid SOF0 marker\n"); - return; - } - if (data_[offset++] != 0x00) { - fmt::print("Invalid SOF0 marker\n"); - return; - } - if (data_[offset++] != 0x02) { - fmt::print("Invalid SOF0 marker\n"); - return; - } - if (data_[offset++] != 0x11) { - fmt::print("Invalid SOF0 marker\n"); - return; - } - if (data_[offset++] != 0x01) { - fmt::print("Invalid SOF0 marker\n"); - return; - } - if (data_[offset++] != 0x03) { - fmt::print("Invalid SOF0 marker\n"); - return; - } - if (data_[offset++] != 0x11) { - fmt::print("Invalid SOF0 marker\n"); - return; - } - if (data_[offset++] != 0x01) { - fmt::print("Invalid SOF0 marker\n"); - return; - } - // check the SOS marker - if (data_[offset++] != 0xFF || data_[offset++] != 0xDA) { - fmt::print("Invalid SOS marker\n"); - return; - } - if (data_[offset++] != 0x00 || data_[offset++] != 0x0C) { - fmt::print("Invalid SOS marker\n"); - return; - } - if (data_[offset++] != 0x03) { - fmt::print("Invalid SOS marker\n"); - return; - } - if (data_[offset++] != 0x01) { - fmt::print("Invalid SOS marker\n"); - return; - } - if (data_[offset++] != 0x00) { - fmt::print("Invalid SOS marker\n"); - return; - } - if (data_[offset++] != 0x02) { - fmt::print("Invalid SOS marker\n"); - return; - } - if (data_[offset++] != 0x11) { - fmt::print("Invalid SOS marker\n"); - return; - } - if (data_[offset++] != 0x03) { - fmt::print("Invalid SOS marker\n"); - return; - } - if (data_[offset++] != 0x11) { - fmt::print("Invalid SOS marker\n"); - return; - } - if (data_[offset++] != 0x00) { - fmt::print("Invalid SOS marker\n"); - return; - } - if (data_[offset++] != 0x3F) { - fmt::print("Invalid SOS marker\n"); - return; - } - if (data_[offset++] != 0x00) { - fmt::print("Invalid SOS marker\n"); - return; - } - data_.resize(offset); + // check the JFIF APP0 marker + if (memcmp(data_.data() + offset, JFIF_APP0_DATA, sizeof(JFIF_APP0_DATA)) != 0) { + fmt::print("Invalid JFIF APP0 marker\n"); + return; + } + offset += sizeof(JFIF_APP0_DATA); + // check the DQT marker for luminance + if (data_[offset++] != 0xFF || data_[offset++] != 0xDB) { + fmt::print("Invalid DQT marker\n"); + return; + } + if (data_[offset++] != 0x00 || data_[offset++] != 0x43) { + fmt::print("Invalid DQT marker\n"); + return; + } + if (data_[offset++] != 0x00) { + fmt::print("Invalid DQT marker\n"); + return; + } + q0_table_ = std::string_view(data_.data() + offset, 64); + offset += 64; + // check the DQT marker for chrominance + if (data_[offset++] != 0xFF || data_[offset++] != 0xDB) { + fmt::print("Invalid DQT marker\n"); + return; + } + if (data_[offset++] != 0x00 || data_[offset++] != 0x43) { + fmt::print("Invalid DQT marker\n"); + return; + } + if (data_[offset++] != 0x01) { + fmt::print("Invalid DQT marker\n"); + return; + } + q1_table_ = std::string_view(data_.data() + offset, 64); + offset += 64; + // check huffman tables + if (data_[offset++] != 0xFF || data_[offset++] != 0xC4) { + fmt::print("Invalid huffman tables marker\n"); + return; + } + if (data_[offset++] != 0x00 || data_[offset++] != 0x1f || data_[offset++] != 0x00) { + fmt::print("Invalid huffman tables marker\n"); + return; + } + offset += sizeof(HUFFMAN_TABLES) - 5; + // check the SOF0 marker + if (data_[offset++] != 0xFF || data_[offset++] != 0xC0) { + fmt::print("Invalid SOF0 marker\n"); + return; + } + if (data_[offset++] != 0x00 || data_[offset++] != 0x11) { + fmt::print("Invalid SOF0 marker\n"); + return; + } + // skip the precision + offset++; + // get the height and width + height_ = (data_[offset] << 8) | data_[offset + 1]; + offset += 2; + width_ = (data_[offset] << 8) | data_[offset + 1]; + offset += 2; + if (data_[offset++] != 0x03) { + fmt::print("Invalid SOF0 marker\n"); + return; } + if (data_[offset++] != 0x01) { + fmt::print("Invalid SOF0 marker\n"); + return; + } + if (data_[offset++] != 0x21) { + fmt::print("Invalid SOF0 marker\n"); + return; + } + if (data_[offset++] != 0x00) { + fmt::print("Invalid SOF0 marker\n"); + return; + } + if (data_[offset++] != 0x02) { + fmt::print("Invalid SOF0 marker\n"); + return; + } + if (data_[offset++] != 0x11) { + fmt::print("Invalid SOF0 marker\n"); + return; + } + if (data_[offset++] != 0x01) { + fmt::print("Invalid SOF0 marker\n"); + return; + } + if (data_[offset++] != 0x03) { + fmt::print("Invalid SOF0 marker\n"); + return; + } + if (data_[offset++] != 0x11) { + fmt::print("Invalid SOF0 marker\n"); + return; + } + if (data_[offset++] != 0x01) { + fmt::print("Invalid SOF0 marker\n"); + return; + } + // check the SOS marker + if (data_[offset++] != 0xFF || data_[offset++] != 0xDA) { + fmt::print("Invalid SOS marker\n"); + return; + } + if (data_[offset++] != 0x00 || data_[offset++] != 0x0C) { + fmt::print("Invalid SOS marker\n"); + return; + } + if (data_[offset++] != 0x03) { + fmt::print("Invalid SOS marker\n"); + return; + } + if (data_[offset++] != 0x01) { + fmt::print("Invalid SOS marker\n"); + return; + } + if (data_[offset++] != 0x00) { + fmt::print("Invalid SOS marker\n"); + return; + } + if (data_[offset++] != 0x02) { + fmt::print("Invalid SOS marker\n"); + return; + } + if (data_[offset++] != 0x11) { + fmt::print("Invalid SOS marker\n"); + return; + } + if (data_[offset++] != 0x03) { + fmt::print("Invalid SOS marker\n"); + return; + } + if (data_[offset++] != 0x11) { + fmt::print("Invalid SOS marker\n"); + return; + } + if (data_[offset++] != 0x00) { + fmt::print("Invalid SOS marker\n"); + return; + } + if (data_[offset++] != 0x3F) { + fmt::print("Invalid SOS marker\n"); + return; + } + if (data_[offset++] != 0x00) { + fmt::print("Invalid SOS marker\n"); + return; + } + data_.resize(offset); + } - int width_; - int height_; - std::string_view q0_table_; - std::string_view q1_table_; + int width_; + int height_; + std::string_view q0_table_; + std::string_view q1_table_; - std::vector data_; - }; + std::vector data_; +}; } // namespace espp diff --git a/components/rtsp/include/rtcp_packet.hpp b/components/rtsp/include/rtcp_packet.hpp index bb963d448..de35f1880 100644 --- a/components/rtsp/include/rtcp_packet.hpp +++ b/components/rtsp/include/rtcp_packet.hpp @@ -4,24 +4,22 @@ #include namespace espp { - /// @brief A class to represent a RTCP packet - /// @details This class is used to represent a RTCP packet. - /// It is used as a base class for all RTCP packet types. - class RtcpPacket { - public: - RtcpPacket() = default; - virtual ~RtcpPacket() = default; +/// @brief A class to represent a RTCP packet +/// @details This class is used to represent a RTCP packet. +/// It is used as a base class for all RTCP packet types. +class RtcpPacket { +public: + RtcpPacket() = default; + virtual ~RtcpPacket() = default; - std::string_view get_data() const { - return std::string_view(reinterpret_cast(m_buffer), m_bufferSize); - } + std::string_view get_data() const { + return std::string_view(reinterpret_cast(m_buffer), m_bufferSize); + } - void serialize() { + void serialize() {} - } - - protected: - uint8_t* m_buffer; - uint32_t m_bufferSize; - }; +protected: + uint8_t *m_buffer; + uint32_t m_bufferSize; +}; } // namespace espp diff --git a/components/rtsp/include/rtp_jpeg_packet.hpp b/components/rtsp/include/rtp_jpeg_packet.hpp index c4cbff166..7942f5258 100644 --- a/components/rtsp/include/rtp_jpeg_packet.hpp +++ b/components/rtsp/include/rtp_jpeg_packet.hpp @@ -3,225 +3,212 @@ #include "rtp_packet.hpp" namespace espp { - /// RTP packet for JPEG video. - /// The RTP payload for JPEG is defined in RFC 2435. - class RtpJpegPacket : public RtpPacket { - public: - /// Construct an RTP packet from a buffer. - /// @param data The buffer containing the RTP packet. - explicit RtpJpegPacket(std::string_view data) : RtpPacket(data) { - parse_mjpeg_header(); +/// RTP packet for JPEG video. +/// The RTP payload for JPEG is defined in RFC 2435. +class RtpJpegPacket : public RtpPacket { +public: + /// Construct an RTP packet from a buffer. + /// @param data The buffer containing the RTP packet. + explicit RtpJpegPacket(std::string_view data) : RtpPacket(data) { parse_mjpeg_header(); } + + /// Construct an RTP packet from fields + /// @details This will construct a packet with quantization tables, so it + /// can only be used for the first packet in a frame. + /// @param type_specific The type-specific field. + /// @param frag_type The fragment type field. + /// @param q The q field. + /// @param width The width field. + /// @param height The height field. + /// @param q0 The first quantization table. + /// @param q1 The second quantization table. + /// @param scan_data The scan data. + explicit RtpJpegPacket(const int type_specific, const int frag_type, const int q, const int width, + const int height, std::string_view q0, std::string_view q1, + std::string_view scan_data) + : RtpPacket(PAYLOAD_OFFSET_WITH_QUANT + scan_data.size()), type_specific_(type_specific), + offset_(0), frag_type_(frag_type), q_(q), width_(width), height_(height) { + + jpeg_data_start_ = PAYLOAD_OFFSET_WITH_QUANT; + jpeg_data_size_ = scan_data.size(); + + serialize_mjpeg_header(); + serialize_q_tables(q0, q1); + + auto &packet = get_packet(); + size_t jpeg_offset = jpeg_data_start_ + get_rtp_header_size(); + memcpy(packet.data() + jpeg_offset, scan_data.data(), scan_data.size()); + } + + /// Construct an RTP packet from fields + /// @details This will construct a packet without quantization tables, so it + /// cannot be used for the first packet in a frame. + /// @param type_specific The type-specific field. + /// @param offset The offset field. + /// @param frag_type The fragment type field. + /// @param q The q field. + /// @param width The width field. + /// @param height The height field. + /// @param scan_data The scan data. + explicit RtpJpegPacket(const int type_specific, const int offset, const int frag_type, + const int q, const int width, const int height, std::string_view scan_data) + : RtpPacket(PAYLOAD_OFFSET_NO_QUANT + scan_data.size()), type_specific_(type_specific), + offset_(offset), frag_type_(frag_type), q_(q), width_(width), height_(height) { + jpeg_data_start_ = PAYLOAD_OFFSET_NO_QUANT; + jpeg_data_size_ = scan_data.size(); + + serialize_mjpeg_header(); + + auto &packet = get_packet(); + size_t jpeg_offset = jpeg_data_start_ + get_rtp_header_size(); + memcpy(packet.data() + jpeg_offset, scan_data.data(), scan_data.size()); + } + + ~RtpJpegPacket() {} + + /// Get the type-specific field. + /// @return The type-specific field. + int get_type_specific() const { return type_specific_; } + + /// Get the offset field. + /// @return The offset field. + int get_offset() const { return offset_; } + + /// Get the fragment type field. + /// @return The fragment type field. + int get_q() const { return q_; } + + /// Get the fragment type field. + /// @return The fragment type field. + int get_width() const { return width_; } + + /// Get the fragment type field. + /// @return The fragment type field. + int get_height() const { return height_; } + + /// Get the mjepg header. + /// @return The mjepg header. + std::string_view get_mjpeg_header() { + return std::string_view(get_payload().data(), MJPEG_HEADER_SIZE); + } + + /// Get whether the packet contains quantization tables. + /// @note The quantization tables are optional. If they are present, the + /// number of quantization tables is always 2. + /// @note This check is based on the value of the q field. If the q field + /// is 128-256, the packet contains quantization tables. + /// @return Whether the packet contains quantization tables. + bool has_q_tables() const { return q_ >= 128 && q_ <= 256; } + + /// Get the number of quantization tables. + /// @note The quantization tables are optional. If they are present, the + /// number of quantization tables is always 2. + /// @note Only the first packet in a frame contains quantization tables. + /// @return The number of quantization tables. + int get_num_q_tables() const { return q_tables_.size(); } + + /// Get the quantization table at the specified index. + /// @param index The index of the quantization table. + /// @return The quantization table at the specified index. + std::string_view get_q_table(int index) const { + if (index < get_num_q_tables()) { + return q_tables_[index]; } + return {}; + } - /// Construct an RTP packet from fields - /// @details This will construct a packet with quantization tables, so it - /// can only be used for the first packet in a frame. - /// @param type_specific The type-specific field. - /// @param frag_type The fragment type field. - /// @param q The q field. - /// @param width The width field. - /// @param height The height field. - /// @param q0 The first quantization table. - /// @param q1 The second quantization table. - /// @param scan_data The scan data. - explicit RtpJpegPacket(const int type_specific, const int frag_type, - const int q, const int width, const int height, - std::string_view q0, std::string_view q1, - std::string_view scan_data) - : RtpPacket(PAYLOAD_OFFSET_WITH_QUANT + scan_data.size()), - type_specific_(type_specific), - offset_(0), - frag_type_(frag_type), - q_(q), - width_(width), - height_(height) { - - jpeg_data_start_ = PAYLOAD_OFFSET_WITH_QUANT; - jpeg_data_size_ = scan_data.size(); - - serialize_mjpeg_header(); - serialize_q_tables(q0, q1); - - auto& packet = get_packet(); - size_t jpeg_offset = jpeg_data_start_ + get_rtp_header_size(); - memcpy(packet.data() + jpeg_offset, scan_data.data(), scan_data.size()); + void set_q_table(int index, std::string_view q_table) { + if (index < get_num_q_tables()) { + q_tables_[index] = q_table; } - - /// Construct an RTP packet from fields - /// @details This will construct a packet without quantization tables, so it - /// cannot be used for the first packet in a frame. - /// @param type_specific The type-specific field. - /// @param offset The offset field. - /// @param frag_type The fragment type field. - /// @param q The q field. - /// @param width The width field. - /// @param height The height field. - /// @param scan_data The scan data. - explicit RtpJpegPacket(const int type_specific, const int offset, const int frag_type, - const int q, const int width, const int height, - std::string_view scan_data) - : RtpPacket(PAYLOAD_OFFSET_NO_QUANT + scan_data.size()), - type_specific_(type_specific), - offset_(offset), - frag_type_(frag_type), - q_(q), - width_(width), - height_(height) { - jpeg_data_start_ = PAYLOAD_OFFSET_NO_QUANT; - jpeg_data_size_ = scan_data.size(); - - serialize_mjpeg_header(); - - auto& packet = get_packet(); - size_t jpeg_offset = jpeg_data_start_ + get_rtp_header_size(); - memcpy(packet.data() + jpeg_offset, scan_data.data(), scan_data.size()); - } - - ~RtpJpegPacket() {} - - /// Get the type-specific field. - /// @return The type-specific field. - int get_type_specific() const { return type_specific_; } - - /// Get the offset field. - /// @return The offset field. - int get_offset() const { return offset_; } - - /// Get the fragment type field. - /// @return The fragment type field. - int get_q() const { return q_; } - - /// Get the fragment type field. - /// @return The fragment type field. - int get_width() const { return width_; } - - /// Get the fragment type field. - /// @return The fragment type field. - int get_height() const { return height_; } - - /// Get the mjepg header. - /// @return The mjepg header. - std::string_view get_mjpeg_header() { - return std::string_view(get_payload().data(), MJPEG_HEADER_SIZE); - } - - /// Get whether the packet contains quantization tables. - /// @note The quantization tables are optional. If they are present, the - /// number of quantization tables is always 2. - /// @note This check is based on the value of the q field. If the q field - /// is 128-256, the packet contains quantization tables. - /// @return Whether the packet contains quantization tables. - bool has_q_tables() const { return q_ >= 128 && q_ <= 256; } - - /// Get the number of quantization tables. - /// @note The quantization tables are optional. If they are present, the - /// number of quantization tables is always 2. - /// @note Only the first packet in a frame contains quantization tables. - /// @return The number of quantization tables. - int get_num_q_tables() const { return q_tables_.size(); } - - /// Get the quantization table at the specified index. - /// @param index The index of the quantization table. - /// @return The quantization table at the specified index. - std::string_view get_q_table(int index) const { - if (index < get_num_q_tables()) { - return q_tables_[index]; - } - return {}; - } - - void set_q_table(int index, std::string_view q_table) { - if (index < get_num_q_tables()) { - q_tables_[index] = q_table; - } - } - - /// Get the JPEG data. - /// The jpeg data is the payload minus the mjpeg header and quantization - /// tables. - /// @return The JPEG data. - std::string_view get_jpeg_data() const { - auto payload = get_payload(); - return std::string_view(payload.data() + jpeg_data_start_, jpeg_data_size_); - } - - protected: - static constexpr int MJPEG_HEADER_SIZE = 8; - static constexpr int QUANT_HEADER_SIZE = 4; - static constexpr int NUM_Q_TABLES = 2; - static constexpr int Q_TABLE_SIZE = 64; - - static constexpr int PAYLOAD_OFFSET_NO_QUANT = MJPEG_HEADER_SIZE; - static constexpr int PAYLOAD_OFFSET_WITH_QUANT = MJPEG_HEADER_SIZE + QUANT_HEADER_SIZE + (NUM_Q_TABLES * Q_TABLE_SIZE); - - void parse_mjpeg_header() { - auto payload = get_payload(); - type_specific_ = payload[0]; - offset_ = (payload[1] << 16) | (payload[2] << 8) | payload[3]; - frag_type_ = payload[4]; - q_ = payload[5]; - width_ = payload[6] * 8; - height_ = payload[7] * 8; - - size_t offset = MJPEG_HEADER_SIZE; - - if (has_q_tables()) { - int num_quant_bytes = payload[11]; - int expected_num_quant_bytes = NUM_Q_TABLES * Q_TABLE_SIZE; - if (num_quant_bytes == expected_num_quant_bytes) { - q_tables_.resize(NUM_Q_TABLES); - offset += QUANT_HEADER_SIZE; - for (int i = 0; i < NUM_Q_TABLES; i++) { - q_tables_[i] = std::string_view(payload.data() + offset, Q_TABLE_SIZE); - offset += Q_TABLE_SIZE; - } + } + + /// Get the JPEG data. + /// The jpeg data is the payload minus the mjpeg header and quantization + /// tables. + /// @return The JPEG data. + std::string_view get_jpeg_data() const { + auto payload = get_payload(); + return std::string_view(payload.data() + jpeg_data_start_, jpeg_data_size_); + } + +protected: + static constexpr int MJPEG_HEADER_SIZE = 8; + static constexpr int QUANT_HEADER_SIZE = 4; + static constexpr int NUM_Q_TABLES = 2; + static constexpr int Q_TABLE_SIZE = 64; + + static constexpr int PAYLOAD_OFFSET_NO_QUANT = MJPEG_HEADER_SIZE; + static constexpr int PAYLOAD_OFFSET_WITH_QUANT = + MJPEG_HEADER_SIZE + QUANT_HEADER_SIZE + (NUM_Q_TABLES * Q_TABLE_SIZE); + + void parse_mjpeg_header() { + auto payload = get_payload(); + type_specific_ = payload[0]; + offset_ = (payload[1] << 16) | (payload[2] << 8) | payload[3]; + frag_type_ = payload[4]; + q_ = payload[5]; + width_ = payload[6] * 8; + height_ = payload[7] * 8; + + size_t offset = MJPEG_HEADER_SIZE; + + if (has_q_tables()) { + int num_quant_bytes = payload[11]; + int expected_num_quant_bytes = NUM_Q_TABLES * Q_TABLE_SIZE; + if (num_quant_bytes == expected_num_quant_bytes) { + q_tables_.resize(NUM_Q_TABLES); + offset += QUANT_HEADER_SIZE; + for (int i = 0; i < NUM_Q_TABLES; i++) { + q_tables_[i] = std::string_view(payload.data() + offset, Q_TABLE_SIZE); + offset += Q_TABLE_SIZE; } } - - jpeg_data_start_ = offset; - jpeg_data_size_ = payload.size() - jpeg_data_start_; - } - - void serialize_mjpeg_header() { - auto& packet = get_packet(); - size_t offset = get_rtp_header_size(); - - packet[offset++] = type_specific_; - packet[offset++] = (offset_ >> 16) & 0xff; - packet[offset++] = (offset_ >> 8) & 0xff; - packet[offset++] = offset_ & 0xff; - packet[offset++] = frag_type_; - packet[offset++] = q_; - packet[offset++] = width_ / 8; - packet[offset++] = height_ / 8; - } - - void serialize_q_tables(std::string_view q0, std::string_view q1) { - q_tables_.resize(NUM_Q_TABLES); - auto& packet = get_packet(); - int offset = get_rtp_header_size() + MJPEG_HEADER_SIZE; - packet[offset++] = 0; - packet[offset++] = 0; - packet[offset++] = 0; - packet[offset++] = NUM_Q_TABLES * Q_TABLE_SIZE; - - memcpy(packet.data() + offset, q0.data(), Q_TABLE_SIZE); - q_tables_[0] = std::string_view(packet.data() + offset, Q_TABLE_SIZE); - offset += Q_TABLE_SIZE; - - memcpy(packet.data() + offset, q1.data(), Q_TABLE_SIZE); - q_tables_[1] = std::string_view(packet.data() + offset, Q_TABLE_SIZE); - offset += Q_TABLE_SIZE; } - int type_specific_{0}; - int offset_{0}; - int frag_type_{0}; - int q_{0}; - int width_{0}; - int height_{0}; - int jpeg_data_start_{0}; - int jpeg_data_size_{0}; - std::vector q_tables_; - }; + jpeg_data_start_ = offset; + jpeg_data_size_ = payload.size() - jpeg_data_start_; + } + + void serialize_mjpeg_header() { + auto &packet = get_packet(); + size_t offset = get_rtp_header_size(); + + packet[offset++] = type_specific_; + packet[offset++] = (offset_ >> 16) & 0xff; + packet[offset++] = (offset_ >> 8) & 0xff; + packet[offset++] = offset_ & 0xff; + packet[offset++] = frag_type_; + packet[offset++] = q_; + packet[offset++] = width_ / 8; + packet[offset++] = height_ / 8; + } + + void serialize_q_tables(std::string_view q0, std::string_view q1) { + q_tables_.resize(NUM_Q_TABLES); + auto &packet = get_packet(); + int offset = get_rtp_header_size() + MJPEG_HEADER_SIZE; + packet[offset++] = 0; + packet[offset++] = 0; + packet[offset++] = 0; + packet[offset++] = NUM_Q_TABLES * Q_TABLE_SIZE; + + memcpy(packet.data() + offset, q0.data(), Q_TABLE_SIZE); + q_tables_[0] = std::string_view(packet.data() + offset, Q_TABLE_SIZE); + offset += Q_TABLE_SIZE; + + memcpy(packet.data() + offset, q1.data(), Q_TABLE_SIZE); + q_tables_[1] = std::string_view(packet.data() + offset, Q_TABLE_SIZE); + offset += Q_TABLE_SIZE; + } + + int type_specific_{0}; + int offset_{0}; + int frag_type_{0}; + int q_{0}; + int width_{0}; + int height_{0}; + int jpeg_data_start_{0}; + int jpeg_data_size_{0}; + std::vector q_tables_; +}; } // namespace espp diff --git a/components/rtsp/include/rtp_packet.hpp b/components/rtsp/include/rtp_packet.hpp index 100011bf7..7ed97b275 100644 --- a/components/rtsp/include/rtp_packet.hpp +++ b/components/rtsp/include/rtp_packet.hpp @@ -5,150 +5,143 @@ #include namespace espp { - /// RtpPacket is a class to parse RTP packet. - class RtpPacket { - public: - /// Construct an empty RtpPacket. - /// The packet_ vector is empty and the header fields are set to 0. - RtpPacket() : version_(2), padding_(false), extension_(false), csrc_count_(0), - marker_(false), payload_type_(0), sequence_number_(0), timestamp_(0), - ssrc_(0), payload_size_(0) { - // ensure that the packet_ vector is at least RTP_HEADER_SIZE bytes long - packet_.resize(RTP_HEADER_SIZE); - } - - /// Construct an RtpPacket with a payload of size payload_size. - explicit RtpPacket(size_t payload_size) : version_(2), padding_(false), extension_(false), csrc_count_(0), - marker_(false), payload_type_(0), sequence_number_(0), timestamp_(0), - ssrc_(0), payload_size_(payload_size) { - // ensure that the packet_ vector is at least RTP_HEADER_SIZE + payload_size bytes long - packet_.resize(RTP_HEADER_SIZE + payload_size); - } - - /// Construct an RtpPacket from a string_view. - /// Store the string_view in the packet_ vector and parses the header. - /// @param data The string_view to parse. - explicit RtpPacket(std::string_view data) { - packet_.assign(data.begin(), data.end()); - payload_size_ = packet_.size() - RTP_HEADER_SIZE; - if (packet_.size() >= RTP_HEADER_SIZE) - parse_rtp_header(); - } - - ~RtpPacket() {} - - /// Getters for the RTP header fields. - int get_version() const { return version_; } - bool get_padding() const { return padding_; } - bool get_extension() const { return extension_; } - int get_csrc_count() const { return csrc_count_; } - bool get_marker() const { return marker_; } - int get_payload_type() const { return payload_type_; } - int get_sequence_number() const { return sequence_number_; } - int get_timestamp() const { return timestamp_; } - int get_ssrc() const { return ssrc_; } - - /// Setters for the RTP header fields. - void set_version(int version) { version_ = version; } - void set_padding(bool padding) { padding_ = padding; } - void set_extension(bool extension) { extension_ = extension; } - void set_csrc_count(int csrc_count) { csrc_count_ = csrc_count; } - void set_marker(bool marker) { marker_ = marker; } - void set_payload_type(int payload_type) { payload_type_ = payload_type; } - void set_sequence_number(int sequence_number) { sequence_number_ = sequence_number; } - void set_timestamp(int timestamp) { timestamp_ = timestamp; } - void set_ssrc(int ssrc) { ssrc_ = ssrc; } - - /// Serialize the RTP header. - /// @note This method should be called after modifying the RTP header fields. - /// @note This method does not serialize the payload. To set the payload, use - /// set_payload(). - /// To get the payload, use get_payload(). - void serialize() { - serialize_rtp_header(); - } - - /// Get a string_view of the whole packet. - /// @note The string_view is valid as long as the packet_ vector is not modified. - /// @note If you manually build the packet_ vector, you should make sure that you - /// call serialize() before calling this method. - /// @return A string_view of the whole packet. - std::string_view get_data() const { - return std::string_view(packet_.data(), packet_.size()); - } - - /// Get the size of the RTP header. - /// @return The size of the RTP header. - size_t get_rtp_header_size() const { - return RTP_HEADER_SIZE; - } - - /// Get a string_view of the RTP header. - /// @return A string_view of the RTP header. - std::string_view get_rpt_header() const { - return std::string_view(packet_.data(), RTP_HEADER_SIZE); - } - - /// Get a reference to the packet_ vector. - /// @return A reference to the packet_ vector. - std::vector& get_packet() { - return packet_; - } - - /// Get a string_view of the payload. - /// @return A string_view of the payload. - std::string_view get_payload() const { - return std::string_view(packet_.data() + RTP_HEADER_SIZE, payload_size_); - } - - /// Set the payload. - /// @param payload The payload to set. - void set_payload(std::string_view payload) { - packet_.resize(RTP_HEADER_SIZE + payload.size()); - std::copy(payload.begin(), payload.end(), packet_.begin() + RTP_HEADER_SIZE); - payload_size_ = payload.size(); - } - - protected: - static constexpr int RTP_HEADER_SIZE = 12; - - void parse_rtp_header() { - version_ = (packet_[0] & 0xC0) >> 6; - padding_ = (packet_[0] & 0x20) >> 5; - extension_ = (packet_[0] & 0x10) >> 4; - csrc_count_ = packet_[0] & 0x0F; - marker_ = (packet_[1] & 0x80) >> 7; - payload_type_ = packet_[1] & 0x7F; - sequence_number_ = (packet_[2] << 8) | packet_[3]; - timestamp_ = (packet_[4] << 24) | (packet_[5] << 16) | (packet_[6] << 8) | packet_[7]; - ssrc_ = (packet_[8] << 24) | (packet_[9] << 16) | (packet_[10] << 8) | packet_[11]; - } - - void serialize_rtp_header() { - packet_[0] = (version_ << 6) | (padding_ << 5) | (extension_ << 4) | csrc_count_; - packet_[1] = (marker_ << 7) | payload_type_; - packet_[2] = sequence_number_ >> 8; - packet_[3] = sequence_number_ & 0xFF; - packet_[4] = timestamp_ >> 24; - packet_[5] = (timestamp_ >> 16) & 0xFF; - packet_[6] = (timestamp_ >> 8) & 0xFF; - packet_[7] = timestamp_ & 0xFF; - packet_[8] = ssrc_ >> 24; - packet_[9] = (ssrc_ >> 16) & 0xFF; - packet_[10] = (ssrc_ >> 8) & 0xFF; - packet_[11] = ssrc_ & 0xFF; - } - - std::vector packet_; - int version_; - bool padding_; - bool extension_; - int csrc_count_; - bool marker_; - int payload_type_; - int sequence_number_; - int timestamp_; - int ssrc_; - int payload_size_; - }; -} // namespace espp +/// RtpPacket is a class to parse RTP packet. +class RtpPacket { +public: + /// Construct an empty RtpPacket. + /// The packet_ vector is empty and the header fields are set to 0. + RtpPacket() + : version_(2), padding_(false), extension_(false), csrc_count_(0), marker_(false), + payload_type_(0), sequence_number_(0), timestamp_(0), ssrc_(0), payload_size_(0) { + // ensure that the packet_ vector is at least RTP_HEADER_SIZE bytes long + packet_.resize(RTP_HEADER_SIZE); + } + + /// Construct an RtpPacket with a payload of size payload_size. + explicit RtpPacket(size_t payload_size) + : version_(2), padding_(false), extension_(false), csrc_count_(0), marker_(false), + payload_type_(0), sequence_number_(0), timestamp_(0), ssrc_(0), + payload_size_(payload_size) { + // ensure that the packet_ vector is at least RTP_HEADER_SIZE + payload_size bytes long + packet_.resize(RTP_HEADER_SIZE + payload_size); + } + + /// Construct an RtpPacket from a string_view. + /// Store the string_view in the packet_ vector and parses the header. + /// @param data The string_view to parse. + explicit RtpPacket(std::string_view data) { + packet_.assign(data.begin(), data.end()); + payload_size_ = packet_.size() - RTP_HEADER_SIZE; + if (packet_.size() >= RTP_HEADER_SIZE) + parse_rtp_header(); + } + + ~RtpPacket() {} + + /// Getters for the RTP header fields. + int get_version() const { return version_; } + bool get_padding() const { return padding_; } + bool get_extension() const { return extension_; } + int get_csrc_count() const { return csrc_count_; } + bool get_marker() const { return marker_; } + int get_payload_type() const { return payload_type_; } + int get_sequence_number() const { return sequence_number_; } + int get_timestamp() const { return timestamp_; } + int get_ssrc() const { return ssrc_; } + + /// Setters for the RTP header fields. + void set_version(int version) { version_ = version; } + void set_padding(bool padding) { padding_ = padding; } + void set_extension(bool extension) { extension_ = extension; } + void set_csrc_count(int csrc_count) { csrc_count_ = csrc_count; } + void set_marker(bool marker) { marker_ = marker; } + void set_payload_type(int payload_type) { payload_type_ = payload_type; } + void set_sequence_number(int sequence_number) { sequence_number_ = sequence_number; } + void set_timestamp(int timestamp) { timestamp_ = timestamp; } + void set_ssrc(int ssrc) { ssrc_ = ssrc; } + + /// Serialize the RTP header. + /// @note This method should be called after modifying the RTP header fields. + /// @note This method does not serialize the payload. To set the payload, use + /// set_payload(). + /// To get the payload, use get_payload(). + void serialize() { serialize_rtp_header(); } + + /// Get a string_view of the whole packet. + /// @note The string_view is valid as long as the packet_ vector is not modified. + /// @note If you manually build the packet_ vector, you should make sure that you + /// call serialize() before calling this method. + /// @return A string_view of the whole packet. + std::string_view get_data() const { return std::string_view(packet_.data(), packet_.size()); } + + /// Get the size of the RTP header. + /// @return The size of the RTP header. + size_t get_rtp_header_size() const { return RTP_HEADER_SIZE; } + + /// Get a string_view of the RTP header. + /// @return A string_view of the RTP header. + std::string_view get_rpt_header() const { + return std::string_view(packet_.data(), RTP_HEADER_SIZE); + } + + /// Get a reference to the packet_ vector. + /// @return A reference to the packet_ vector. + std::vector &get_packet() { return packet_; } + + /// Get a string_view of the payload. + /// @return A string_view of the payload. + std::string_view get_payload() const { + return std::string_view(packet_.data() + RTP_HEADER_SIZE, payload_size_); + } + + /// Set the payload. + /// @param payload The payload to set. + void set_payload(std::string_view payload) { + packet_.resize(RTP_HEADER_SIZE + payload.size()); + std::copy(payload.begin(), payload.end(), packet_.begin() + RTP_HEADER_SIZE); + payload_size_ = payload.size(); + } + +protected: + static constexpr int RTP_HEADER_SIZE = 12; + + void parse_rtp_header() { + version_ = (packet_[0] & 0xC0) >> 6; + padding_ = (packet_[0] & 0x20) >> 5; + extension_ = (packet_[0] & 0x10) >> 4; + csrc_count_ = packet_[0] & 0x0F; + marker_ = (packet_[1] & 0x80) >> 7; + payload_type_ = packet_[1] & 0x7F; + sequence_number_ = (packet_[2] << 8) | packet_[3]; + timestamp_ = (packet_[4] << 24) | (packet_[5] << 16) | (packet_[6] << 8) | packet_[7]; + ssrc_ = (packet_[8] << 24) | (packet_[9] << 16) | (packet_[10] << 8) | packet_[11]; + } + + void serialize_rtp_header() { + packet_[0] = (version_ << 6) | (padding_ << 5) | (extension_ << 4) | csrc_count_; + packet_[1] = (marker_ << 7) | payload_type_; + packet_[2] = sequence_number_ >> 8; + packet_[3] = sequence_number_ & 0xFF; + packet_[4] = timestamp_ >> 24; + packet_[5] = (timestamp_ >> 16) & 0xFF; + packet_[6] = (timestamp_ >> 8) & 0xFF; + packet_[7] = timestamp_ & 0xFF; + packet_[8] = ssrc_ >> 24; + packet_[9] = (ssrc_ >> 16) & 0xFF; + packet_[10] = (ssrc_ >> 8) & 0xFF; + packet_[11] = ssrc_ & 0xFF; + } + + std::vector packet_; + int version_; + bool padding_; + bool extension_; + int csrc_count_; + bool marker_; + int payload_type_; + int sequence_number_; + int timestamp_; + int ssrc_; + int payload_size_; +}; +} // namespace espp diff --git a/components/rtsp/include/rtsp_client.hpp b/components/rtsp/include/rtsp_client.hpp index e3cd945e5..1daf059a1 100644 --- a/components/rtsp/include/rtsp_client.hpp +++ b/components/rtsp/include/rtsp_client.hpp @@ -13,466 +13,475 @@ namespace espp { - /// A class for interacting with an RTSP server using RTP and RTCP over UDP - /// - /// This class is used to connect to an RTSP server and receive JPEG frames - /// over RTP. It uses the TCP socket to send RTSP requests and receive RTSP - /// responses. It uses the UDP socket to receive RTP and RTCP packets. - /// - /// The RTSP client is designed to be used with the RTSP server in the - /// [camera-streamer]https://github.com/esp-cpp/camera-streamer) project, but it - /// should work with any RTSP server that sends JPEG frames over RTP. - /// - /// \section RtspClient Example - /// \snippet rtsp_example.cpp rtsp_client_example - class RtspClient { - public: - /// Function type for the callback to call when a JPEG frame is received - using jpeg_frame_callback_t = std::function jpeg_frame)>; - - /// Configuration for the RTSP client - struct Config { - std::string server_address; ///< The server IP Address to connect to - int rtsp_port{8554}; ///< The port of the RTSP server - std::string path{"/mjpeg/1"}; ///< The path to the RTSP stream on the server. Will be appended to the server address and port to form the full path of the form "rtsp://:" - jpeg_frame_callback_t on_jpeg_frame; ///< The callback to call when a JPEG frame is received - espp::Logger::Verbosity log_level = espp::Logger::Verbosity::INFO; ///< The verbosity of the logger - }; +/// A class for interacting with an RTSP server using RTP and RTCP over UDP +/// +/// This class is used to connect to an RTSP server and receive JPEG frames +/// over RTP. It uses the TCP socket to send RTSP requests and receive RTSP +/// responses. It uses the UDP socket to receive RTP and RTCP packets. +/// +/// The RTSP client is designed to be used with the RTSP server in the +/// [camera-streamer]https://github.com/esp-cpp/camera-streamer) project, but it +/// should work with any RTSP server that sends JPEG frames over RTP. +/// +/// \section RtspClient Example +/// \snippet rtsp_example.cpp rtsp_client_example +class RtspClient { +public: + /// Function type for the callback to call when a JPEG frame is received + using jpeg_frame_callback_t = std::function jpeg_frame)>; + + /// Configuration for the RTSP client + struct Config { + std::string server_address; ///< The server IP Address to connect to + int rtsp_port{8554}; ///< The port of the RTSP server + std::string path{"/mjpeg/1"}; ///< The path to the RTSP stream on the server. Will be appended + ///< to the server address and port to form the full path of the + ///< form "rtsp://:" + jpeg_frame_callback_t on_jpeg_frame; ///< The callback to call when a JPEG frame is received + espp::Logger::Verbosity log_level = + espp::Logger::Verbosity::INFO; ///< The verbosity of the logger + }; - /// Constructor - /// \param config The configuration for the RTSP client - explicit RtspClient(const Config& config) - : server_address_(config.server_address), - rtsp_port_(config.rtsp_port), + /// Constructor + /// \param config The configuration for the RTSP client + explicit RtspClient(const Config &config) + : server_address_(config.server_address), rtsp_port_(config.rtsp_port), rtsp_socket_({.log_level = espp::Logger::Verbosity::WARN}), rtp_socket_({.log_level = espp::Logger::Verbosity::WARN}), rtcp_socket_({.log_level = espp::Logger::Verbosity::WARN}), - on_jpeg_frame_(config.on_jpeg_frame), - cseq_(0), + on_jpeg_frame_(config.on_jpeg_frame), cseq_(0), path_("rtsp://" + server_address_ + ":" + std::to_string(rtsp_port_) + config.path), - logger_({.tag = "RtspClient", .level = config.log_level}) { + logger_({.tag = "RtspClient", .level = config.log_level}) {} + + /// Destructor + /// Disconnects from the RTSP server + ~RtspClient() { + std::error_code ec; + disconnect(ec); + if (ec) { + logger_.error("Error disconnecting: {}", ec.message()); } - - /// Destructor - /// Disconnects from the RTSP server - ~RtspClient() { - std::error_code ec; - disconnect(ec); - if (ec) { - logger_.error("Error disconnecting: {}", ec.message()); - } + } + + /// Send an RTSP request to the server + /// \note This is a blocking call + /// \note This will parse the response and set the session ID if it is + /// present in the response. If the response is not a 200 OK, then + /// an error code will be set and the response will be returned. + /// If the response is a 200 OK, then the response will be returned + /// and the error code will be set to success. + /// \param method The method to use for connecting. + /// Options are "OPTIONS", "DESCRIBE", "SETUP", "PLAY", and "TEARDOWN" + /// \param path The path to the RTSP stream on the server. + /// \param extra_headers Any extra headers to send with the request. These + /// will be added to the request after the CSeq and Session headers. The + /// key is the header name and the value is the header value. For example, + /// {"Accept": "application/sdp"} will add "Accept: application/sdp" to the + /// request. The "User-Agent" header will be added automatically. The + /// "CSeq" and "Session" headers will be added automatically. + /// The "Accept" header will be added automatically. The "Transport" + /// header will be added automatically for the "SETUP" method. Defaults to + /// an empty map. + /// \param ec The error code to set if an error occurs + /// \return The response from the server + std::string send_request(const std::string &method, const std::string &path, + const std::unordered_map &extra_headers, + std::error_code &ec) { + // send the request + std::string request = method + " " + path + " RTSP/1.0\r\n"; + request += "CSeq: " + std::to_string(cseq_) + "\r\n"; + if (session_id_.size() > 0) { + request += "Session: " + session_id_ + "\r\n"; } - - /// Send an RTSP request to the server - /// \note This is a blocking call - /// \note This will parse the response and set the session ID if it is - /// present in the response. If the response is not a 200 OK, then - /// an error code will be set and the response will be returned. - /// If the response is a 200 OK, then the response will be returned - /// and the error code will be set to success. - /// \param method The method to use for connecting. - /// Options are "OPTIONS", "DESCRIBE", "SETUP", "PLAY", and "TEARDOWN" - /// \param path The path to the RTSP stream on the server. - /// \param extra_headers Any extra headers to send with the request. These - /// will be added to the request after the CSeq and Session headers. The - /// key is the header name and the value is the header value. For example, - /// {"Accept": "application/sdp"} will add "Accept: application/sdp" to the - /// request. The "User-Agent" header will be added automatically. The - /// "CSeq" and "Session" headers will be added automatically. - /// The "Accept" header will be added automatically. The "Transport" - /// header will be added automatically for the "SETUP" method. Defaults to - /// an empty map. - /// \param ec The error code to set if an error occurs - /// \return The response from the server - std::string send_request(const std::string& method, const std::string& path, const std::unordered_map& extra_headers, std::error_code& ec) { - // send the request - std::string request = method + " " + path + " RTSP/1.0\r\n"; - request += "CSeq: " + std::to_string(cseq_) + "\r\n"; - if (session_id_.size() > 0) { - request += "Session: " + session_id_ + "\r\n"; - } - for (auto& [key, value] : extra_headers) { - request += key + ": " + value + "\r\n"; - } - request += "User-Agent: rtsp-client\r\n"; - request += "Accept: application/sdp\r\n"; - request += "\r\n"; - std::string response; - auto transmit_config = espp::detail::TcpTransmitConfig{ + for (auto &[key, value] : extra_headers) { + request += key + ": " + value + "\r\n"; + } + request += "User-Agent: rtsp-client\r\n"; + request += "Accept: application/sdp\r\n"; + request += "\r\n"; + std::string response; + auto transmit_config = espp::detail::TcpTransmitConfig{ .wait_for_response = true, .response_size = 1024, - .on_response_callback = [&response](auto &response_vector) { response.assign(response_vector.begin(), response_vector.end()); }, + .on_response_callback = + [&response](auto &response_vector) { + response.assign(response_vector.begin(), response_vector.end()); + }, .response_timeout = std::chrono::seconds(5), - }; - // NOTE: now this call blocks until the response is received - logger_.debug("Request:\n{}", request); - if (!rtsp_socket_.transmit(request, transmit_config)) { - ec = std::make_error_code(std::errc::io_error); - logger_.error("Failed to send request"); - return {}; - } - - // TODO: how to keep receiving until we get the full response? - // if (response.find("\r\n\r\n") != std::string::npos) { - // break; - // } - - // parse the response - logger_.debug("Response:\n{}", response); - if (parse_response(response, ec)) { - return response; - } + }; + // NOTE: now this call blocks until the response is received + logger_.debug("Request:\n{}", request); + if (!rtsp_socket_.transmit(request, transmit_config)) { + ec = std::make_error_code(std::errc::io_error); + logger_.error("Failed to send request"); return {}; } - /// Connect to the RTSP server - /// Connects to the RTSP server and sends the OPTIONS request. - /// \param ec The error code to set if an error occurs - void connect(std::error_code& ec) { - // exit early if error code is already set - if (ec) { - return; - } + // TODO: how to keep receiving until we get the full response? + // if (response.find("\r\n\r\n") != std::string::npos) { + // break; + // } - rtsp_socket_.reinit(); - auto did_connect = rtsp_socket_.connect({ - .ip_address = server_address_, - .port = static_cast(rtsp_port_), - }); - if (!did_connect) { - ec = std::make_error_code(std::errc::io_error); - logger_.error("Failed to connect to {}:{}", server_address_, rtsp_port_); - return; - } - - // send the options request - send_request("OPTIONS", "*", {}, ec); + // parse the response + logger_.debug("Response:\n{}", response); + if (parse_response(response, ec)) { + return response; } - - /// Disconnect from the RTSP server - /// Disconnects from the RTSP server and sends the TEARDOWN request. - /// \param ec The error code to set if an error occurs - void disconnect(std::error_code& ec) { - // send the teardown request - teardown(ec); - rtsp_socket_.reinit(); + return {}; + } + + /// Connect to the RTSP server + /// Connects to the RTSP server and sends the OPTIONS request. + /// \param ec The error code to set if an error occurs + void connect(std::error_code &ec) { + // exit early if error code is already set + if (ec) { + return; } - /// Describe the RTSP stream - /// Sends the DESCRIBE request to the RTSP server and parses the response. - /// \param ec The error code to set if an error occurs - void describe(std::error_code& ec) { - // exit early if the error code is set - if (ec) { - return; - } - // send the describe request - auto response = send_request("DESCRIBE", path_, {}, ec); - if (ec) { - return; - } - // sdp response is of the form: - // std::regex sdp_regex("m=video (\\d+) RTP/AVP (\\d+)"); - // parse the sdp response and get the video port without using regex - // this is a very simple sdp parser that only works for this specific case - auto sdp_start = response.find("m=video"); - if (sdp_start == std::string::npos) { - ec = std::make_error_code(std::errc::wrong_protocol_type); - logger_.error("Invalid sdp"); - return; - } - auto sdp_end = response.find("\r\n", sdp_start); - if (sdp_end == std::string::npos) { - ec = std::make_error_code(std::errc::protocol_error); - logger_.error("Incomplete sdp"); - return; - } - auto sdp = response.substr(sdp_start, sdp_end - sdp_start); - auto port_start = sdp.find(" "); - if (port_start == std::string::npos) { - ec = std::make_error_code(std::errc::protocol_error); - logger_.error("Could not find port start"); - return; - } - auto port_end = sdp.find(" ", port_start + 1); - if (port_end == std::string::npos) { - ec = std::make_error_code(std::errc::protocol_error); - logger_.error("Could not find port end"); - return; - } - auto port = sdp.substr(port_start + 1, port_end - port_start - 1); - video_port_ = std::stoi(port); - logger_.debug("Video port: {}", video_port_); - auto payload_type_start = sdp.find(" ", port_end + 1); - if (payload_type_start == std::string::npos) { - ec = std::make_error_code(std::errc::protocol_error); - logger_.error("Could not find payload type start"); - return; - } - auto payload_type = sdp.substr(payload_type_start + 1, sdp.size() - payload_type_start - 1); - video_payload_type_ = std::stoi(payload_type); - logger_.debug("Video payload type: {}", video_payload_type_); + rtsp_socket_.reinit(); + auto did_connect = rtsp_socket_.connect({ + .ip_address = server_address_, + .port = static_cast(rtsp_port_), + }); + if (!did_connect) { + ec = std::make_error_code(std::errc::io_error); + logger_.error("Failed to connect to {}:{}", server_address_, rtsp_port_); + return; } - /// Setup the RTSP stream - /// \note Starts the RTP and RTCP threads. - /// Sends the SETUP request to the RTSP server and parses the response. - /// \note The default ports are 5000 and 5001 for RTP and RTCP respectively. - /// \param ec The error code to set if an error occurs - void setup(std::error_code& ec) { - // default to rtp and rtcp client ports 5000 and 5001 - setup(5000, 50001, ec); + // send the options request + send_request("OPTIONS", "*", {}, ec); + } + + /// Disconnect from the RTSP server + /// Disconnects from the RTSP server and sends the TEARDOWN request. + /// \param ec The error code to set if an error occurs + void disconnect(std::error_code &ec) { + // send the teardown request + teardown(ec); + rtsp_socket_.reinit(); + } + + /// Describe the RTSP stream + /// Sends the DESCRIBE request to the RTSP server and parses the response. + /// \param ec The error code to set if an error occurs + void describe(std::error_code &ec) { + // exit early if the error code is set + if (ec) { + return; + } + // send the describe request + auto response = send_request("DESCRIBE", path_, {}, ec); + if (ec) { + return; + } + // sdp response is of the form: + // std::regex sdp_regex("m=video (\\d+) RTP/AVP (\\d+)"); + // parse the sdp response and get the video port without using regex + // this is a very simple sdp parser that only works for this specific case + auto sdp_start = response.find("m=video"); + if (sdp_start == std::string::npos) { + ec = std::make_error_code(std::errc::wrong_protocol_type); + logger_.error("Invalid sdp"); + return; + } + auto sdp_end = response.find("\r\n", sdp_start); + if (sdp_end == std::string::npos) { + ec = std::make_error_code(std::errc::protocol_error); + logger_.error("Incomplete sdp"); + return; + } + auto sdp = response.substr(sdp_start, sdp_end - sdp_start); + auto port_start = sdp.find(" "); + if (port_start == std::string::npos) { + ec = std::make_error_code(std::errc::protocol_error); + logger_.error("Could not find port start"); + return; + } + auto port_end = sdp.find(" ", port_start + 1); + if (port_end == std::string::npos) { + ec = std::make_error_code(std::errc::protocol_error); + logger_.error("Could not find port end"); + return; + } + auto port = sdp.substr(port_start + 1, port_end - port_start - 1); + video_port_ = std::stoi(port); + logger_.debug("Video port: {}", video_port_); + auto payload_type_start = sdp.find(" ", port_end + 1); + if (payload_type_start == std::string::npos) { + ec = std::make_error_code(std::errc::protocol_error); + logger_.error("Could not find payload type start"); + return; + } + auto payload_type = sdp.substr(payload_type_start + 1, sdp.size() - payload_type_start - 1); + video_payload_type_ = std::stoi(payload_type); + logger_.debug("Video payload type: {}", video_payload_type_); + } + + /// Setup the RTSP stream + /// \note Starts the RTP and RTCP threads. + /// Sends the SETUP request to the RTSP server and parses the response. + /// \note The default ports are 5000 and 5001 for RTP and RTCP respectively. + /// \param ec The error code to set if an error occurs + void setup(std::error_code &ec) { + // default to rtp and rtcp client ports 5000 and 5001 + setup(5000, 50001, ec); + } + + /// Setup the RTSP stream + /// Sends the SETUP request to the RTSP server and parses the response. + /// \note Starts the RTP and RTCP threads. + /// \param rtp_port The RTP client port + /// \param rtcp_port The RTCP client port + /// \param ec The error code to set if an error occurs + void setup(size_t rtp_port, size_t rtcp_port, std::error_code &ec) { + // exit early if the error code is set + if (ec) { + return; } - /// Setup the RTSP stream - /// Sends the SETUP request to the RTSP server and parses the response. - /// \note Starts the RTP and RTCP threads. - /// \param rtp_port The RTP client port - /// \param rtcp_port The RTCP client port - /// \param ec The error code to set if an error occurs - void setup(size_t rtp_port, size_t rtcp_port, std::error_code& ec) { - // exit early if the error code is set - if (ec) { - return; - } - - // set up the transport header with the rtp and rtcp ports - auto transport_header = - "RTP/AVP;unicast;client_port=" - + std::to_string(rtp_port) + "-" + std::to_string(rtcp_port); - - // send the setup request - auto response = send_request("SETUP", path_, {{"Transport", transport_header}}, ec); - if (ec) { - return; - } + // set up the transport header with the rtp and rtcp ports + auto transport_header = + "RTP/AVP;unicast;client_port=" + std::to_string(rtp_port) + "-" + std::to_string(rtcp_port); - init_rtp(rtp_port, ec); - init_rtcp(rtcp_port, ec); + // send the setup request + auto response = send_request("SETUP", path_, {{"Transport", transport_header}}, ec); + if (ec) { + return; } - /// Play the RTSP stream - /// Sends the PLAY request to the RTSP server and parses the response. - /// \param ec The error code to set if an error occurs - void play(std::error_code& ec) { - // exit early if the error code is set - if (ec) { - return; - } - // send the play request - send_request("PLAY", path_ , {}, ec); + init_rtp(rtp_port, ec); + init_rtcp(rtcp_port, ec); + } + + /// Play the RTSP stream + /// Sends the PLAY request to the RTSP server and parses the response. + /// \param ec The error code to set if an error occurs + void play(std::error_code &ec) { + // exit early if the error code is set + if (ec) { + return; } - - /// Pause the RTSP stream - /// Sends the PAUSE request to the RTSP server and parses the response. - /// \param ec The error code to set if an error occurs - void pause(std::error_code& ec) { - // exit early if the error code is set - if (ec) { - return; - } - // send the pause request - send_request("PAUSE", path_, {}, ec); + // send the play request + send_request("PLAY", path_, {}, ec); + } + + /// Pause the RTSP stream + /// Sends the PAUSE request to the RTSP server and parses the response. + /// \param ec The error code to set if an error occurs + void pause(std::error_code &ec) { + // exit early if the error code is set + if (ec) { + return; } - - /// Teardown the RTSP stream - /// Sends the TEARDOWN request to the RTSP server and parses the response. - /// \param ec The error code to set if an error occurs - void teardown(std::error_code& ec) { - // exit early if the error code is set - if (ec) { - return; - } - // send the teardown request - send_request("TEARDOWN", path_, {}, ec); + // send the pause request + send_request("PAUSE", path_, {}, ec); + } + + /// Teardown the RTSP stream + /// Sends the TEARDOWN request to the RTSP server and parses the response. + /// \param ec The error code to set if an error occurs + void teardown(std::error_code &ec) { + // exit early if the error code is set + if (ec) { + return; } - - protected: - /// Parse the RTSP response - /// \note Parses response data for the following fields: - /// - Status code - /// - Status message - /// - Session - /// \note Increments the sequence number on success. - /// \param response_data The response data to parse - /// \param ec The error code to set if an error occurs - /// \return True if the response was parsed successfully, false otherwise - bool parse_response(const std::string& response_data, std::error_code& ec) { - // exit early if the error code is set - if (ec) { - return false; - } - if (response_data.empty()) { - ec = std::make_error_code(std::errc::no_message); - logger_.error("Empty response"); - return false; - } - // RTP response is of the form: - // std::regex response_regex("RTSP/1.0 (\\d+) (.*)\r\n(.*)\r\n\r\n"); - // parse the response but don't use regex since it may be slow on embedded platforms - // make sure it matches the expected response format - if (response_data.find("RTSP/1.0") != 0) { - ec = std::make_error_code(std::errc::protocol_error); - logger_.error("Invalid response"); - return false; - } - // parse the status code and message - int status_code = std::stoi(response_data.substr(9, 3)); - std::string status_message = response_data.substr(13, response_data.find("\r\n") - 13); - if (status_code != 200) { - ec = std::make_error_code(std::errc::protocol_error); - logger_.error(std::string("Request failed: ") + status_message); - return false; - } - // parse the session id - auto session_pos = response_data.find("Session: "); - if (session_pos != std::string::npos) { - session_id_ = response_data.substr(session_pos + 9, response_data.find("\r\n", session_pos) - session_pos - 9); - } - // increment the cseq - cseq_++; - return true; + // send the teardown request + send_request("TEARDOWN", path_, {}, ec); + } + +protected: + /// Parse the RTSP response + /// \note Parses response data for the following fields: + /// - Status code + /// - Status message + /// - Session + /// \note Increments the sequence number on success. + /// \param response_data The response data to parse + /// \param ec The error code to set if an error occurs + /// \return True if the response was parsed successfully, false otherwise + bool parse_response(const std::string &response_data, std::error_code &ec) { + // exit early if the error code is set + if (ec) { + return false; } - - /// Initialize the RTP socket - /// \note Starts the RTP socket task. - /// \param rtp_port The RTP client port - /// \param ec The error code to set if an error occurs - void init_rtp(size_t rtp_port, std::error_code& ec) { - // exit early if the error code is set - if (ec) { - return; - } - logger_.debug("Starting rtp socket"); - auto rtp_task_config = espp::Task::Config{ + if (response_data.empty()) { + ec = std::make_error_code(std::errc::no_message); + logger_.error("Empty response"); + return false; + } + // RTP response is of the form: + // std::regex response_regex("RTSP/1.0 (\\d+) (.*)\r\n(.*)\r\n\r\n"); + // parse the response but don't use regex since it may be slow on embedded platforms + // make sure it matches the expected response format + if (response_data.find("RTSP/1.0") != 0) { + ec = std::make_error_code(std::errc::protocol_error); + logger_.error("Invalid response"); + return false; + } + // parse the status code and message + int status_code = std::stoi(response_data.substr(9, 3)); + std::string status_message = response_data.substr(13, response_data.find("\r\n") - 13); + if (status_code != 200) { + ec = std::make_error_code(std::errc::protocol_error); + logger_.error(std::string("Request failed: ") + status_message); + return false; + } + // parse the session id + auto session_pos = response_data.find("Session: "); + if (session_pos != std::string::npos) { + session_id_ = response_data.substr(session_pos + 9, + response_data.find("\r\n", session_pos) - session_pos - 9); + } + // increment the cseq + cseq_++; + return true; + } + + /// Initialize the RTP socket + /// \note Starts the RTP socket task. + /// \param rtp_port The RTP client port + /// \param ec The error code to set if an error occurs + void init_rtp(size_t rtp_port, std::error_code &ec) { + // exit early if the error code is set + if (ec) { + return; + } + logger_.debug("Starting rtp socket"); + auto rtp_task_config = espp::Task::Config{ .name = "Rtp", .callback = nullptr, .stack_size_bytes = 16 * 1024, - }; - auto rtp_config = espp::UdpSocket::ReceiveConfig{ + }; + auto rtp_config = espp::UdpSocket::ReceiveConfig{ .port = rtp_port, .buffer_size = 2 * 1024, - .on_receive_callback = std::bind(&RtspClient::handle_rtp_packet, this, std::placeholders::_1, std::placeholders::_2), - }; - if (!rtp_socket_.start_receiving(rtp_task_config, rtp_config)) { - ec = std::make_error_code(std::errc::operation_canceled); - logger_.error("Failed to start receiving rtp packets"); - return; - } + .on_receive_callback = std::bind(&RtspClient::handle_rtp_packet, this, + std::placeholders::_1, std::placeholders::_2), + }; + if (!rtp_socket_.start_receiving(rtp_task_config, rtp_config)) { + ec = std::make_error_code(std::errc::operation_canceled); + logger_.error("Failed to start receiving rtp packets"); + return; } - - /// Initialize the RTCP socket - /// \note Starts the RTCP socket task. - /// \param rtcp_port The RTCP client port - /// \param ec The error code to set if an error occurs - void init_rtcp(size_t rtcp_port, std::error_code& ec) { - // exit early if the error code is set - if (ec) { - return; - } - logger_.debug("Starting rtcp socket"); - auto rtcp_task_config = espp::Task::Config{ + } + + /// Initialize the RTCP socket + /// \note Starts the RTCP socket task. + /// \param rtcp_port The RTCP client port + /// \param ec The error code to set if an error occurs + void init_rtcp(size_t rtcp_port, std::error_code &ec) { + // exit early if the error code is set + if (ec) { + return; + } + logger_.debug("Starting rtcp socket"); + auto rtcp_task_config = espp::Task::Config{ .name = "Rtcp", .callback = nullptr, .stack_size_bytes = 6 * 1024, - }; - auto rtcp_config = espp::UdpSocket::ReceiveConfig{ + }; + auto rtcp_config = espp::UdpSocket::ReceiveConfig{ .port = rtcp_port, .buffer_size = 1 * 1024, - .on_receive_callback = std::bind(&RtspClient::handle_rtcp_packet, this, std::placeholders::_1, std::placeholders::_2), - }; - if (!rtcp_socket_.start_receiving(rtcp_task_config, rtcp_config)) { - ec = std::make_error_code(std::errc::operation_canceled); - logger_.error("Failed to start receiving rtcp packets"); - return; - } + .on_receive_callback = std::bind(&RtspClient::handle_rtcp_packet, this, + std::placeholders::_1, std::placeholders::_2), + }; + if (!rtcp_socket_.start_receiving(rtcp_task_config, rtcp_config)) { + ec = std::make_error_code(std::errc::operation_canceled); + logger_.error("Failed to start receiving rtcp packets"); + return; } - - /// Handle an RTP packet - /// \note Parses the RTP packet and appends it to the current JPEG frame. - /// \note If the packet is the last fragment of the JPEG frame, the frame is sent to the on_jpeg_frame callback. - /// \note This function is called by the RTP socket task. - /// \param data The data to handle - /// \param sender_info The sender info - /// \return Optional data to send back to the sender - std::optional> handle_rtp_packet(std::vector &data, const espp::Socket::Info &sender_info) { - // jpeg frame that we are building - static std::unique_ptr jpeg_frame; - - logger_.debug("Got RTP packet of size: {}", data.size()); - - std::string_view packet(reinterpret_cast(data.data()), data.size()); - // parse the rtp packet - RtpJpegPacket rtp_jpeg_packet(packet); - auto frag_offset = rtp_jpeg_packet.get_offset(); - if (frag_offset == 0) { - // first fragment - logger_.debug("Received first fragment, size: {}, sequence number: {}", - rtp_jpeg_packet.get_data().size(), rtp_jpeg_packet.get_sequence_number()); - if (jpeg_frame) { - // we already have a frame, this is an error - logger_.warn("Received first fragment but already have a frame"); - jpeg_frame.reset(); - } - jpeg_frame = std::make_unique(rtp_jpeg_packet); - } else if (jpeg_frame) { - logger_.debug("Received middle fragment, size: {}, sequence number: {}", - rtp_jpeg_packet.get_data().size(), rtp_jpeg_packet.get_sequence_number()); - // middle fragment - jpeg_frame->append(rtp_jpeg_packet); - } else { - // we don't have a frame to append to but we got a middle fragment - // this is an error - logger_.warn("Received middle fragment without a frame"); - return {}; - } - - // check if this is the last packet of the frame (the last packet will have - // the marker bit set) - if (jpeg_frame && jpeg_frame->is_complete()) { - // get the jpeg data - auto jpeg_data = jpeg_frame->get_data(); - logger_.debug("Received jpeg frame of size: {} B", jpeg_data.size()); - // call the on_jpeg_frame callback - if (on_jpeg_frame_) { - on_jpeg_frame_(std::move(jpeg_frame)); - } - logger_.debug("Sent jpeg frame to callback, now jpeg_frame is nullptr? {}", jpeg_frame == nullptr); + } + + /// Handle an RTP packet + /// \note Parses the RTP packet and appends it to the current JPEG frame. + /// \note If the packet is the last fragment of the JPEG frame, the frame is sent to the + /// on_jpeg_frame callback. \note This function is called by the RTP socket task. \param data The + /// data to handle \param sender_info The sender info \return Optional data to send back to the + /// sender + std::optional> handle_rtp_packet(std::vector &data, + const espp::Socket::Info &sender_info) { + // jpeg frame that we are building + static std::unique_ptr jpeg_frame; + + logger_.debug("Got RTP packet of size: {}", data.size()); + + std::string_view packet(reinterpret_cast(data.data()), data.size()); + // parse the rtp packet + RtpJpegPacket rtp_jpeg_packet(packet); + auto frag_offset = rtp_jpeg_packet.get_offset(); + if (frag_offset == 0) { + // first fragment + logger_.debug("Received first fragment, size: {}, sequence number: {}", + rtp_jpeg_packet.get_data().size(), rtp_jpeg_packet.get_sequence_number()); + if (jpeg_frame) { + // we already have a frame, this is an error + logger_.warn("Received first fragment but already have a frame"); + jpeg_frame.reset(); } - // return an empty vector to indicate that we don't want to send a response + jpeg_frame = std::make_unique(rtp_jpeg_packet); + } else if (jpeg_frame) { + logger_.debug("Received middle fragment, size: {}, sequence number: {}", + rtp_jpeg_packet.get_data().size(), rtp_jpeg_packet.get_sequence_number()); + // middle fragment + jpeg_frame->append(rtp_jpeg_packet); + } else { + // we don't have a frame to append to but we got a middle fragment + // this is an error + logger_.warn("Received middle fragment without a frame"); return {}; } - /// Handle an RTCP packet - /// \note Parses the RTCP packet and sends a response if necessary. - /// \note This function is called by the RTCP socket task. - /// \param data The data to handle - /// \param sender_info The sender info - /// \return Optional data to send back to the sender - std::optional> handle_rtcp_packet(std::vector &data, const espp::Socket::Info &sender_info) { - // receive the rtcp packet - std::string_view packet(reinterpret_cast(data.data()), data.size()); - // TODO: parse the rtcp packet - // return an empty vector to indicate that we don't want to send a response - return {}; + // check if this is the last packet of the frame (the last packet will have + // the marker bit set) + if (jpeg_frame && jpeg_frame->is_complete()) { + // get the jpeg data + auto jpeg_data = jpeg_frame->get_data(); + logger_.debug("Received jpeg frame of size: {} B", jpeg_data.size()); + // call the on_jpeg_frame callback + if (on_jpeg_frame_) { + on_jpeg_frame_(std::move(jpeg_frame)); + } + logger_.debug("Sent jpeg frame to callback, now jpeg_frame is nullptr? {}", + jpeg_frame == nullptr); } - - std::string server_address_; - int rtsp_port_; - - espp::TcpSocket rtsp_socket_; - espp::UdpSocket rtp_socket_; - espp::UdpSocket rtcp_socket_; - - jpeg_frame_callback_t on_jpeg_frame_{nullptr}; - - int cseq_ = 0; - int video_port_ = 0; - int video_payload_type_ = 0; - std::string path_; - std::string session_id_; - - espp::Logger logger_; - }; + // return an empty vector to indicate that we don't want to send a response + return {}; + } + + /// Handle an RTCP packet + /// \note Parses the RTCP packet and sends a response if necessary. + /// \note This function is called by the RTCP socket task. + /// \param data The data to handle + /// \param sender_info The sender info + /// \return Optional data to send back to the sender + std::optional> handle_rtcp_packet(std::vector &data, + const espp::Socket::Info &sender_info) { + // receive the rtcp packet + std::string_view packet(reinterpret_cast(data.data()), data.size()); + // TODO: parse the rtcp packet + // return an empty vector to indicate that we don't want to send a response + return {}; + } + + std::string server_address_; + int rtsp_port_; + + espp::TcpSocket rtsp_socket_; + espp::UdpSocket rtp_socket_; + espp::UdpSocket rtcp_socket_; + + jpeg_frame_callback_t on_jpeg_frame_{nullptr}; + + int cseq_ = 0; + int video_port_ = 0; + int video_payload_type_ = 0; + std::string path_; + std::string session_id_; + + espp::Logger logger_; +}; } // namespace espp diff --git a/components/rtsp/include/rtsp_server.hpp b/components/rtsp/include/rtsp_server.hpp index a977eb56d..da7970851 100644 --- a/components/rtsp/include/rtsp_server.hpp +++ b/components/rtsp/include/rtsp_server.hpp @@ -8,319 +8,316 @@ #include "esp_random.h" #include "logger.hpp" +#include "task.hpp" #include "tcp_socket.hpp" #include "udp_socket.hpp" -#include "task.hpp" -#include "rtp_packet.hpp" -#include "rtp_jpeg_packet.hpp" #include "jpeg_frame.hpp" #include "rtcp_packet.hpp" +#include "rtp_jpeg_packet.hpp" +#include "rtp_packet.hpp" #include "rtsp_session.hpp" namespace espp { - /// Class for streaming MJPEG data from a camera using RTSP + RTP - /// Starts a TCP socket to listen for RTSP connections, and then spawns off a - /// new RTSP session for each connection. - /// @see RtspSession - /// @note This class does not currently send RTCP packets - /// - /// \section RtspServer example - /// \snippet rtsp_example.cpp rtsp_server_example - class RtspServer { - public: - /// @brief Configuration for the RTSP server - struct Config { - std::string server_address; ///< The ip address of the server - int port; ///< The port to listen on - std::string path; ///< The path to the RTSP stream - size_t max_data_size = 1000; ///< The maximum size of RTP packet data for the MJPEG stream. Frames will be broken up into multiple packets if they are larger than this. It seems that 1500 works well for sending, but is too large for the esp32 (camera-display) to receive properly. - Logger::Verbosity log_level = Logger::Verbosity::WARN; ///< The log level for the RTSP server - }; - - /// @brief Construct an RTSP server - /// @param config The configuration for the RTSP server - explicit RtspServer(const Config& config) - : server_address_(config.server_address) - , port_(config.port) - , path_(config.path) - , rtsp_socket_({.log_level = espp::Logger::Verbosity::WARN}) - , max_data_size_(config.max_data_size) - , logger_({.tag = "RTSP Server", .level = config.log_level}) { - // generate a random ssrc - ssrc_ = esp_random(); +/// Class for streaming MJPEG data from a camera using RTSP + RTP +/// Starts a TCP socket to listen for RTSP connections, and then spawns off a +/// new RTSP session for each connection. +/// @see RtspSession +/// @note This class does not currently send RTCP packets +/// +/// \section RtspServer example +/// \snippet rtsp_example.cpp rtsp_server_example +class RtspServer { +public: + /// @brief Configuration for the RTSP server + struct Config { + std::string server_address; ///< The ip address of the server + int port; ///< The port to listen on + std::string path; ///< The path to the RTSP stream + size_t max_data_size = + 1000; ///< The maximum size of RTP packet data for the MJPEG stream. Frames will be broken + ///< up into multiple packets if they are larger than this. It seems that 1500 works + ///< well for sending, but is too large for the esp32 (camera-display) to receive + ///< properly. + Logger::Verbosity log_level = Logger::Verbosity::WARN; ///< The log level for the RTSP server + }; + + /// @brief Construct an RTSP server + /// @param config The configuration for the RTSP server + explicit RtspServer(const Config &config) + : server_address_(config.server_address), port_(config.port), path_(config.path), + rtsp_socket_({.log_level = espp::Logger::Verbosity::WARN}), + max_data_size_(config.max_data_size), + logger_({.tag = "RTSP Server", .level = config.log_level}) { + // generate a random ssrc + ssrc_ = esp_random(); + } + + /// @brief Destroy the RTSP server + ~RtspServer() { stop(); } + + /// @brief Sets the log level for the RTSP sessions created by this server + /// @note This does not affect the log level of the RTSP server itself + /// @note This does not change the log level of any sessions that have + /// already been created + /// @param log_level The log level to set + void set_session_log_level(Logger::Verbosity log_level) { session_log_level_ = log_level; } + + /// @brief Start the RTSP server + /// Starts the accept task, session task, and binds the RTSP socket + /// @return True if the server was started successfully, false otherwise + bool start() { + if (accept_task_ && accept_task_->is_started()) { + logger_.error("Server is already running"); + return false; } - /// @brief Destroy the RTSP server - ~RtspServer() { - stop(); + logger_.info("Starting RTSP server on port {}", port_); + + if (!rtsp_socket_.bind(port_)) { + logger_.error("Failed to bind to port {}", port_); + return false; } - /// @brief Sets the log level for the RTSP sessions created by this server - /// @note This does not affect the log level of the RTSP server itself - /// @note This does not change the log level of any sessions that have - /// already been created - /// @param log_level The log level to set - void set_session_log_level(Logger::Verbosity log_level) { - session_log_level_ = log_level; + int max_pending_connections = 5; + if (!rtsp_socket_.listen(max_pending_connections)) { + logger_.error("Failed to listen on port {}", port_); + return false; } - /// @brief Start the RTSP server - /// Starts the accept task, session task, and binds the RTSP socket - /// @return True if the server was started successfully, false otherwise - bool start() { - if (accept_task_ && accept_task_->is_started()) { - logger_.error("Server is already running"); - return false; + using namespace std::placeholders; + accept_task_ = std::make_unique(Task::Config{ + .name = "RTSP Accept Task", + .callback = std::bind(&RtspServer::accept_task_function, this, _1, _2), + .stack_size_bytes = 6 * 1024, + .log_level = espp::Logger::Verbosity::WARN, + }); + accept_task_->start(); + return true; + } + + /// @brief Stop the FTP server + /// Stops the accept task, session task, and closes the RTSP socket + void stop() { + logger_.info("Stopping RTSP server"); + // stop the accept task + if (accept_task_) { + accept_task_->stop(); + } + // stop the session task + if (session_task_) { + session_task_->stop(); + } + // clear the list of sessions + sessions_.clear(); + // close the RTSP socket + rtsp_socket_.close(); + } + + /// @brief Send a frame over the RTSP connection + /// Converts the full JPEG frame into a series of simplified RTP/JPEG + /// packets and stores it to be sent over the RTP socket, but does not + /// actually send it + /// @note Overwrites any existing frame that has not been sent + /// @param frame The frame to send + void send_frame(const JpegFrame &frame) { + // get the frame scan data + auto frame_header = frame.get_header(); + auto frame_data = frame.get_scan_data(); + + auto width = frame_header.get_width(); + auto height = frame_header.get_height(); + auto q0 = frame_header.get_quantization_table(0); + auto q1 = frame_header.get_quantization_table(1); + + // if the frame data is larger than the MTU, then we need to break it up + // into multiple RTP packets + size_t num_packets = frame_data.size() / max_data_size_ + 1; + logger_.debug("Frame data is {} bytes, breaking into {} packets", frame_data.size(), + num_packets); + + // create num_packets RtpJpegPackets + // The first packet will have the quantization tables, and the last packet + // will have the end of image marker and the marker bit set + std::vector> packets; + packets.reserve(num_packets); + for (size_t i = 0; i < num_packets; i++) { + // get the start and end indices for the current packet + size_t start_index = i * max_data_size_; + size_t end_index = std::min(start_index + max_data_size_, frame_data.size()); + + static const int type_specific = 0; + static const int fragment_type = 0; + int offset = i * max_data_size_; + + std::unique_ptr packet; + // if this is the first packet, it has the quantization tables + if (i == 0) { + // use the original q value and include the quantization tables + packet = std::make_unique( + type_specific, fragment_type, 128, width, height, q0, q1, + frame_data.substr(start_index, end_index - start_index)); + } else { + // use a different q value (less than 128) and don't include the + // quantization tables + packet = std::make_unique( + type_specific, offset, fragment_type, 96, width, height, + frame_data.substr(start_index, end_index - start_index)); } - logger_.info("Starting RTSP server on port {}", port_); - - if (!rtsp_socket_.bind(port_)) { - logger_.error("Failed to bind to port {}", port_); - return false; + // set the payload type to 26 (JPEG) + packet->set_payload_type(26); + // set the sequence number + packet->set_sequence_number(sequence_number_++); + // set the timestamp + static auto start_time = std::chrono::steady_clock::now(); + auto now = std::chrono::steady_clock::now(); + auto timestamp = + std::chrono::duration_cast(now - start_time).count(); + packet->set_timestamp(timestamp * 90); + + // set the ssrc + packet->set_ssrc(ssrc_); + + auto mjpeg_header = packet->get_mjpeg_header(); + std::vector mjpeg_vec(mjpeg_header.begin(), mjpeg_header.end()); + + // if it's the last packet, set the marker bit + if (i == num_packets - 1) { + packet->set_marker(true); } - int max_pending_connections = 5; - if (!rtsp_socket_.listen(max_pending_connections)) { - logger_.error("Failed to listen on port {}", port_); - return false; - } + // make sure the packet header has been serialized + packet->serialize(); - using namespace std::placeholders; - accept_task_ = std::make_unique(Task::Config{ - .name = "RTSP Accept Task", - .callback = std::bind(&RtspServer::accept_task_function, this, _1, _2), - .stack_size_bytes = 6 * 1024, - .log_level = espp::Logger::Verbosity::WARN, - }); - accept_task_->start(); - return true; + // add the packet to the list of packets + packets.emplace_back(std::move(packet)); } - /// @brief Stop the FTP server - /// Stops the accept task, session task, and closes the RTSP socket - void stop() { - logger_.info("Stopping RTSP server"); - // stop the accept task - if (accept_task_) { - accept_task_->stop(); - } - // stop the session task - if (session_task_) { - session_task_->stop(); - } - // clear the list of sessions - sessions_.clear(); - // close the RTSP socket - rtsp_socket_.close(); + // now move the packets into the rtp_packets_ vector + { + std::unique_lock lock(rtp_packets_mutex_); + // move the new packets into the list + rtp_packets_ = std::move(packets); } - - /// @brief Send a frame over the RTSP connection - /// Converts the full JPEG frame into a series of simplified RTP/JPEG - /// packets and stores it to be sent over the RTP socket, but does not - /// actually send it - /// @note Overwrites any existing frame that has not been sent - /// @param frame The frame to send - void send_frame(const JpegFrame& frame) { - // get the frame scan data - auto frame_header = frame.get_header(); - auto frame_data = frame.get_scan_data(); - - auto width = frame_header.get_width(); - auto height = frame_header.get_height(); - auto q0 = frame_header.get_quantization_table(0); - auto q1 = frame_header.get_quantization_table(1); - - // if the frame data is larger than the MTU, then we need to break it up - // into multiple RTP packets - size_t num_packets = frame_data.size() / max_data_size_ + 1; - logger_.debug("Frame data is {} bytes, breaking into {} packets", frame_data.size(), num_packets); - - // create num_packets RtpJpegPackets - // The first packet will have the quantization tables, and the last packet - // will have the end of image marker and the marker bit set - std::vector> packets; - packets.reserve(num_packets); - for (size_t i = 0; i < num_packets; i++) { - // get the start and end indices for the current packet - size_t start_index = i * max_data_size_; - size_t end_index = std::min(start_index + max_data_size_, frame_data.size()); - - static const int type_specific = 0; - static const int fragment_type = 0; - int offset = i * max_data_size_; - - std::unique_ptr packet; - // if this is the first packet, it has the quantization tables - if (i == 0) { - // use the original q value and include the quantization tables - packet = std::make_unique(type_specific, fragment_type, - 128, width, height, - q0, q1, - frame_data.substr(start_index, end_index - start_index)); - } else { - // use a different q value (less than 128) and don't include the - // quantization tables - packet = std::make_unique(type_specific, offset, fragment_type, - 96, width, height, - frame_data.substr(start_index, end_index - start_index)); - } - - // set the payload type to 26 (JPEG) - packet->set_payload_type(26); - // set the sequence number - packet->set_sequence_number(sequence_number_++); - // set the timestamp - static auto start_time = std::chrono::steady_clock::now(); - auto now = std::chrono::steady_clock::now(); - auto timestamp = std::chrono::duration_cast(now - start_time).count(); - packet->set_timestamp(timestamp * 90); - - // set the ssrc - packet->set_ssrc(ssrc_); - - auto mjpeg_header = packet->get_mjpeg_header(); - std::vector mjpeg_vec(mjpeg_header.begin(), mjpeg_header.end()); - - // if it's the last packet, set the marker bit - if (i == num_packets - 1) { - packet->set_marker(true); - } - - // make sure the packet header has been serialized - packet->serialize(); - - // add the packet to the list of packets - packets.emplace_back(std::move(packet)); - } - - // now move the packets into the rtp_packets_ vector - { - std::unique_lock lock(rtp_packets_mutex_); - // move the new packets into the list - rtp_packets_ = std::move(packets); - } + } + +protected: + bool accept_task_function(std::mutex &m, std::condition_variable &cv) { + // accept a new connection + auto control_socket = rtsp_socket_.accept(); + if (!control_socket) { + logger_.error("Failed to accept new connection"); + return false; } - protected: + logger_.info("Accepted new connection"); + + // create a new session + auto session = std::make_unique( + std::move(control_socket), + RtspSession::Config{.server_address = fmt::format("{}:{}", server_address_, port_), + .rtsp_path = path_, + .log_level = session_log_level_}); + + // add the session to the list of sessions + auto session_id = session->get_session_id(); + sessions_.emplace(session_id, std::move(session)); + + // start the session task if it is not already running + using namespace std::placeholders; + if (!session_task_ || !session_task_->is_started()) { + logger_.info("Starting session task"); + session_task_ = std::make_unique(Task::Config{ + .name = "RtspSessionTask", + .callback = std::bind(&RtspServer::session_task_function, this, _1, _2), + .stack_size_bytes = 6 * 1024, + .log_level = espp::Logger::Verbosity::WARN, + }); + session_task_->start(); + } + // we do not want to stop the task + return false; + } + + bool session_task_function(std::mutex &m, std::condition_variable &cv) { + // sleep between frames + { + using namespace std::chrono_literals; + std::unique_lock lk(m); + cv.wait_for(lk, 10ms); + } - bool accept_task_function(std::mutex& m, std::condition_variable& cv) { - // accept a new connection - auto control_socket = rtsp_socket_.accept(); - if (!control_socket) { - logger_.error("Failed to accept new connection"); + // when this function returns, the vector of pointers will go out of scope + // and the pointers will be deleted (which is good because it means we + // won't send the same frame twice) + std::vector> packets; + { + // copy the rtp packets into a local vector + std::unique_lock lock(rtp_packets_mutex_); + if (rtp_packets_.empty()) { + // if there is not a new frame (no packets), then simply return + // we do not want to stop the task return false; } - - logger_.info("Accepted new connection"); - - // create a new session - auto session = std::make_unique(std::move(control_socket), - RtspSession::Config{ - .server_address = fmt::format("{}:{}", server_address_, port_), - .rtsp_path = path_, - .log_level = session_log_level_ - }); - - // add the session to the list of sessions - auto session_id = session->get_session_id(); - sessions_.emplace(session_id, std::move(session)); - - // start the session task if it is not already running - using namespace std::placeholders; - if (!session_task_ || !session_task_->is_started()) { - logger_.info("Starting session task"); - session_task_ = std::make_unique(Task::Config{ - .name = "RtspSessionTask", - .callback = std::bind(&RtspServer::session_task_function, this, _1, _2), - .stack_size_bytes = 6 * 1024, - .log_level = espp::Logger::Verbosity::WARN, - }); - session_task_->start(); - } - // we do not want to stop the task - return false; + // move the packets into the local vector + packets = std::move(rtp_packets_); } - bool session_task_function(std::mutex& m, std::condition_variable& cv) { - // sleep between frames - { - using namespace std::chrono_literals; - std::unique_lock lk(m); - cv.wait_for(lk, 10ms); - } - - // when this function returns, the vector of pointers will go out of scope - // and the pointers will be deleted (which is good because it means we - // won't send the same frame twice) - std::vector> packets; - { - // copy the rtp packets into a local vector - std::unique_lock lock(rtp_packets_mutex_); - if (rtp_packets_.empty()) { - // if there is not a new frame (no packets), then simply return - // we do not want to stop the task - return false; - } - // move the packets into the local vector - packets = std::move(rtp_packets_); - } - - logger_.debug("Sending frame data to clients"); - - // for each session in sessions_ - // if the session is active - // send the latest frame to the client - std::lock_guard lk(session_mutex_); - for (auto& session : sessions_) { - [[maybe_unused]] auto session_id = session.first; - auto& session_ptr = session.second; - // send the packets to the client - for (auto& packet : packets) { - // if the session is not active or is closed, then stop sending - if (!session_ptr->is_active() || session_ptr->is_closed()) { - break; - } - session_ptr->send_rtp_packet(*packet); + logger_.debug("Sending frame data to clients"); + + // for each session in sessions_ + // if the session is active + // send the latest frame to the client + std::lock_guard lk(session_mutex_); + for (auto &session : sessions_) { + [[maybe_unused]] auto session_id = session.first; + auto &session_ptr = session.second; + // send the packets to the client + for (auto &packet : packets) { + // if the session is not active or is closed, then stop sending + if (!session_ptr->is_active() || session_ptr->is_closed()) { + break; } + session_ptr->send_rtp_packet(*packet); } - // loop over the sessions and erase ones which are closed - for (auto it = sessions_.begin(); it != sessions_.end();) { - auto& session = it->second; - if (session->is_closed()) { - logger_.info("Removing session {}", session->get_session_id()); - it = sessions_.erase(it); - } else { - ++it; - } + } + // loop over the sessions and erase ones which are closed + for (auto it = sessions_.begin(); it != sessions_.end();) { + auto &session = it->second; + if (session->is_closed()) { + logger_.info("Removing session {}", session->get_session_id()); + it = sessions_.erase(it); + } else { + ++it; } - - // we do not want to stop the task - return false; } - uint32_t ssrc_; ///< the ssrc (synchronization source identifier) for the RTP packets - uint16_t sequence_number_{0}; ///< the sequence number for the RTP packets + // we do not want to stop the task + return false; + } - std::string server_address_; ///< the address of the server - int port_; ///< the port of the RTSP server - std::string path_; ///< the path of the RTSP server, e.g. rtsp:://:/ + uint32_t ssrc_; ///< the ssrc (synchronization source identifier) for the RTP packets + uint16_t sequence_number_{0}; ///< the sequence number for the RTP packets - TcpSocket rtsp_socket_; + std::string server_address_; ///< the address of the server + int port_; ///< the port of the RTSP server + std::string path_; ///< the path of the RTSP server, e.g. rtsp:://:/ - size_t max_data_size_; + TcpSocket rtsp_socket_; - std::mutex rtp_packets_mutex_; - std::vector> rtp_packets_; + size_t max_data_size_; - Logger::Verbosity session_log_level_{Logger::Verbosity::WARN}; - std::mutex session_mutex_; - std::unordered_map> sessions_; + std::mutex rtp_packets_mutex_; + std::vector> rtp_packets_; - Logger logger_; - std::unique_ptr accept_task_; - std::unique_ptr session_task_; - }; + Logger::Verbosity session_log_level_{Logger::Verbosity::WARN}; + std::mutex session_mutex_; + std::unordered_map> sessions_; + + Logger logger_; + std::unique_ptr accept_task_; + std::unique_ptr session_task_; +}; } // namespace espp diff --git a/components/task/include/task.hpp b/components/task/include/task.hpp index fb8e71d18..4d3ade92a 100644 --- a/components/task/include/task.hpp +++ b/components/task/include/task.hpp @@ -178,6 +178,13 @@ class Task { */ bool is_started() { return started_; } + /** + * @brief Is the task running? + * + * @return true if the task is running, false otherwise. + */ + bool is_running() { return is_started(); } + #if defined(ESP_PLATFORM) /** * @brief Get the info (as a string) for the task of the current context. @@ -215,6 +222,7 @@ class Task { break; } } else { + started_ = false; break; } } diff --git a/docs/adc/adc_types.html b/docs/adc/adc_types.html index 20a8b2692..60ded94dd 100644 --- a/docs/adc/adc_types.html +++ b/docs/adc/adc_types.html @@ -139,7 +139,7 @@
  • ADC APIs »
  • ADC Types
  • - Edit on GitHub + Edit on GitHub

  • @@ -156,7 +156,7 @@

    API Reference

    Header File

    diff --git a/docs/adc/ads1x15.html b/docs/adc/ads1x15.html index e3d7ec4a2..1c16d298e 100644 --- a/docs/adc/ads1x15.html +++ b/docs/adc/ads1x15.html @@ -140,7 +140,7 @@
  • ADC APIs »
  • ADS1x15 I2C ADC
  • - Edit on GitHub + Edit on GitHub

  • @@ -157,7 +157,7 @@

    API Reference

    Header File

    diff --git a/docs/adc/ads7138.html b/docs/adc/ads7138.html index df1658e95..e95054243 100644 --- a/docs/adc/ads7138.html +++ b/docs/adc/ads7138.html @@ -140,7 +140,7 @@
  • ADC APIs »
  • ADS7138 I2C ADC
  • - Edit on GitHub + Edit on GitHub

  • @@ -162,7 +162,7 @@

    API Reference

    Header File

    diff --git a/docs/adc/continuous_adc.html b/docs/adc/continuous_adc.html index 6e6641225..8fe308b53 100644 --- a/docs/adc/continuous_adc.html +++ b/docs/adc/continuous_adc.html @@ -140,7 +140,7 @@
  • ADC APIs »
  • Continuous ADC
  • - Edit on GitHub + Edit on GitHub

  • @@ -162,7 +162,7 @@

    API Reference

    Header File

    diff --git a/docs/adc/index.html b/docs/adc/index.html index b7567ab0f..bcb6324ce 100644 --- a/docs/adc/index.html +++ b/docs/adc/index.html @@ -132,7 +132,7 @@
  • »
  • ADC APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/adc/oneshot_adc.html b/docs/adc/oneshot_adc.html index 2543cb35c..b6eac26af 100644 --- a/docs/adc/oneshot_adc.html +++ b/docs/adc/oneshot_adc.html @@ -140,7 +140,7 @@
  • ADC APIs »
  • Oneshot ADC
  • - Edit on GitHub + Edit on GitHub

  • @@ -161,7 +161,7 @@

    API Reference

    Header File

    diff --git a/docs/bldc/bldc_driver.html b/docs/bldc/bldc_driver.html index 10e978573..eca7d5b56 100644 --- a/docs/bldc/bldc_driver.html +++ b/docs/bldc/bldc_driver.html @@ -137,7 +137,7 @@
  • BLDC APIs »
  • BLDC Driver
  • - Edit on GitHub + Edit on GitHub

  • @@ -154,7 +154,7 @@

    API Reference

    Header File

    diff --git a/docs/bldc/bldc_motor.html b/docs/bldc/bldc_motor.html index c45126158..6a746e1e7 100644 --- a/docs/bldc/bldc_motor.html +++ b/docs/bldc/bldc_motor.html @@ -139,7 +139,7 @@
  • BLDC APIs »
  • BLDC Motor
  • - Edit on GitHub + Edit on GitHub

  • @@ -170,7 +170,7 @@

    API Reference

    Header File

    @@ -322,6 +322,17 @@

    Example Usage +
    +inline bool is_enabled() const
    +

    Check if the motor is enabled.

    +
    +
    Returns
    +

    True if the motor is enabled, false otherwise.

    +
    +
    +
    +
    inline void enable()
    @@ -548,13 +559,13 @@

    Example Usage

    Header File

    Header File

    diff --git a/docs/bldc/index.html b/docs/bldc/index.html index bf85d5511..eb23e542d 100644 --- a/docs/bldc/index.html +++ b/docs/bldc/index.html @@ -129,7 +129,7 @@
  • »
  • BLDC APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/button.html b/docs/button.html index 57a7db778..fd00219ef 100644 --- a/docs/button.html +++ b/docs/button.html @@ -132,7 +132,7 @@
  • »
  • Button APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -158,7 +158,7 @@

    API Reference

    Header File

    diff --git a/docs/cli.html b/docs/cli.html index 616806c24..d487ff35d 100644 --- a/docs/cli.html +++ b/docs/cli.html @@ -135,7 +135,7 @@
  • »
  • Command Line Interface (CLI) APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -178,7 +178,7 @@

    API Reference

    Header File

    @@ -327,7 +327,7 @@

    Oneshot CLI Example

    Header File

    diff --git a/docs/color.html b/docs/color.html index 5a932b06b..4d06d8241 100644 --- a/docs/color.html +++ b/docs/color.html @@ -132,7 +132,7 @@
  • »
  • Color APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -155,7 +155,7 @@

    API Reference

    Header File

    diff --git a/docs/controller.html b/docs/controller.html index 223f1b391..b783ffd03 100644 --- a/docs/controller.html +++ b/docs/controller.html @@ -132,7 +132,7 @@
  • »
  • Controller APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -153,7 +153,7 @@

    API Reference

    Header File

    diff --git a/docs/csv.html b/docs/csv.html index 9b7ceddb0..b099c6c96 100644 --- a/docs/csv.html +++ b/docs/csv.html @@ -133,7 +133,7 @@
  • »
  • CSV APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -153,14 +153,14 @@

    API Reference

    Header File

    Macros

    -__gnu_linux__
    +__gnu_linux__
    diff --git a/docs/display/display.html b/docs/display/display.html index df540d81e..aba0a038f 100644 --- a/docs/display/display.html +++ b/docs/display/display.html @@ -137,7 +137,7 @@
  • Display APIs »
  • Display
  • - Edit on GitHub + Edit on GitHub

  • @@ -155,7 +155,7 @@

    API Reference

    Header File

    diff --git a/docs/display/display_drivers.html b/docs/display/display_drivers.html index 38b2833d1..c68d784a2 100644 --- a/docs/display/display_drivers.html +++ b/docs/display/display_drivers.html @@ -139,7 +139,7 @@
  • Display APIs »
  • Display Drivers
  • - Edit on GitHub + Edit on GitHub

  • @@ -157,7 +157,7 @@

    API Reference

    Header File

    @@ -434,7 +434,7 @@

    ili9341 Example

    Header File

    diff --git a/docs/display/index.html b/docs/display/index.html index f740e52c7..cbfd1ddfa 100644 --- a/docs/display/index.html +++ b/docs/display/index.html @@ -129,7 +129,7 @@
  • »
  • Display APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/encoder/abi_encoder.html b/docs/encoder/abi_encoder.html index 79e94f816..25bebd30e 100644 --- a/docs/encoder/abi_encoder.html +++ b/docs/encoder/abi_encoder.html @@ -139,7 +139,7 @@
  • Encoder APIs »
  • ABI Encoder
  • - Edit on GitHub + Edit on GitHub

  • @@ -161,7 +161,7 @@

    API Reference

    Header File

    diff --git a/docs/encoder/as5600.html b/docs/encoder/as5600.html index bd9ca612f..3fc6fa1de 100644 --- a/docs/encoder/as5600.html +++ b/docs/encoder/as5600.html @@ -139,7 +139,7 @@
  • Encoder APIs »
  • AS5600 Magnetic Encoder
  • - Edit on GitHub + Edit on GitHub

  • @@ -172,7 +172,7 @@

    API Reference

    Header File

    diff --git a/docs/encoder/encoder_types.html b/docs/encoder/encoder_types.html index 0c4ddc616..2aa614bc5 100644 --- a/docs/encoder/encoder_types.html +++ b/docs/encoder/encoder_types.html @@ -138,7 +138,7 @@
  • Encoder APIs »
  • Encoder Types
  • - Edit on GitHub + Edit on GitHub

  • @@ -155,7 +155,7 @@

    API Reference

    Header File

    diff --git a/docs/encoder/index.html b/docs/encoder/index.html index 50b554b7e..a168e8c58 100644 --- a/docs/encoder/index.html +++ b/docs/encoder/index.html @@ -131,7 +131,7 @@
  • »
  • Encoder APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/encoder/mt6701.html b/docs/encoder/mt6701.html index 0e2ac29b3..9d0346fdd 100644 --- a/docs/encoder/mt6701.html +++ b/docs/encoder/mt6701.html @@ -139,7 +139,7 @@
  • Encoder APIs »
  • MT6701 Magnetic Encoder
  • - Edit on GitHub + Edit on GitHub

  • @@ -172,7 +172,7 @@

    API Reference

    Header File

    diff --git a/docs/event_manager.html b/docs/event_manager.html index 0ad66ab80..2ca7f20f6 100644 --- a/docs/event_manager.html +++ b/docs/event_manager.html @@ -132,7 +132,7 @@
  • »
  • Event Manager APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -158,7 +158,7 @@

    API Reference

    Header File

    diff --git a/docs/file_system.html b/docs/file_system.html index bdf209dec..030e23a74 100644 --- a/docs/file_system.html +++ b/docs/file_system.html @@ -132,7 +132,7 @@
  • »
  • File System APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -155,7 +155,7 @@

    API Reference

    Header File

    diff --git a/docs/filters/biquad.html b/docs/filters/biquad.html index 7bca2356b..c147b16ee 100644 --- a/docs/filters/biquad.html +++ b/docs/filters/biquad.html @@ -141,7 +141,7 @@
  • Filter APIs »
  • Biquad Filter
  • - Edit on GitHub + Edit on GitHub

  • @@ -158,7 +158,7 @@

    API Reference

    Header File

    diff --git a/docs/filters/butterworth.html b/docs/filters/butterworth.html index 1db569a76..bc06bf50e 100644 --- a/docs/filters/butterworth.html +++ b/docs/filters/butterworth.html @@ -140,7 +140,7 @@
  • Filter APIs »
  • Butterworth Filter
  • - Edit on GitHub + Edit on GitHub

  • @@ -158,7 +158,7 @@

    API Reference

    Header File

    diff --git a/docs/filters/index.html b/docs/filters/index.html index 4308d6a14..077cf1de5 100644 --- a/docs/filters/index.html +++ b/docs/filters/index.html @@ -132,7 +132,7 @@
  • »
  • Filter APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/filters/lowpass.html b/docs/filters/lowpass.html index 59e3347c8..43d1a2dcf 100644 --- a/docs/filters/lowpass.html +++ b/docs/filters/lowpass.html @@ -140,7 +140,7 @@
  • Filter APIs »
  • Lowpass Filter
  • - Edit on GitHub + Edit on GitHub

  • @@ -159,7 +159,7 @@

    API Reference

    Header File

    diff --git a/docs/filters/sos.html b/docs/filters/sos.html index f94aa7d34..9cb31f7a5 100644 --- a/docs/filters/sos.html +++ b/docs/filters/sos.html @@ -140,7 +140,7 @@
  • Filter APIs »
  • Second Order Sections (SoS) Filter
  • - Edit on GitHub + Edit on GitHub

  • @@ -158,7 +158,7 @@

    API Reference

    Header File

    diff --git a/docs/filters/transfer_function.html b/docs/filters/transfer_function.html index 6bab6cdd4..2f829ed97 100644 --- a/docs/filters/transfer_function.html +++ b/docs/filters/transfer_function.html @@ -139,7 +139,7 @@
  • Filter APIs »
  • Transfer Function API
  • - Edit on GitHub + Edit on GitHub

  • @@ -156,7 +156,7 @@

    API Reference

    Header File

    diff --git a/docs/ftp/ftp_server.html b/docs/ftp/ftp_server.html index 9aac7c866..13f56ac12 100644 --- a/docs/ftp/ftp_server.html +++ b/docs/ftp/ftp_server.html @@ -139,7 +139,7 @@
  • FTP APIs »
  • FTP Server
  • - Edit on GitHub + Edit on GitHub

  • @@ -161,7 +161,7 @@

    API Reference

    Header File

    @@ -221,14 +221,14 @@

    Classes

    Header File

    Functions

    Warning

    -

    doxygenfunction: Unable to resolve function “to_time_t” with arguments None in doxygen xml output for project “esp-docs” from directory: /Users/bob/backbone/lodestone/components/espp/doc/_build/en/esp32/xml_in/. +

    doxygenfunction: Unable to resolve function “to_time_t” with arguments None in doxygen xml output for project “esp-docs” from directory: /Users/bob/esp-cpp/bldc_test_stand/components/espp/doc/_build/en/esp32/xml_in/. Potential matches:

    - template<typename TP> std::time_t to_time_t(TP tp)
    diff --git a/docs/ftp/index.html b/docs/ftp/index.html
    index 8c0560e57..a2e903ef8 100644
    --- a/docs/ftp/index.html
    +++ b/docs/ftp/index.html
    @@ -128,7 +128,7 @@
           
  • »
  • FTP APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/genindex.html b/docs/genindex.html index 2d7ca2c0e..3bbf002c8 100644 --- a/docs/genindex.html +++ b/docs/genindex.html @@ -122,7 +122,7 @@
  • »
  • Index
  • - Edit on GitHub + Edit on GitHub

  • @@ -652,6 +652,8 @@

    E

  • espp::BldcHaptics::Config::motor (C++ member)
  • espp::BldcHaptics::get_position (C++ function) +
  • +
  • espp::BldcHaptics::is_running (C++ function)
  • espp::BldcHaptics::play_haptic (C++ function)
  • @@ -660,6 +662,8 @@

    E

  • espp::BldcHaptics::stop (C++ function)
  • espp::BldcHaptics::update_detent_config (C++ function) +
  • +
  • espp::BldcHaptics::~BldcHaptics (C++ function)
  • espp::BldcMotor (C++ class)
  • @@ -710,6 +714,8 @@

    E

  • espp::BldcMotor::get_shaft_angle (C++ function)
  • espp::BldcMotor::get_shaft_velocity (C++ function) +
  • +
  • espp::BldcMotor::is_enabled (C++ function)
  • espp::BldcMotor::loop_foc (C++ function)
  • @@ -1426,11 +1432,11 @@

    E

  • espp::LedStrip::Config::write (C++ member)
  • espp::LedStrip::LedStrip (C++ function) -
  • -
  • espp::LedStrip::num_leds (C++ function)

  • @@ -180,19 +180,19 @@

    API Reference

    Header File

    Header File

    Header File

    @@ -301,6 +301,27 @@

    Example 2: Playing a haptic click / buzz +
    +inline ~BldcHaptics()
    +

    Destructor for the haptic motor.

    +
    +

    Note

    +

    This will stop the motor if it is running

    +
    +
    + +
    +
    +inline bool is_running() const
    +

    Check if the haptic motor is running.

    +
    +
    Returns
    +

    True if the haptic motor is running, false otherwise

    +
    +
    +
    +
    inline void start()
    diff --git a/docs/haptics/drv2605.html b/docs/haptics/drv2605.html index 75e181b6c..626db12fb 100644 --- a/docs/haptics/drv2605.html +++ b/docs/haptics/drv2605.html @@ -137,7 +137,7 @@
  • Haptics APIs »
  • DRV2605 Haptic Motor Driver
  • - Edit on GitHub + Edit on GitHub

  • @@ -159,7 +159,7 @@

    API Reference

    Header File

    diff --git a/docs/haptics/index.html b/docs/haptics/index.html index a915915cb..b21e261a9 100644 --- a/docs/haptics/index.html +++ b/docs/haptics/index.html @@ -129,7 +129,7 @@
  • »
  • Haptics APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/index.html b/docs/index.html index d0f8fc648..5949b92e7 100644 --- a/docs/index.html +++ b/docs/index.html @@ -124,7 +124,7 @@
  • »
  • ESPP Documentation
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/input/index.html b/docs/input/index.html index 5a8e90b1d..9af08a99e 100644 --- a/docs/input/index.html +++ b/docs/input/index.html @@ -128,7 +128,7 @@
  • »
  • Input APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/input/touchpad_input.html b/docs/input/touchpad_input.html index 59cdac91c..38362abec 100644 --- a/docs/input/touchpad_input.html +++ b/docs/input/touchpad_input.html @@ -136,7 +136,7 @@
  • Input APIs »
  • Touchpad Input
  • - Edit on GitHub + Edit on GitHub

  • @@ -154,7 +154,7 @@

    API Reference

    Header File

    diff --git a/docs/io_expander/aw9523.html b/docs/io_expander/aw9523.html index e75886e8e..6e7cc71a8 100644 --- a/docs/io_expander/aw9523.html +++ b/docs/io_expander/aw9523.html @@ -137,7 +137,7 @@
  • IO Expander APIs »
  • AW9523 I/O Expander
  • - Edit on GitHub + Edit on GitHub

  • @@ -156,7 +156,7 @@

    API Reference

    Header File

    diff --git a/docs/io_expander/index.html b/docs/io_expander/index.html index c8969a773..bf03232ea 100644 --- a/docs/io_expander/index.html +++ b/docs/io_expander/index.html @@ -129,7 +129,7 @@
  • »
  • IO Expander APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/io_expander/mcp23x17.html b/docs/io_expander/mcp23x17.html index b0277abd5..349ace6fc 100644 --- a/docs/io_expander/mcp23x17.html +++ b/docs/io_expander/mcp23x17.html @@ -137,7 +137,7 @@
  • IO Expander APIs »
  • MCP23x17 I/O Expander
  • - Edit on GitHub + Edit on GitHub

  • @@ -154,7 +154,7 @@

    API Reference

    Header File

    diff --git a/docs/joystick.html b/docs/joystick.html index 44519a836..e425ad950 100644 --- a/docs/joystick.html +++ b/docs/joystick.html @@ -133,7 +133,7 @@
  • »
  • Joystick APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -156,7 +156,7 @@

    API Reference

    Header File

    diff --git a/docs/led.html b/docs/led.html index c5cda2f0b..9dc829855 100644 --- a/docs/led.html +++ b/docs/led.html @@ -133,7 +133,7 @@
  • »
  • LED APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -155,7 +155,7 @@

    API Reference

    Header File

    diff --git a/docs/led_strip.html b/docs/led_strip.html index f0466c876..9a79bd75c 100644 --- a/docs/led_strip.html +++ b/docs/led_strip.html @@ -132,7 +132,7 @@
  • »
  • LED Strip APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -152,7 +152,7 @@

    API Reference

    Header File

    diff --git a/docs/logger.html b/docs/logger.html index 301897516..75373a26b 100644 --- a/docs/logger.html +++ b/docs/logger.html @@ -134,7 +134,7 @@
  • »
  • Logging APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -161,7 +161,7 @@

    API Reference

    Header File

    diff --git a/docs/math/bezier.html b/docs/math/bezier.html index 977319fba..5a61fceb0 100644 --- a/docs/math/bezier.html +++ b/docs/math/bezier.html @@ -140,7 +140,7 @@
  • Math APIs »
  • Bezier
  • - Edit on GitHub + Edit on GitHub

  • @@ -158,7 +158,7 @@

    API Reference

    Header File

    diff --git a/docs/math/fast_math.html b/docs/math/fast_math.html index 524d53527..cfaccc253 100644 --- a/docs/math/fast_math.html +++ b/docs/math/fast_math.html @@ -139,7 +139,7 @@
  • Math APIs »
  • Fast Math
  • - Edit on GitHub + Edit on GitHub

  • @@ -167,7 +167,7 @@

    API Reference

    Header File

    diff --git a/docs/math/gaussian.html b/docs/math/gaussian.html index 59aec1e82..5067ca23f 100644 --- a/docs/math/gaussian.html +++ b/docs/math/gaussian.html @@ -141,7 +141,7 @@
  • Math APIs »
  • Gaussian
  • - Edit on GitHub + Edit on GitHub

  • @@ -161,7 +161,7 @@

    API Reference

    Header File

    diff --git a/docs/math/index.html b/docs/math/index.html index 27fb9cad3..6e1f10444 100644 --- a/docs/math/index.html +++ b/docs/math/index.html @@ -132,7 +132,7 @@
  • »
  • Math APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/math/range_mapper.html b/docs/math/range_mapper.html index dcb09599c..68f92c7d4 100644 --- a/docs/math/range_mapper.html +++ b/docs/math/range_mapper.html @@ -140,7 +140,7 @@
  • Math APIs »
  • Range Mapper
  • - Edit on GitHub + Edit on GitHub

  • @@ -157,7 +157,7 @@

    API Reference

    Header File

    diff --git a/docs/math/vector2d.html b/docs/math/vector2d.html index 3353b0c25..2cefe08ec 100644 --- a/docs/math/vector2d.html +++ b/docs/math/vector2d.html @@ -140,7 +140,7 @@
  • Math APIs »
  • Vector2d
  • - Edit on GitHub + Edit on GitHub

  • @@ -157,7 +157,7 @@

    API Reference

    Header File

    diff --git a/docs/monitor.html b/docs/monitor.html index 507ceba67..04788dec9 100644 --- a/docs/monitor.html +++ b/docs/monitor.html @@ -133,7 +133,7 @@
  • »
  • Monitoring APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -158,7 +158,7 @@

    API Reference

    Header File

    diff --git a/docs/network/index.html b/docs/network/index.html index 2ba70ad52..3b148b811 100644 --- a/docs/network/index.html +++ b/docs/network/index.html @@ -130,7 +130,7 @@
  • »
  • Network APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/network/socket.html b/docs/network/socket.html index a1ab6fa52..f1a2bf25d 100644 --- a/docs/network/socket.html +++ b/docs/network/socket.html @@ -138,7 +138,7 @@
  • Network APIs »
  • Sockets
  • - Edit on GitHub + Edit on GitHub

  • @@ -156,7 +156,7 @@

    API Reference

    Header File

    diff --git a/docs/network/tcp_socket.html b/docs/network/tcp_socket.html index 5bc6b4238..1a59563fd 100644 --- a/docs/network/tcp_socket.html +++ b/docs/network/tcp_socket.html @@ -138,7 +138,7 @@
  • Network APIs »
  • TCP Sockets
  • - Edit on GitHub + Edit on GitHub

  • @@ -157,7 +157,7 @@

    API Reference

    Header File

    diff --git a/docs/network/udp_socket.html b/docs/network/udp_socket.html index 7e6e6bfc6..0fbb3581a 100644 --- a/docs/network/udp_socket.html +++ b/docs/network/udp_socket.html @@ -138,7 +138,7 @@
  • Network APIs »
  • UDP Sockets
  • - Edit on GitHub + Edit on GitHub

  • @@ -156,7 +156,7 @@

    API Reference

    Header File

    diff --git a/docs/nfc/index.html b/docs/nfc/index.html index 6ee4b2e6f..ca4a7b29c 100644 --- a/docs/nfc/index.html +++ b/docs/nfc/index.html @@ -129,7 +129,7 @@
  • »
  • NFC APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/nfc/ndef.html b/docs/nfc/ndef.html index 7f64a17af..4ed9c3237 100644 --- a/docs/nfc/ndef.html +++ b/docs/nfc/ndef.html @@ -138,7 +138,7 @@
  • NFC APIs »
  • NDEF
  • - Edit on GitHub + Edit on GitHub

  • @@ -155,7 +155,7 @@

    API Reference

    Header File

    diff --git a/docs/nfc/st25dv.html b/docs/nfc/st25dv.html index d2ee8011c..3a36f0e08 100644 --- a/docs/nfc/st25dv.html +++ b/docs/nfc/st25dv.html @@ -138,7 +138,7 @@
  • NFC APIs »
  • ST25DV
  • - Edit on GitHub + Edit on GitHub

  • @@ -159,7 +159,7 @@

    API Reference

    Header File

    diff --git a/docs/objects.inv b/docs/objects.inv index c04f45d28..340c18014 100644 Binary files a/docs/objects.inv and b/docs/objects.inv differ diff --git a/docs/pid.html b/docs/pid.html index 8e58c39a5..b034fabba 100644 --- a/docs/pid.html +++ b/docs/pid.html @@ -133,7 +133,7 @@
  • »
  • PID APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -155,7 +155,7 @@

    API Reference

    Header File

    diff --git a/docs/rmt.html b/docs/rmt.html index b1bfc8bca..aba1ca843 100644 --- a/docs/rmt.html +++ b/docs/rmt.html @@ -134,7 +134,7 @@
  • »
  • Remote Control Transceiver (RMT)
  • - Edit on GitHub + Edit on GitHub

  • @@ -161,7 +161,7 @@

    API Reference

    Header File

    @@ -325,7 +325,7 @@

    Example 1: Transmitting data

    Header File

    diff --git a/docs/rtsp.html b/docs/rtsp.html index 31b9eeba0..5575aae39 100644 --- a/docs/rtsp.html +++ b/docs/rtsp.html @@ -148,7 +148,7 @@
  • »
  • RTSP APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -188,7 +188,7 @@

    API Reference

    Header File

    @@ -203,13 +203,15 @@

    Classes

      espp::RtspClient rtsp_client({
           .server_address = ip_address, // string of the form {}.{}.{}.{}
    -        .rtsp_port = CONFIG_RTSP_SERVER_PORT,
    -        .path = "/mjpeg/1",
    -        .on_jpeg_frame = [](std::unique_ptr<espp::JpegFrame> jpeg_frame) {
    -          fmt::print("Got JPEG frame of size {}x{}\n", jpeg_frame->get_width(), jpeg_frame->get_height());
    -        },
    -        .log_level = espp::Logger::Verbosity::ERROR,
    -        });
    +      .rtsp_port = CONFIG_RTSP_SERVER_PORT,
    +      .path = "/mjpeg/1",
    +      .on_jpeg_frame =
    +          [](std::unique_ptr<espp::JpegFrame> jpeg_frame) {
    +            fmt::print("Got JPEG frame of size {}x{}\n", jpeg_frame->get_width(),
    +                       jpeg_frame->get_height());
    +          },
    +      .log_level = espp::Logger::Verbosity::ERROR,
    +  });
     
       std::error_code ec;
     
    @@ -423,7 +425,7 @@ 

    Example
    std::string path = {"/mjpeg/1"}
    -

    The path to the RTSP stream on the server. Will be appended to the server address and port to form the full path of the form “rtsp://<server_address>:<rtsp_port><path>”.

    +

    The path to the RTSP stream on the server. Will be appended to the server address and port to form the full path of the form “rtsp://<server_address>:<rtsp_port><path>”

    @@ -447,7 +449,7 @@

    Example

    Header File

    @@ -473,7 +475,7 @@

    example .port = server_port, .path = "/mjpeg/1", .log_level = espp::Logger::Verbosity::INFO, - }); + }); rtsp_server.start(); espp::JpegFrame jpeg_frame(jpeg_data, sizeof(jpeg_data)); @@ -605,7 +607,7 @@

    example

    Header File

    @@ -762,7 +764,7 @@

    Classes

    Header File

    @@ -904,7 +906,7 @@

    Classes

    Header File

    @@ -1203,7 +1205,7 @@

    Classes

    Header File

    @@ -1219,7 +1221,7 @@

    Classes

    Header File

    @@ -1306,7 +1308,7 @@

    Classes

    Header File

    diff --git a/docs/searchindex.js b/docs/searchindex.js index c34f8d975..c86186a2b 100644 --- a/docs/searchindex.js +++ b/docs/searchindex.js @@ -1 +1 @@ -Search.setIndex({docnames:["adc/adc_types","adc/ads1x15","adc/ads7138","adc/continuous_adc","adc/index","adc/oneshot_adc","bldc/bldc_driver","bldc/bldc_motor","bldc/index","button","cli","color","controller","csv","display/display","display/display_drivers","display/index","encoder/abi_encoder","encoder/as5600","encoder/encoder_types","encoder/index","encoder/mt6701","event_manager","file_system","filters/biquad","filters/butterworth","filters/index","filters/lowpass","filters/sos","filters/transfer_function","ftp/ftp_server","ftp/index","haptics/bldc_haptics","haptics/drv2605","haptics/index","index","input/index","input/touchpad_input","io_expander/aw9523","io_expander/index","io_expander/mcp23x17","joystick","led","led_strip","logger","math/bezier","math/fast_math","math/gaussian","math/index","math/range_mapper","math/vector2d","monitor","network/index","network/socket","network/tcp_socket","network/udp_socket","nfc/index","nfc/ndef","nfc/st25dv","pid","rmt","rtsp","serialization","state_machine","task","thermistor","wifi/index","wifi/wifi_ap","wifi/wifi_sta"],envversion:{"sphinx.domains.c":2,"sphinx.domains.changeset":1,"sphinx.domains.citation":1,"sphinx.domains.cpp":5,"sphinx.domains.index":1,"sphinx.domains.javascript":2,"sphinx.domains.math":2,"sphinx.domains.python":3,"sphinx.domains.rst":2,"sphinx.domains.std":2,"sphinx.ext.todo":2,sphinx:56},filenames:["adc/adc_types.rst","adc/ads1x15.rst","adc/ads7138.rst","adc/continuous_adc.rst","adc/index.rst","adc/oneshot_adc.rst","bldc/bldc_driver.rst","bldc/bldc_motor.rst","bldc/index.rst","button.rst","cli.rst","color.rst","controller.rst","csv.rst","display/display.rst","display/display_drivers.rst","display/index.rst","encoder/abi_encoder.rst","encoder/as5600.rst","encoder/encoder_types.rst","encoder/index.rst","encoder/mt6701.rst","event_manager.rst","file_system.rst","filters/biquad.rst","filters/butterworth.rst","filters/index.rst","filters/lowpass.rst","filters/sos.rst","filters/transfer_function.rst","ftp/ftp_server.rst","ftp/index.rst","haptics/bldc_haptics.rst","haptics/drv2605.rst","haptics/index.rst","index.rst","input/index.rst","input/touchpad_input.rst","io_expander/aw9523.rst","io_expander/index.rst","io_expander/mcp23x17.rst","joystick.rst","led.rst","led_strip.rst","logger.rst","math/bezier.rst","math/fast_math.rst","math/gaussian.rst","math/index.rst","math/range_mapper.rst","math/vector2d.rst","monitor.rst","network/index.rst","network/socket.rst","network/tcp_socket.rst","network/udp_socket.rst","nfc/index.rst","nfc/ndef.rst","nfc/st25dv.rst","pid.rst","rmt.rst","rtsp.rst","serialization.rst","state_machine.rst","task.rst","thermistor.rst","wifi/index.rst","wifi/wifi_ap.rst","wifi/wifi_sta.rst"],objects:{"":[[63,0,1,"c.MAGIC_ENUM_NO_CHECK_SUPPORT","MAGIC_ENUM_NO_CHECK_SUPPORT"],[13,0,1,"c.__gnu_linux__","__gnu_linux__"],[62,0,1,"c.__gnu_linux__","__gnu_linux__"],[10,0,1,"c.__linux__","__linux__"],[57,1,1,"_CPPv4N19PhonyNameDueToError3rawE","PhonyNameDueToError::raw"],[58,1,1,"_CPPv4N19PhonyNameDueToError3rawE","PhonyNameDueToError::raw"],[17,2,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoderE","espp::AbiEncoder"],[17,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder10AbiEncoderERK6Config","espp::AbiEncoder::AbiEncoder"],[17,4,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder10AbiEncoderERK6Config","espp::AbiEncoder::AbiEncoder::config"],[17,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder10AbiEncoderERK6Config","espp::AbiEncoder::AbiEncoder::type"],[17,2,1,"_CPPv4N4espp10AbiEncoder6ConfigE","espp::AbiEncoder::Config"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config6a_gpioE","espp::AbiEncoder::Config::a_gpio"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config6b_gpioE","espp::AbiEncoder::Config::b_gpio"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config21counts_per_revolutionE","espp::AbiEncoder::Config::counts_per_revolution"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config10high_limitE","espp::AbiEncoder::Config::high_limit"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config6i_gpioE","espp::AbiEncoder::Config::i_gpio"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config9log_levelE","espp::AbiEncoder::Config::log_level"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config9low_limitE","espp::AbiEncoder::Config::low_limit"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config13max_glitch_nsE","espp::AbiEncoder::Config::max_glitch_ns"],[17,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoderE","espp::AbiEncoder::T"],[17,3,1,"_CPPv4N4espp10AbiEncoder5clearEv","espp::AbiEncoder::clear"],[17,3,1,"_CPPv4N4espp10AbiEncoder9get_countEv","espp::AbiEncoder::get_count"],[17,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_degreesENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_degrees"],[17,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_degreesENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_degrees::type"],[17,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_radiansENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_radians"],[17,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_radiansENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_radians::type"],[17,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder15get_revolutionsENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_revolutions"],[17,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder15get_revolutionsENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_revolutions::type"],[17,3,1,"_CPPv4N4espp10AbiEncoder5startEv","espp::AbiEncoder::start"],[17,3,1,"_CPPv4N4espp10AbiEncoder4stopEv","espp::AbiEncoder::stop"],[17,3,1,"_CPPv4N4espp10AbiEncoderD0Ev","espp::AbiEncoder::~AbiEncoder"],[1,2,1,"_CPPv4N4espp7Ads1x15E","espp::Ads1x15"],[1,2,1,"_CPPv4N4espp7Ads1x1513Ads1015ConfigE","espp::Ads1x15::Ads1015Config"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1015Config14device_addressE","espp::Ads1x15::Ads1015Config::device_address"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1015Config4gainE","espp::Ads1x15::Ads1015Config::gain"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1015Config9log_levelE","espp::Ads1x15::Ads1015Config::log_level"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1015Config4readE","espp::Ads1x15::Ads1015Config::read"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1015Config11sample_rateE","espp::Ads1x15::Ads1015Config::sample_rate"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1015Config5writeE","espp::Ads1x15::Ads1015Config::write"],[1,6,1,"_CPPv4N4espp7Ads1x1511Ads1015RateE","espp::Ads1x15::Ads1015Rate"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate6SPS128E","espp::Ads1x15::Ads1015Rate::SPS128"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate7SPS1600E","espp::Ads1x15::Ads1015Rate::SPS1600"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate7SPS2400E","espp::Ads1x15::Ads1015Rate::SPS2400"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate6SPS250E","espp::Ads1x15::Ads1015Rate::SPS250"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate7SPS3300E","espp::Ads1x15::Ads1015Rate::SPS3300"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate6SPS490E","espp::Ads1x15::Ads1015Rate::SPS490"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate6SPS920E","espp::Ads1x15::Ads1015Rate::SPS920"],[1,2,1,"_CPPv4N4espp7Ads1x1513Ads1115ConfigE","espp::Ads1x15::Ads1115Config"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1115Config14device_addressE","espp::Ads1x15::Ads1115Config::device_address"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1115Config4gainE","espp::Ads1x15::Ads1115Config::gain"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1115Config9log_levelE","espp::Ads1x15::Ads1115Config::log_level"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1115Config4readE","espp::Ads1x15::Ads1115Config::read"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1115Config11sample_rateE","espp::Ads1x15::Ads1115Config::sample_rate"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1115Config5writeE","espp::Ads1x15::Ads1115Config::write"],[1,6,1,"_CPPv4N4espp7Ads1x1511Ads1115RateE","espp::Ads1x15::Ads1115Rate"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate6SPS128E","espp::Ads1x15::Ads1115Rate::SPS128"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate5SPS16E","espp::Ads1x15::Ads1115Rate::SPS16"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate6SPS250E","espp::Ads1x15::Ads1115Rate::SPS250"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate5SPS32E","espp::Ads1x15::Ads1115Rate::SPS32"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate6SPS475E","espp::Ads1x15::Ads1115Rate::SPS475"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate5SPS64E","espp::Ads1x15::Ads1115Rate::SPS64"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate4SPS8E","espp::Ads1x15::Ads1115Rate::SPS8"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate6SPS860E","espp::Ads1x15::Ads1115Rate::SPS860"],[1,3,1,"_CPPv4N4espp7Ads1x157Ads1x15ERK13Ads1015Config","espp::Ads1x15::Ads1x15"],[1,3,1,"_CPPv4N4espp7Ads1x157Ads1x15ERK13Ads1115Config","espp::Ads1x15::Ads1x15"],[1,4,1,"_CPPv4N4espp7Ads1x157Ads1x15ERK13Ads1015Config","espp::Ads1x15::Ads1x15::config"],[1,4,1,"_CPPv4N4espp7Ads1x157Ads1x15ERK13Ads1115Config","espp::Ads1x15::Ads1x15::config"],[1,1,1,"_CPPv4N4espp7Ads1x1515DEFAULT_ADDRESSE","espp::Ads1x15::DEFAULT_ADDRESS"],[1,6,1,"_CPPv4N4espp7Ads1x154GainE","espp::Ads1x15::Gain"],[1,7,1,"_CPPv4N4espp7Ads1x154Gain5EIGHTE","espp::Ads1x15::Gain::EIGHT"],[1,7,1,"_CPPv4N4espp7Ads1x154Gain4FOURE","espp::Ads1x15::Gain::FOUR"],[1,7,1,"_CPPv4N4espp7Ads1x154Gain3ONEE","espp::Ads1x15::Gain::ONE"],[1,7,1,"_CPPv4N4espp7Ads1x154Gain7SIXTEENE","espp::Ads1x15::Gain::SIXTEEN"],[1,7,1,"_CPPv4N4espp7Ads1x154Gain3TWOE","espp::Ads1x15::Gain::TWO"],[1,7,1,"_CPPv4N4espp7Ads1x154Gain9TWOTHIRDSE","espp::Ads1x15::Gain::TWOTHIRDS"],[1,8,1,"_CPPv4N4espp7Ads1x157read_fnE","espp::Ads1x15::read_fn"],[1,3,1,"_CPPv4N4espp7Ads1x159sample_mvEi","espp::Ads1x15::sample_mv"],[1,4,1,"_CPPv4N4espp7Ads1x159sample_mvEi","espp::Ads1x15::sample_mv::channel"],[1,8,1,"_CPPv4N4espp7Ads1x158write_fnE","espp::Ads1x15::write_fn"],[2,2,1,"_CPPv4N4espp7Ads7138E","espp::Ads7138"],[2,3,1,"_CPPv4N4espp7Ads71387Ads7138ERK6Config","espp::Ads7138::Ads7138"],[2,4,1,"_CPPv4N4espp7Ads71387Ads7138ERK6Config","espp::Ads7138::Ads7138::config"],[2,6,1,"_CPPv4N4espp7Ads713810AlertLogicE","espp::Ads7138::AlertLogic"],[2,7,1,"_CPPv4N4espp7Ads713810AlertLogic11ACTIVE_HIGHE","espp::Ads7138::AlertLogic::ACTIVE_HIGH"],[2,7,1,"_CPPv4N4espp7Ads713810AlertLogic10ACTIVE_LOWE","espp::Ads7138::AlertLogic::ACTIVE_LOW"],[2,7,1,"_CPPv4N4espp7Ads713810AlertLogic11PULSED_HIGHE","espp::Ads7138::AlertLogic::PULSED_HIGH"],[2,7,1,"_CPPv4N4espp7Ads713810AlertLogic10PULSED_LOWE","espp::Ads7138::AlertLogic::PULSED_LOW"],[2,6,1,"_CPPv4N4espp7Ads713811AnalogEventE","espp::Ads7138::AnalogEvent"],[2,7,1,"_CPPv4N4espp7Ads713811AnalogEvent6INSIDEE","espp::Ads7138::AnalogEvent::INSIDE"],[2,7,1,"_CPPv4N4espp7Ads713811AnalogEvent7OUTSIDEE","espp::Ads7138::AnalogEvent::OUTSIDE"],[2,6,1,"_CPPv4N4espp7Ads71386AppendE","espp::Ads7138::Append"],[2,7,1,"_CPPv4N4espp7Ads71386Append10CHANNEL_IDE","espp::Ads7138::Append::CHANNEL_ID"],[2,7,1,"_CPPv4N4espp7Ads71386Append4NONEE","espp::Ads7138::Append::NONE"],[2,7,1,"_CPPv4N4espp7Ads71386Append6STATUSE","espp::Ads7138::Append::STATUS"],[2,6,1,"_CPPv4N4espp7Ads71387ChannelE","espp::Ads7138::Channel"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH0E","espp::Ads7138::Channel::CH0"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH1E","espp::Ads7138::Channel::CH1"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH2E","espp::Ads7138::Channel::CH2"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH3E","espp::Ads7138::Channel::CH3"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH4E","espp::Ads7138::Channel::CH4"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH5E","espp::Ads7138::Channel::CH5"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH6E","espp::Ads7138::Channel::CH6"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH7E","espp::Ads7138::Channel::CH7"],[2,2,1,"_CPPv4N4espp7Ads71386ConfigE","espp::Ads7138::Config"],[2,1,1,"_CPPv4N4espp7Ads71386Config13analog_inputsE","espp::Ads7138::Config::analog_inputs"],[2,1,1,"_CPPv4N4espp7Ads71386Config10avdd_voltsE","espp::Ads7138::Config::avdd_volts"],[2,1,1,"_CPPv4N4espp7Ads71386Config14device_addressE","espp::Ads7138::Config::device_address"],[2,1,1,"_CPPv4N4espp7Ads71386Config14digital_inputsE","espp::Ads7138::Config::digital_inputs"],[2,1,1,"_CPPv4N4espp7Ads71386Config15digital_outputsE","espp::Ads7138::Config::digital_outputs"],[2,1,1,"_CPPv4N4espp7Ads71386Config9log_levelE","espp::Ads7138::Config::log_level"],[2,1,1,"_CPPv4N4espp7Ads71386Config4modeE","espp::Ads7138::Config::mode"],[2,1,1,"_CPPv4N4espp7Ads71386Config18oversampling_ratioE","espp::Ads7138::Config::oversampling_ratio"],[2,1,1,"_CPPv4N4espp7Ads71386Config4readE","espp::Ads7138::Config::read"],[2,1,1,"_CPPv4N4espp7Ads71386Config18statistics_enabledE","espp::Ads7138::Config::statistics_enabled"],[2,1,1,"_CPPv4N4espp7Ads71386Config5writeE","espp::Ads7138::Config::write"],[2,1,1,"_CPPv4N4espp7Ads713815DEFAULT_ADDRESSE","espp::Ads7138::DEFAULT_ADDRESS"],[2,6,1,"_CPPv4N4espp7Ads713810DataFormatE","espp::Ads7138::DataFormat"],[2,7,1,"_CPPv4N4espp7Ads713810DataFormat8AVERAGEDE","espp::Ads7138::DataFormat::AVERAGED"],[2,7,1,"_CPPv4N4espp7Ads713810DataFormat3RAWE","espp::Ads7138::DataFormat::RAW"],[2,6,1,"_CPPv4N4espp7Ads713812DigitalEventE","espp::Ads7138::DigitalEvent"],[2,7,1,"_CPPv4N4espp7Ads713812DigitalEvent4HIGHE","espp::Ads7138::DigitalEvent::HIGH"],[2,7,1,"_CPPv4N4espp7Ads713812DigitalEvent3LOWE","espp::Ads7138::DigitalEvent::LOW"],[2,6,1,"_CPPv4N4espp7Ads71384ModeE","espp::Ads7138::Mode"],[2,7,1,"_CPPv4N4espp7Ads71384Mode10AUTONOMOUSE","espp::Ads7138::Mode::AUTONOMOUS"],[2,7,1,"_CPPv4N4espp7Ads71384Mode8AUTO_SEQE","espp::Ads7138::Mode::AUTO_SEQ"],[2,7,1,"_CPPv4N4espp7Ads71384Mode6MANUALE","espp::Ads7138::Mode::MANUAL"],[2,6,1,"_CPPv4N4espp7Ads713810OutputModeE","espp::Ads7138::OutputMode"],[2,7,1,"_CPPv4N4espp7Ads713810OutputMode10OPEN_DRAINE","espp::Ads7138::OutputMode::OPEN_DRAIN"],[2,7,1,"_CPPv4N4espp7Ads713810OutputMode9PUSH_PULLE","espp::Ads7138::OutputMode::PUSH_PULL"],[2,6,1,"_CPPv4N4espp7Ads713817OversamplingRatioE","espp::Ads7138::OversamplingRatio"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio4NONEE","espp::Ads7138::OversamplingRatio::NONE"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio7OSR_128E","espp::Ads7138::OversamplingRatio::OSR_128"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio6OSR_16E","espp::Ads7138::OversamplingRatio::OSR_16"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio5OSR_2E","espp::Ads7138::OversamplingRatio::OSR_2"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio6OSR_32E","espp::Ads7138::OversamplingRatio::OSR_32"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio5OSR_4E","espp::Ads7138::OversamplingRatio::OSR_4"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio6OSR_64E","espp::Ads7138::OversamplingRatio::OSR_64"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio5OSR_8E","espp::Ads7138::OversamplingRatio::OSR_8"],[2,3,1,"_CPPv4N4espp7Ads713821clear_event_high_flagE7uint8_t","espp::Ads7138::clear_event_high_flag"],[2,4,1,"_CPPv4N4espp7Ads713821clear_event_high_flagE7uint8_t","espp::Ads7138::clear_event_high_flag::flags"],[2,3,1,"_CPPv4N4espp7Ads713820clear_event_low_flagE7uint8_t","espp::Ads7138::clear_event_low_flag"],[2,4,1,"_CPPv4N4espp7Ads713820clear_event_low_flagE7uint8_t","espp::Ads7138::clear_event_low_flag::flags"],[2,3,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogic","espp::Ads7138::configure_alert"],[2,4,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogic","espp::Ads7138::configure_alert::alert_logic"],[2,4,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogic","espp::Ads7138::configure_alert::output_mode"],[2,3,1,"_CPPv4N4espp7Ads713810get_all_mvEv","espp::Ads7138::get_all_mv"],[2,3,1,"_CPPv4N4espp7Ads713823get_digital_input_valueE7Channel","espp::Ads7138::get_digital_input_value"],[2,4,1,"_CPPv4N4espp7Ads713823get_digital_input_valueE7Channel","espp::Ads7138::get_digital_input_value::channel"],[2,3,1,"_CPPv4N4espp7Ads713824get_digital_input_valuesEv","espp::Ads7138::get_digital_input_values"],[2,3,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_t","espp::Ads7138::get_event_data"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_t","espp::Ads7138::get_event_data::event_flags"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_t","espp::Ads7138::get_event_data::event_high_flags"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_t","espp::Ads7138::get_event_data::event_low_flags"],[2,3,1,"_CPPv4N4espp7Ads713815get_event_flagsEv","espp::Ads7138::get_event_flags"],[2,3,1,"_CPPv4N4espp7Ads713819get_event_high_flagEv","espp::Ads7138::get_event_high_flag"],[2,3,1,"_CPPv4N4espp7Ads713818get_event_low_flagEv","espp::Ads7138::get_event_low_flag"],[2,3,1,"_CPPv4N4espp7Ads71386get_mvE7Channel","espp::Ads7138::get_mv"],[2,4,1,"_CPPv4N4espp7Ads71386get_mvE7Channel","espp::Ads7138::get_mv::channel"],[2,8,1,"_CPPv4N4espp7Ads71387read_fnE","espp::Ads7138::read_fn"],[2,3,1,"_CPPv4N4espp7Ads71385resetEv","espp::Ads7138::reset"],[2,3,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventi","espp::Ads7138::set_analog_alert"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventi","espp::Ads7138::set_analog_alert::channel"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventi","espp::Ads7138::set_analog_alert::event"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventi","espp::Ads7138::set_analog_alert::event_count"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventi","espp::Ads7138::set_analog_alert::high_threshold_mv"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventi","espp::Ads7138::set_analog_alert::low_threshold_mv"],[2,3,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEvent","espp::Ads7138::set_digital_alert"],[2,4,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEvent","espp::Ads7138::set_digital_alert::channel"],[2,4,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEvent","espp::Ads7138::set_digital_alert::event"],[2,3,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputMode","espp::Ads7138::set_digital_output_mode"],[2,4,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputMode","espp::Ads7138::set_digital_output_mode::channel"],[2,4,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputMode","espp::Ads7138::set_digital_output_mode::output_mode"],[2,3,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7Channelb","espp::Ads7138::set_digital_output_value"],[2,4,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7Channelb","espp::Ads7138::set_digital_output_value::channel"],[2,4,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7Channelb","espp::Ads7138::set_digital_output_value::value"],[2,8,1,"_CPPv4N4espp7Ads71388write_fnE","espp::Ads7138::write_fn"],[18,2,1,"_CPPv4N4espp6As5600E","espp::As5600"],[18,3,1,"_CPPv4N4espp6As56006As5600ERK6Config","espp::As5600::As5600"],[18,4,1,"_CPPv4N4espp6As56006As5600ERK6Config","espp::As5600::As5600::config"],[18,1,1,"_CPPv4N4espp6As560021COUNTS_PER_REVOLUTIONE","espp::As5600::COUNTS_PER_REVOLUTION"],[18,1,1,"_CPPv4N4espp6As560023COUNTS_PER_REVOLUTION_FE","espp::As5600::COUNTS_PER_REVOLUTION_F"],[18,1,1,"_CPPv4N4espp6As560017COUNTS_TO_DEGREESE","espp::As5600::COUNTS_TO_DEGREES"],[18,1,1,"_CPPv4N4espp6As560017COUNTS_TO_RADIANSE","espp::As5600::COUNTS_TO_RADIANS"],[18,2,1,"_CPPv4N4espp6As56006ConfigE","espp::As5600::Config"],[18,1,1,"_CPPv4N4espp6As56006Config14device_addressE","espp::As5600::Config::device_address"],[18,1,1,"_CPPv4N4espp6As56006Config4readE","espp::As5600::Config::read"],[18,1,1,"_CPPv4N4espp6As56006Config13update_periodE","espp::As5600::Config::update_period"],[18,1,1,"_CPPv4N4espp6As56006Config15velocity_filterE","espp::As5600::Config::velocity_filter"],[18,1,1,"_CPPv4N4espp6As56006Config5writeE","espp::As5600::Config::write"],[18,1,1,"_CPPv4N4espp6As560015DEFAULT_ADDRESSE","espp::As5600::DEFAULT_ADDRESS"],[18,1,1,"_CPPv4N4espp6As560018SECONDS_PER_MINUTEE","espp::As5600::SECONDS_PER_MINUTE"],[18,3,1,"_CPPv4NK4espp6As560015get_accumulatorEv","espp::As5600::get_accumulator"],[18,3,1,"_CPPv4NK4espp6As56009get_countEv","espp::As5600::get_count"],[18,3,1,"_CPPv4NK4espp6As560011get_degreesEv","espp::As5600::get_degrees"],[18,3,1,"_CPPv4NK4espp6As560022get_mechanical_degreesEv","espp::As5600::get_mechanical_degrees"],[18,3,1,"_CPPv4NK4espp6As560022get_mechanical_radiansEv","espp::As5600::get_mechanical_radians"],[18,3,1,"_CPPv4NK4espp6As560011get_radiansEv","espp::As5600::get_radians"],[18,3,1,"_CPPv4NK4espp6As56007get_rpmEv","espp::As5600::get_rpm"],[18,3,1,"_CPPv4NK4espp6As560017needs_zero_searchEv","espp::As5600::needs_zero_search"],[18,8,1,"_CPPv4N4espp6As56007read_fnE","espp::As5600::read_fn"],[18,8,1,"_CPPv4N4espp6As560018velocity_filter_fnE","espp::As5600::velocity_filter_fn"],[18,8,1,"_CPPv4N4espp6As56008write_fnE","espp::As5600::write_fn"],[38,2,1,"_CPPv4N4espp6Aw9523E","espp::Aw9523"],[38,3,1,"_CPPv4N4espp6Aw95236Aw9523ERK6Config","espp::Aw9523::Aw9523"],[38,4,1,"_CPPv4N4espp6Aw95236Aw9523ERK6Config","espp::Aw9523::Aw9523::config"],[38,2,1,"_CPPv4N4espp6Aw95236ConfigE","espp::Aw9523::Config"],[38,1,1,"_CPPv4N4espp6Aw95236Config14device_addressE","espp::Aw9523::Config::device_address"],[38,1,1,"_CPPv4N4espp6Aw95236Config9log_levelE","espp::Aw9523::Config::log_level"],[38,1,1,"_CPPv4N4espp6Aw95236Config15max_led_currentE","espp::Aw9523::Config::max_led_current"],[38,1,1,"_CPPv4N4espp6Aw95236Config20output_drive_mode_p0E","espp::Aw9523::Config::output_drive_mode_p0"],[38,1,1,"_CPPv4N4espp6Aw95236Config21port_0_direction_maskE","espp::Aw9523::Config::port_0_direction_mask"],[38,1,1,"_CPPv4N4espp6Aw95236Config21port_0_interrupt_maskE","espp::Aw9523::Config::port_0_interrupt_mask"],[38,1,1,"_CPPv4N4espp6Aw95236Config21port_1_direction_maskE","espp::Aw9523::Config::port_1_direction_mask"],[38,1,1,"_CPPv4N4espp6Aw95236Config21port_1_interrupt_maskE","espp::Aw9523::Config::port_1_interrupt_mask"],[38,1,1,"_CPPv4N4espp6Aw95236Config4readE","espp::Aw9523::Config::read"],[38,1,1,"_CPPv4N4espp6Aw95236Config5writeE","espp::Aw9523::Config::write"],[38,1,1,"_CPPv4N4espp6Aw952315DEFAULT_ADDRESSE","espp::Aw9523::DEFAULT_ADDRESS"],[38,6,1,"_CPPv4N4espp6Aw952313MaxLedCurrentE","espp::Aw9523::MaxLedCurrent"],[38,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent4IMAXE","espp::Aw9523::MaxLedCurrent::IMAX"],[38,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent7IMAX_25E","espp::Aw9523::MaxLedCurrent::IMAX_25"],[38,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent7IMAX_50E","espp::Aw9523::MaxLedCurrent::IMAX_50"],[38,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent7IMAX_75E","espp::Aw9523::MaxLedCurrent::IMAX_75"],[38,6,1,"_CPPv4N4espp6Aw952317OutputDriveModeP0E","espp::Aw9523::OutputDriveModeP0"],[38,7,1,"_CPPv4N4espp6Aw952317OutputDriveModeP010OPEN_DRAINE","espp::Aw9523::OutputDriveModeP0::OPEN_DRAIN"],[38,7,1,"_CPPv4N4espp6Aw952317OutputDriveModeP09PUSH_PUSHE","espp::Aw9523::OutputDriveModeP0::PUSH_PUSH"],[38,6,1,"_CPPv4N4espp6Aw95234PortE","espp::Aw9523::Port"],[38,7,1,"_CPPv4N4espp6Aw95234Port5PORT0E","espp::Aw9523::Port::PORT0"],[38,7,1,"_CPPv4N4espp6Aw95234Port5PORT1E","espp::Aw9523::Port::PORT1"],[38,3,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrent","espp::Aw9523::configure_global_control"],[38,4,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrent","espp::Aw9523::configure_global_control::max_led_current"],[38,4,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrent","espp::Aw9523::configure_global_control::output_drive_mode_p0"],[38,3,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_t","espp::Aw9523::configure_led"],[38,3,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_t","espp::Aw9523::configure_led"],[38,3,1,"_CPPv4N4espp6Aw952313configure_ledE8uint16_t","espp::Aw9523::configure_led"],[38,4,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_t","espp::Aw9523::configure_led::mask"],[38,4,1,"_CPPv4N4espp6Aw952313configure_ledE8uint16_t","espp::Aw9523::configure_led::mask"],[38,4,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_t","espp::Aw9523::configure_led::p0"],[38,4,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_t","espp::Aw9523::configure_led::p1"],[38,4,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_t","espp::Aw9523::configure_led::port"],[38,3,1,"_CPPv4N4espp6Aw95238get_pinsE4Port","espp::Aw9523::get_pins"],[38,3,1,"_CPPv4N4espp6Aw95238get_pinsEv","espp::Aw9523::get_pins"],[38,4,1,"_CPPv4N4espp6Aw95238get_pinsE4Port","espp::Aw9523::get_pins::port"],[38,3,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_t","espp::Aw9523::led"],[38,4,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_t","espp::Aw9523::led::brightness"],[38,4,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_t","espp::Aw9523::led::pin"],[38,8,1,"_CPPv4N4espp6Aw95237read_fnE","espp::Aw9523::read_fn"],[38,3,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_t","espp::Aw9523::set_direction"],[38,3,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_t","espp::Aw9523::set_direction"],[38,4,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_t","espp::Aw9523::set_direction::mask"],[38,4,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_t","espp::Aw9523::set_direction::p0"],[38,4,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_t","espp::Aw9523::set_direction::p1"],[38,4,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_t","espp::Aw9523::set_direction::port"],[38,3,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_t","espp::Aw9523::set_interrupt"],[38,3,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_t","espp::Aw9523::set_interrupt"],[38,4,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_t","espp::Aw9523::set_interrupt::mask"],[38,4,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_t","espp::Aw9523::set_interrupt::p0"],[38,4,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_t","espp::Aw9523::set_interrupt::p1"],[38,4,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_t","espp::Aw9523::set_interrupt::port"],[38,3,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_t","espp::Aw9523::set_pins"],[38,3,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_t","espp::Aw9523::set_pins"],[38,4,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_t","espp::Aw9523::set_pins::output"],[38,4,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_t","espp::Aw9523::set_pins::p0"],[38,4,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_t","espp::Aw9523::set_pins::p1"],[38,4,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_t","espp::Aw9523::set_pins::port"],[38,8,1,"_CPPv4N4espp6Aw95238write_fnE","espp::Aw9523::write_fn"],[45,2,1,"_CPPv4I0EN4espp6BezierE","espp::Bezier"],[45,3,1,"_CPPv4N4espp6Bezier6BezierERK14WeightedConfig","espp::Bezier::Bezier"],[45,3,1,"_CPPv4N4espp6Bezier6BezierERK6Config","espp::Bezier::Bezier"],[45,4,1,"_CPPv4N4espp6Bezier6BezierERK14WeightedConfig","espp::Bezier::Bezier::config"],[45,4,1,"_CPPv4N4espp6Bezier6BezierERK6Config","espp::Bezier::Bezier::config"],[45,2,1,"_CPPv4N4espp6Bezier6ConfigE","espp::Bezier::Config"],[45,1,1,"_CPPv4N4espp6Bezier6Config14control_pointsE","espp::Bezier::Config::control_points"],[45,5,1,"_CPPv4I0EN4espp6BezierE","espp::Bezier::T"],[45,2,1,"_CPPv4N4espp6Bezier14WeightedConfigE","espp::Bezier::WeightedConfig"],[45,1,1,"_CPPv4N4espp6Bezier14WeightedConfig14control_pointsE","espp::Bezier::WeightedConfig::control_points"],[45,1,1,"_CPPv4N4espp6Bezier14WeightedConfig7weightsE","espp::Bezier::WeightedConfig::weights"],[45,3,1,"_CPPv4NK4espp6Bezier2atEf","espp::Bezier::at"],[45,4,1,"_CPPv4NK4espp6Bezier2atEf","espp::Bezier::at::t"],[45,3,1,"_CPPv4NK4espp6BezierclEf","espp::Bezier::operator()"],[45,4,1,"_CPPv4NK4espp6BezierclEf","espp::Bezier::operator()::t"],[24,2,1,"_CPPv4N4espp15BiquadFilterDf1E","espp::BiquadFilterDf1"],[24,3,1,"_CPPv4N4espp15BiquadFilterDf16updateEf","espp::BiquadFilterDf1::update"],[24,4,1,"_CPPv4N4espp15BiquadFilterDf16updateEf","espp::BiquadFilterDf1::update::input"],[24,2,1,"_CPPv4N4espp15BiquadFilterDf2E","espp::BiquadFilterDf2"],[24,3,1,"_CPPv4N4espp15BiquadFilterDf26updateEKf","espp::BiquadFilterDf2::update"],[24,3,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update"],[24,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEKf","espp::BiquadFilterDf2::update::input"],[24,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update::input"],[24,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update::length"],[24,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update::output"],[6,2,1,"_CPPv4N4espp10BldcDriverE","espp::BldcDriver"],[6,3,1,"_CPPv4N4espp10BldcDriver10BldcDriverERK6Config","espp::BldcDriver::BldcDriver"],[6,4,1,"_CPPv4N4espp10BldcDriver10BldcDriverERK6Config","espp::BldcDriver::BldcDriver::config"],[6,2,1,"_CPPv4N4espp10BldcDriver6ConfigE","espp::BldcDriver::Config"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config9dead_zoneE","espp::BldcDriver::Config::dead_zone"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_a_hE","espp::BldcDriver::Config::gpio_a_h"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_a_lE","espp::BldcDriver::Config::gpio_a_l"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_b_hE","espp::BldcDriver::Config::gpio_b_h"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_b_lE","espp::BldcDriver::Config::gpio_b_l"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_c_hE","espp::BldcDriver::Config::gpio_c_h"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_c_lE","espp::BldcDriver::Config::gpio_c_l"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config11gpio_enableE","espp::BldcDriver::Config::gpio_enable"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config10gpio_faultE","espp::BldcDriver::Config::gpio_fault"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config13limit_voltageE","espp::BldcDriver::Config::limit_voltage"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config9log_levelE","espp::BldcDriver::Config::log_level"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config20power_supply_voltageE","espp::BldcDriver::Config::power_supply_voltage"],[6,3,1,"_CPPv4N4espp10BldcDriver15configure_powerEff","espp::BldcDriver::configure_power"],[6,4,1,"_CPPv4N4espp10BldcDriver15configure_powerEff","espp::BldcDriver::configure_power::power_supply_voltage"],[6,4,1,"_CPPv4N4espp10BldcDriver15configure_powerEff","espp::BldcDriver::configure_power::voltage_limit"],[6,3,1,"_CPPv4N4espp10BldcDriver7disableEv","espp::BldcDriver::disable"],[6,3,1,"_CPPv4N4espp10BldcDriver6enableEv","espp::BldcDriver::enable"],[6,3,1,"_CPPv4NK4espp10BldcDriver22get_power_supply_limitEv","espp::BldcDriver::get_power_supply_limit"],[6,3,1,"_CPPv4NK4espp10BldcDriver17get_voltage_limitEv","espp::BldcDriver::get_voltage_limit"],[6,3,1,"_CPPv4NK4espp10BldcDriver10is_enabledEv","espp::BldcDriver::is_enabled"],[6,3,1,"_CPPv4N4espp10BldcDriver10is_faultedEv","espp::BldcDriver::is_faulted"],[6,3,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state"],[6,4,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state::state_a"],[6,4,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state::state_b"],[6,4,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state::state_c"],[6,3,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm"],[6,4,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm::duty_a"],[6,4,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm::duty_b"],[6,4,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm::duty_c"],[6,3,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage"],[6,4,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage::ua"],[6,4,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage::ub"],[6,4,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage::uc"],[6,3,1,"_CPPv4N4espp10BldcDriverD0Ev","espp::BldcDriver::~BldcDriver"],[32,2,1,"_CPPv4I_12MotorConceptEN4espp11BldcHapticsE","espp::BldcHaptics"],[32,3,1,"_CPPv4N4espp11BldcHaptics11BldcHapticsERK6Config","espp::BldcHaptics::BldcHaptics"],[32,4,1,"_CPPv4N4espp11BldcHaptics11BldcHapticsERK6Config","espp::BldcHaptics::BldcHaptics::config"],[32,2,1,"_CPPv4N4espp11BldcHaptics6ConfigE","espp::BldcHaptics::Config"],[32,1,1,"_CPPv4N4espp11BldcHaptics6Config13kd_factor_maxE","espp::BldcHaptics::Config::kd_factor_max"],[32,1,1,"_CPPv4N4espp11BldcHaptics6Config13kd_factor_minE","espp::BldcHaptics::Config::kd_factor_min"],[32,1,1,"_CPPv4N4espp11BldcHaptics6Config9kp_factorE","espp::BldcHaptics::Config::kp_factor"],[32,1,1,"_CPPv4N4espp11BldcHaptics6Config9log_levelE","espp::BldcHaptics::Config::log_level"],[32,1,1,"_CPPv4N4espp11BldcHaptics6Config5motorE","espp::BldcHaptics::Config::motor"],[32,5,1,"_CPPv4I_12MotorConceptEN4espp11BldcHapticsE","espp::BldcHaptics::M"],[32,3,1,"_CPPv4NK4espp11BldcHaptics12get_positionEv","espp::BldcHaptics::get_position"],[32,3,1,"_CPPv4N4espp11BldcHaptics11play_hapticERKN6detail12HapticConfigE","espp::BldcHaptics::play_haptic"],[32,4,1,"_CPPv4N4espp11BldcHaptics11play_hapticERKN6detail12HapticConfigE","espp::BldcHaptics::play_haptic::config"],[32,3,1,"_CPPv4N4espp11BldcHaptics5startEv","espp::BldcHaptics::start"],[32,3,1,"_CPPv4N4espp11BldcHaptics4stopEv","espp::BldcHaptics::stop"],[32,3,1,"_CPPv4N4espp11BldcHaptics20update_detent_configERKN6detail12DetentConfigE","espp::BldcHaptics::update_detent_config"],[32,4,1,"_CPPv4N4espp11BldcHaptics20update_detent_configERKN6detail12DetentConfigE","espp::BldcHaptics::update_detent_config::config"],[7,2,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor"],[7,3,1,"_CPPv4N4espp9BldcMotor9BldcMotorERK6Config","espp::BldcMotor::BldcMotor"],[7,4,1,"_CPPv4N4espp9BldcMotor9BldcMotorERK6Config","espp::BldcMotor::BldcMotor::config"],[7,5,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor::CS"],[7,2,1,"_CPPv4N4espp9BldcMotor6ConfigE","espp::BldcMotor::Config"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config12angle_filterE","espp::BldcMotor::Config::angle_filter"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config13current_limitE","espp::BldcMotor::Config::current_limit"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config13current_senseE","espp::BldcMotor::Config::current_sense"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config16d_current_filterE","espp::BldcMotor::Config::d_current_filter"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config6driverE","espp::BldcMotor::Config::driver"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config8foc_typeE","espp::BldcMotor::Config::foc_type"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config9kv_ratingE","espp::BldcMotor::Config::kv_rating"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config9log_levelE","espp::BldcMotor::Config::log_level"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config14num_pole_pairsE","espp::BldcMotor::Config::num_pole_pairs"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config16phase_inductanceE","espp::BldcMotor::Config::phase_inductance"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config16phase_resistanceE","espp::BldcMotor::Config::phase_resistance"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config16q_current_filterE","espp::BldcMotor::Config::q_current_filter"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config6sensorE","espp::BldcMotor::Config::sensor"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config17torque_controllerE","espp::BldcMotor::Config::torque_controller"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config15velocity_filterE","espp::BldcMotor::Config::velocity_filter"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config14velocity_limitE","espp::BldcMotor::Config::velocity_limit"],[7,5,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor::D"],[7,5,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor::S"],[7,3,1,"_CPPv4N4espp9BldcMotor7disableEv","espp::BldcMotor::disable"],[7,3,1,"_CPPv4N4espp9BldcMotor6enableEv","espp::BldcMotor::enable"],[7,8,1,"_CPPv4N4espp9BldcMotor9filter_fnE","espp::BldcMotor::filter_fn"],[7,3,1,"_CPPv4N4espp9BldcMotor20get_electrical_angleEv","espp::BldcMotor::get_electrical_angle"],[7,3,1,"_CPPv4N4espp9BldcMotor15get_shaft_angleEv","espp::BldcMotor::get_shaft_angle"],[7,3,1,"_CPPv4N4espp9BldcMotor18get_shaft_velocityEv","espp::BldcMotor::get_shaft_velocity"],[7,3,1,"_CPPv4N4espp9BldcMotor8loop_focEv","espp::BldcMotor::loop_foc"],[7,3,1,"_CPPv4N4espp9BldcMotor4moveEf","espp::BldcMotor::move"],[7,4,1,"_CPPv4N4espp9BldcMotor4moveEf","espp::BldcMotor::move::new_target"],[7,3,1,"_CPPv4N4espp9BldcMotor23set_motion_control_typeEN6detail17MotionControlTypeE","espp::BldcMotor::set_motion_control_type"],[7,4,1,"_CPPv4N4espp9BldcMotor23set_motion_control_typeEN6detail17MotionControlTypeE","espp::BldcMotor::set_motion_control_type::motion_control_type"],[7,3,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage"],[7,4,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage::el_angle"],[7,4,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage::ud"],[7,4,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage::uq"],[7,3,1,"_CPPv4N4espp9BldcMotorD0Ev","espp::BldcMotor::~BldcMotor"],[25,2,1,"_CPPv4I_6size_t0EN4espp17ButterworthFilterE","espp::ButterworthFilter"],[25,3,1,"_CPPv4N4espp17ButterworthFilter17ButterworthFilterERK6Config","espp::ButterworthFilter::ButterworthFilter"],[25,4,1,"_CPPv4N4espp17ButterworthFilter17ButterworthFilterERK6Config","espp::ButterworthFilter::ButterworthFilter::config"],[25,2,1,"_CPPv4N4espp17ButterworthFilter6ConfigE","espp::ButterworthFilter::Config"],[25,1,1,"_CPPv4N4espp17ButterworthFilter6Config27normalized_cutoff_frequencyE","espp::ButterworthFilter::Config::normalized_cutoff_frequency"],[25,5,1,"_CPPv4I_6size_t0EN4espp17ButterworthFilterE","espp::ButterworthFilter::Impl"],[25,5,1,"_CPPv4I_6size_t0EN4espp17ButterworthFilterE","espp::ButterworthFilter::ORDER"],[25,3,1,"_CPPv4N4espp17ButterworthFilterclEf","espp::ButterworthFilter::operator()"],[25,4,1,"_CPPv4N4espp17ButterworthFilterclEf","espp::ButterworthFilter::operator()::input"],[25,3,1,"_CPPv4N4espp17ButterworthFilter6updateEf","espp::ButterworthFilter::update"],[25,4,1,"_CPPv4N4espp17ButterworthFilter6updateEf","espp::ButterworthFilter::update::input"],[9,2,1,"_CPPv4N4espp6ButtonE","espp::Button"],[9,6,1,"_CPPv4N4espp6Button11ActiveLevelE","espp::Button::ActiveLevel"],[9,7,1,"_CPPv4N4espp6Button11ActiveLevel4HIGHE","espp::Button::ActiveLevel::HIGH"],[9,7,1,"_CPPv4N4espp6Button11ActiveLevel3LOWE","espp::Button::ActiveLevel::LOW"],[9,3,1,"_CPPv4N4espp6Button6ButtonERK6Config","espp::Button::Button"],[9,4,1,"_CPPv4N4espp6Button6ButtonERK6Config","espp::Button::Button::config"],[9,2,1,"_CPPv4N4espp6Button6ConfigE","espp::Button::Config"],[9,1,1,"_CPPv4N4espp6Button6Config12active_levelE","espp::Button::Config::active_level"],[9,1,1,"_CPPv4N4espp6Button6Config8callbackE","espp::Button::Config::callback"],[9,1,1,"_CPPv4N4espp6Button6Config8gpio_numE","espp::Button::Config::gpio_num"],[9,1,1,"_CPPv4N4espp6Button6Config14interrupt_typeE","espp::Button::Config::interrupt_type"],[9,1,1,"_CPPv4N4espp6Button6Config9log_levelE","espp::Button::Config::log_level"],[9,1,1,"_CPPv4N4espp6Button6Config16pulldown_enabledE","espp::Button::Config::pulldown_enabled"],[9,1,1,"_CPPv4N4espp6Button6Config14pullup_enabledE","espp::Button::Config::pullup_enabled"],[9,1,1,"_CPPv4N4espp6Button6Config21task_stack_size_bytesE","espp::Button::Config::task_stack_size_bytes"],[9,2,1,"_CPPv4N4espp6Button5EventE","espp::Button::Event"],[9,1,1,"_CPPv4N4espp6Button5Event8gpio_numE","espp::Button::Event::gpio_num"],[9,1,1,"_CPPv4N4espp6Button5Event7pressedE","espp::Button::Event::pressed"],[9,6,1,"_CPPv4N4espp6Button13InterruptTypeE","espp::Button::InterruptType"],[9,7,1,"_CPPv4N4espp6Button13InterruptType8ANY_EDGEE","espp::Button::InterruptType::ANY_EDGE"],[9,7,1,"_CPPv4N4espp6Button13InterruptType12FALLING_EDGEE","espp::Button::InterruptType::FALLING_EDGE"],[9,7,1,"_CPPv4N4espp6Button13InterruptType10HIGH_LEVELE","espp::Button::InterruptType::HIGH_LEVEL"],[9,7,1,"_CPPv4N4espp6Button13InterruptType9LOW_LEVELE","espp::Button::InterruptType::LOW_LEVEL"],[9,7,1,"_CPPv4N4espp6Button13InterruptType11RISING_EDGEE","espp::Button::InterruptType::RISING_EDGE"],[9,8,1,"_CPPv4N4espp6Button17event_callback_fnE","espp::Button::event_callback_fn"],[9,3,1,"_CPPv4NK4espp6Button10is_pressedEv","espp::Button::is_pressed"],[9,3,1,"_CPPv4N4espp6ButtonD0Ev","espp::Button::~Button"],[10,2,1,"_CPPv4N4espp3CliE","espp::Cli"],[10,3,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli"],[10,4,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli::_cli"],[10,4,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli::_in"],[10,4,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli::_out"],[10,3,1,"_CPPv4NK4espp3Cli15GetInputHistoryEv","espp::Cli::GetInputHistory"],[10,3,1,"_CPPv4N4espp3Cli15SetInputHistoryERKN9LineInput7HistoryE","espp::Cli::SetInputHistory"],[10,4,1,"_CPPv4N4espp3Cli15SetInputHistoryERKN9LineInput7HistoryE","espp::Cli::SetInputHistory::history"],[10,3,1,"_CPPv4N4espp3Cli19SetInputHistorySizeE6size_t","espp::Cli::SetInputHistorySize"],[10,4,1,"_CPPv4N4espp3Cli19SetInputHistorySizeE6size_t","espp::Cli::SetInputHistorySize::history_size"],[10,3,1,"_CPPv4N4espp3Cli5StartEv","espp::Cli::Start"],[10,3,1,"_CPPv4N4espp3Cli22configure_stdin_stdoutEv","espp::Cli::configure_stdin_stdout"],[3,2,1,"_CPPv4N4espp13ContinuousAdcE","espp::ContinuousAdc"],[3,2,1,"_CPPv4N4espp13ContinuousAdc6ConfigE","espp::ContinuousAdc::Config"],[3,1,1,"_CPPv4N4espp13ContinuousAdc6Config8channelsE","espp::ContinuousAdc::Config::channels"],[3,1,1,"_CPPv4N4espp13ContinuousAdc6Config12convert_modeE","espp::ContinuousAdc::Config::convert_mode"],[3,1,1,"_CPPv4N4espp13ContinuousAdc6Config9log_levelE","espp::ContinuousAdc::Config::log_level"],[3,1,1,"_CPPv4N4espp13ContinuousAdc6Config14sample_rate_hzE","espp::ContinuousAdc::Config::sample_rate_hz"],[3,1,1,"_CPPv4N4espp13ContinuousAdc6Config13task_priorityE","espp::ContinuousAdc::Config::task_priority"],[3,1,1,"_CPPv4N4espp13ContinuousAdc6Config17window_size_bytesE","espp::ContinuousAdc::Config::window_size_bytes"],[3,3,1,"_CPPv4N4espp13ContinuousAdc13ContinuousAdcERK6Config","espp::ContinuousAdc::ContinuousAdc"],[3,4,1,"_CPPv4N4espp13ContinuousAdc13ContinuousAdcERK6Config","espp::ContinuousAdc::ContinuousAdc::config"],[3,3,1,"_CPPv4N4espp13ContinuousAdc6get_mvERK9AdcConfig","espp::ContinuousAdc::get_mv"],[3,4,1,"_CPPv4N4espp13ContinuousAdc6get_mvERK9AdcConfig","espp::ContinuousAdc::get_mv::config"],[3,3,1,"_CPPv4N4espp13ContinuousAdc8get_rateERK9AdcConfig","espp::ContinuousAdc::get_rate"],[3,4,1,"_CPPv4N4espp13ContinuousAdc8get_rateERK9AdcConfig","espp::ContinuousAdc::get_rate::config"],[3,3,1,"_CPPv4N4espp13ContinuousAdc5startEv","espp::ContinuousAdc::start"],[3,3,1,"_CPPv4N4espp13ContinuousAdc4stopEv","espp::ContinuousAdc::stop"],[3,3,1,"_CPPv4N4espp13ContinuousAdcD0Ev","espp::ContinuousAdc::~ContinuousAdc"],[12,2,1,"_CPPv4N4espp10ControllerE","espp::Controller"],[12,2,1,"_CPPv4N4espp10Controller20AnalogJoystickConfigE","espp::Controller::AnalogJoystickConfig"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig10active_lowE","espp::Controller::AnalogJoystickConfig::active_low"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_aE","espp::Controller::AnalogJoystickConfig::gpio_a"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_bE","espp::Controller::AnalogJoystickConfig::gpio_b"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig20gpio_joystick_selectE","espp::Controller::AnalogJoystickConfig::gpio_joystick_select"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig11gpio_selectE","espp::Controller::AnalogJoystickConfig::gpio_select"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig10gpio_startE","espp::Controller::AnalogJoystickConfig::gpio_start"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_xE","espp::Controller::AnalogJoystickConfig::gpio_x"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_yE","espp::Controller::AnalogJoystickConfig::gpio_y"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig15joystick_configE","espp::Controller::AnalogJoystickConfig::joystick_config"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig9log_levelE","espp::Controller::AnalogJoystickConfig::log_level"],[12,6,1,"_CPPv4N4espp10Controller6ButtonE","espp::Controller::Button"],[12,7,1,"_CPPv4N4espp10Controller6Button1AE","espp::Controller::Button::A"],[12,7,1,"_CPPv4N4espp10Controller6Button1BE","espp::Controller::Button::B"],[12,7,1,"_CPPv4N4espp10Controller6Button4DOWNE","espp::Controller::Button::DOWN"],[12,7,1,"_CPPv4N4espp10Controller6Button15JOYSTICK_SELECTE","espp::Controller::Button::JOYSTICK_SELECT"],[12,7,1,"_CPPv4N4espp10Controller6Button11LAST_UNUSEDE","espp::Controller::Button::LAST_UNUSED"],[12,7,1,"_CPPv4N4espp10Controller6Button4LEFTE","espp::Controller::Button::LEFT"],[12,7,1,"_CPPv4N4espp10Controller6Button5RIGHTE","espp::Controller::Button::RIGHT"],[12,7,1,"_CPPv4N4espp10Controller6Button6SELECTE","espp::Controller::Button::SELECT"],[12,7,1,"_CPPv4N4espp10Controller6Button5STARTE","espp::Controller::Button::START"],[12,7,1,"_CPPv4N4espp10Controller6Button2UPE","espp::Controller::Button::UP"],[12,7,1,"_CPPv4N4espp10Controller6Button1XE","espp::Controller::Button::X"],[12,7,1,"_CPPv4N4espp10Controller6Button1YE","espp::Controller::Button::Y"],[12,3,1,"_CPPv4N4espp10Controller10ControllerERK10DualConfig","espp::Controller::Controller"],[12,3,1,"_CPPv4N4espp10Controller10ControllerERK13DigitalConfig","espp::Controller::Controller"],[12,3,1,"_CPPv4N4espp10Controller10ControllerERK20AnalogJoystickConfig","espp::Controller::Controller"],[12,4,1,"_CPPv4N4espp10Controller10ControllerERK10DualConfig","espp::Controller::Controller::config"],[12,4,1,"_CPPv4N4espp10Controller10ControllerERK13DigitalConfig","espp::Controller::Controller::config"],[12,4,1,"_CPPv4N4espp10Controller10ControllerERK20AnalogJoystickConfig","espp::Controller::Controller::config"],[12,2,1,"_CPPv4N4espp10Controller13DigitalConfigE","espp::Controller::DigitalConfig"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig10active_lowE","espp::Controller::DigitalConfig::active_low"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_aE","espp::Controller::DigitalConfig::gpio_a"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_bE","espp::Controller::DigitalConfig::gpio_b"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig9gpio_downE","espp::Controller::DigitalConfig::gpio_down"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig9gpio_leftE","espp::Controller::DigitalConfig::gpio_left"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig10gpio_rightE","espp::Controller::DigitalConfig::gpio_right"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig11gpio_selectE","espp::Controller::DigitalConfig::gpio_select"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig10gpio_startE","espp::Controller::DigitalConfig::gpio_start"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig7gpio_upE","espp::Controller::DigitalConfig::gpio_up"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_xE","espp::Controller::DigitalConfig::gpio_x"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_yE","espp::Controller::DigitalConfig::gpio_y"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig9log_levelE","espp::Controller::DigitalConfig::log_level"],[12,2,1,"_CPPv4N4espp10Controller10DualConfigE","espp::Controller::DualConfig"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig10active_lowE","espp::Controller::DualConfig::active_low"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_aE","espp::Controller::DualConfig::gpio_a"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_bE","espp::Controller::DualConfig::gpio_b"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig9gpio_downE","espp::Controller::DualConfig::gpio_down"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig20gpio_joystick_selectE","espp::Controller::DualConfig::gpio_joystick_select"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig9gpio_leftE","espp::Controller::DualConfig::gpio_left"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig10gpio_rightE","espp::Controller::DualConfig::gpio_right"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig11gpio_selectE","espp::Controller::DualConfig::gpio_select"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig10gpio_startE","espp::Controller::DualConfig::gpio_start"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig7gpio_upE","espp::Controller::DualConfig::gpio_up"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_xE","espp::Controller::DualConfig::gpio_x"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_yE","espp::Controller::DualConfig::gpio_y"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig9log_levelE","espp::Controller::DualConfig::log_level"],[12,2,1,"_CPPv4N4espp10Controller5StateE","espp::Controller::State"],[12,1,1,"_CPPv4N4espp10Controller5State1aE","espp::Controller::State::a"],[12,1,1,"_CPPv4N4espp10Controller5State1bE","espp::Controller::State::b"],[12,1,1,"_CPPv4N4espp10Controller5State4downE","espp::Controller::State::down"],[12,1,1,"_CPPv4N4espp10Controller5State15joystick_selectE","espp::Controller::State::joystick_select"],[12,1,1,"_CPPv4N4espp10Controller5State4leftE","espp::Controller::State::left"],[12,1,1,"_CPPv4N4espp10Controller5State5rightE","espp::Controller::State::right"],[12,1,1,"_CPPv4N4espp10Controller5State6selectE","espp::Controller::State::select"],[12,1,1,"_CPPv4N4espp10Controller5State5startE","espp::Controller::State::start"],[12,1,1,"_CPPv4N4espp10Controller5State2upE","espp::Controller::State::up"],[12,1,1,"_CPPv4N4espp10Controller5State1xE","espp::Controller::State::x"],[12,1,1,"_CPPv4N4espp10Controller5State1yE","espp::Controller::State::y"],[12,3,1,"_CPPv4N4espp10Controller9get_stateEv","espp::Controller::get_state"],[12,3,1,"_CPPv4N4espp10Controller10is_pressedEK6Button","espp::Controller::is_pressed"],[12,4,1,"_CPPv4N4espp10Controller10is_pressedEK6Button","espp::Controller::is_pressed::input"],[12,3,1,"_CPPv4N4espp10Controller6updateEv","espp::Controller::update"],[12,3,1,"_CPPv4N4espp10ControllerD0Ev","espp::Controller::~Controller"],[14,2,1,"_CPPv4N4espp7DisplayE","espp::Display"],[14,2,1,"_CPPv4N4espp7Display16AllocatingConfigE","espp::Display::AllocatingConfig"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig16allocation_flagsE","espp::Display::AllocatingConfig::allocation_flags"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig15double_bufferedE","espp::Display::AllocatingConfig::double_buffered"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig14flush_callbackE","espp::Display::AllocatingConfig::flush_callback"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig6heightE","espp::Display::AllocatingConfig::height"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig9log_levelE","espp::Display::AllocatingConfig::log_level"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig17pixel_buffer_sizeE","espp::Display::AllocatingConfig::pixel_buffer_size"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig8rotationE","espp::Display::AllocatingConfig::rotation"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig25software_rotation_enabledE","espp::Display::AllocatingConfig::software_rotation_enabled"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig13update_periodE","espp::Display::AllocatingConfig::update_period"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig5widthE","espp::Display::AllocatingConfig::width"],[14,3,1,"_CPPv4N4espp7Display7DisplayERK16AllocatingConfig","espp::Display::Display"],[14,3,1,"_CPPv4N4espp7Display7DisplayERK19NonAllocatingConfig","espp::Display::Display"],[14,4,1,"_CPPv4N4espp7Display7DisplayERK16AllocatingConfig","espp::Display::Display::config"],[14,4,1,"_CPPv4N4espp7Display7DisplayERK19NonAllocatingConfig","espp::Display::Display::config"],[14,2,1,"_CPPv4N4espp7Display19NonAllocatingConfigE","espp::Display::NonAllocatingConfig"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig14flush_callbackE","espp::Display::NonAllocatingConfig::flush_callback"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig6heightE","espp::Display::NonAllocatingConfig::height"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig9log_levelE","espp::Display::NonAllocatingConfig::log_level"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig17pixel_buffer_sizeE","espp::Display::NonAllocatingConfig::pixel_buffer_size"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig8rotationE","espp::Display::NonAllocatingConfig::rotation"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig25software_rotation_enabledE","espp::Display::NonAllocatingConfig::software_rotation_enabled"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig13update_periodE","espp::Display::NonAllocatingConfig::update_period"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig5vram0E","espp::Display::NonAllocatingConfig::vram0"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig5vram1E","espp::Display::NonAllocatingConfig::vram1"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig5widthE","espp::Display::NonAllocatingConfig::width"],[14,6,1,"_CPPv4N4espp7Display8RotationE","espp::Display::Rotation"],[14,7,1,"_CPPv4N4espp7Display8Rotation9LANDSCAPEE","espp::Display::Rotation::LANDSCAPE"],[14,7,1,"_CPPv4N4espp7Display8Rotation18LANDSCAPE_INVERTEDE","espp::Display::Rotation::LANDSCAPE_INVERTED"],[14,7,1,"_CPPv4N4espp7Display8Rotation8PORTRAITE","espp::Display::Rotation::PORTRAIT"],[14,7,1,"_CPPv4N4espp7Display8Rotation17PORTRAIT_INVERTEDE","espp::Display::Rotation::PORTRAIT_INVERTED"],[14,6,1,"_CPPv4N4espp7Display6SignalE","espp::Display::Signal"],[14,7,1,"_CPPv4N4espp7Display6Signal5FLUSHE","espp::Display::Signal::FLUSH"],[14,7,1,"_CPPv4N4espp7Display6Signal4NONEE","espp::Display::Signal::NONE"],[14,8,1,"_CPPv4N4espp7Display8flush_fnE","espp::Display::flush_fn"],[14,3,1,"_CPPv4N4espp7Display13force_refreshEv","espp::Display::force_refresh"],[14,3,1,"_CPPv4NK4espp7Display6heightEv","espp::Display::height"],[14,3,1,"_CPPv4N4espp7Display5pauseEv","espp::Display::pause"],[14,3,1,"_CPPv4N4espp7Display6resumeEv","espp::Display::resume"],[14,3,1,"_CPPv4N4espp7Display5vram0Ev","espp::Display::vram0"],[14,3,1,"_CPPv4N4espp7Display5vram1Ev","espp::Display::vram1"],[14,3,1,"_CPPv4N4espp7Display15vram_size_bytesEv","espp::Display::vram_size_bytes"],[14,3,1,"_CPPv4N4espp7Display12vram_size_pxEv","espp::Display::vram_size_px"],[14,3,1,"_CPPv4NK4espp7Display5widthEv","espp::Display::width"],[14,3,1,"_CPPv4N4espp7DisplayD0Ev","espp::Display::~Display"],[33,2,1,"_CPPv4N4espp7Drv2605E","espp::Drv2605"],[33,2,1,"_CPPv4N4espp7Drv26056ConfigE","espp::Drv2605::Config"],[33,1,1,"_CPPv4N4espp7Drv26056Config14device_addressE","espp::Drv2605::Config::device_address"],[33,1,1,"_CPPv4N4espp7Drv26056Config9log_levelE","espp::Drv2605::Config::log_level"],[33,1,1,"_CPPv4N4espp7Drv26056Config10motor_typeE","espp::Drv2605::Config::motor_type"],[33,1,1,"_CPPv4N4espp7Drv26056Config4readE","espp::Drv2605::Config::read"],[33,1,1,"_CPPv4N4espp7Drv26056Config5writeE","espp::Drv2605::Config::write"],[33,3,1,"_CPPv4N4espp7Drv26057Drv2605ERK6Config","espp::Drv2605::Drv2605"],[33,4,1,"_CPPv4N4espp7Drv26057Drv2605ERK6Config","espp::Drv2605::Drv2605::config"],[33,6,1,"_CPPv4N4espp7Drv26054ModeE","espp::Drv2605::Mode"],[33,7,1,"_CPPv4N4espp7Drv26054Mode9AUDIOVIBEE","espp::Drv2605::Mode::AUDIOVIBE"],[33,7,1,"_CPPv4N4espp7Drv26054Mode7AUTOCALE","espp::Drv2605::Mode::AUTOCAL"],[33,7,1,"_CPPv4N4espp7Drv26054Mode7DIAGNOSE","espp::Drv2605::Mode::DIAGNOS"],[33,7,1,"_CPPv4N4espp7Drv26054Mode11EXTTRIGEDGEE","espp::Drv2605::Mode::EXTTRIGEDGE"],[33,7,1,"_CPPv4N4espp7Drv26054Mode10EXTTRIGLVLE","espp::Drv2605::Mode::EXTTRIGLVL"],[33,7,1,"_CPPv4N4espp7Drv26054Mode7INTTRIGE","espp::Drv2605::Mode::INTTRIG"],[33,7,1,"_CPPv4N4espp7Drv26054Mode9PWMANALOGE","espp::Drv2605::Mode::PWMANALOG"],[33,7,1,"_CPPv4N4espp7Drv26054Mode8REALTIMEE","espp::Drv2605::Mode::REALTIME"],[33,6,1,"_CPPv4N4espp7Drv26059MotorTypeE","espp::Drv2605::MotorType"],[33,7,1,"_CPPv4N4espp7Drv26059MotorType3ERME","espp::Drv2605::MotorType::ERM"],[33,7,1,"_CPPv4N4espp7Drv26059MotorType3LRAE","espp::Drv2605::MotorType::LRA"],[33,6,1,"_CPPv4N4espp7Drv26058WaveformE","espp::Drv2605::Waveform"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform12ALERT_1000MSE","espp::Drv2605::Waveform::ALERT_1000MS"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform11ALERT_750MSE","espp::Drv2605::Waveform::ALERT_750MS"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ1E","espp::Drv2605::Waveform::BUZZ1"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ2E","espp::Drv2605::Waveform::BUZZ2"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ3E","espp::Drv2605::Waveform::BUZZ3"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ4E","espp::Drv2605::Waveform::BUZZ4"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ5E","espp::Drv2605::Waveform::BUZZ5"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform12DOUBLE_CLICKE","espp::Drv2605::Waveform::DOUBLE_CLICK"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform3ENDE","espp::Drv2605::Waveform::END"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform3MAXE","espp::Drv2605::Waveform::MAX"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform16PULSING_STRONG_1E","espp::Drv2605::Waveform::PULSING_STRONG_1"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform16PULSING_STRONG_2E","espp::Drv2605::Waveform::PULSING_STRONG_2"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform11SHARP_CLICKE","espp::Drv2605::Waveform::SHARP_CLICK"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform9SOFT_BUMPE","espp::Drv2605::Waveform::SOFT_BUMP"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform9SOFT_FUZZE","espp::Drv2605::Waveform::SOFT_FUZZ"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform11STRONG_BUZZE","espp::Drv2605::Waveform::STRONG_BUZZ"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform12STRONG_CLICKE","espp::Drv2605::Waveform::STRONG_CLICK"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform18TRANSITION_CLICK_1E","espp::Drv2605::Waveform::TRANSITION_CLICK_1"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform16TRANSITION_HUM_1E","espp::Drv2605::Waveform::TRANSITION_HUM_1"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform12TRIPLE_CLICKE","espp::Drv2605::Waveform::TRIPLE_CLICK"],[33,8,1,"_CPPv4N4espp7Drv26057read_fnE","espp::Drv2605::read_fn"],[33,3,1,"_CPPv4N4espp7Drv260514select_libraryE7uint8_t","espp::Drv2605::select_library"],[33,4,1,"_CPPv4N4espp7Drv260514select_libraryE7uint8_t","espp::Drv2605::select_library::lib"],[33,3,1,"_CPPv4N4espp7Drv26058set_modeE4Mode","espp::Drv2605::set_mode"],[33,4,1,"_CPPv4N4espp7Drv26058set_modeE4Mode","espp::Drv2605::set_mode::mode"],[33,3,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8Waveform","espp::Drv2605::set_waveform"],[33,4,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8Waveform","espp::Drv2605::set_waveform::slot"],[33,4,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8Waveform","espp::Drv2605::set_waveform::w"],[33,3,1,"_CPPv4N4espp7Drv26055startEv","espp::Drv2605::start"],[33,3,1,"_CPPv4N4espp7Drv26054stopEv","espp::Drv2605::stop"],[33,8,1,"_CPPv4N4espp7Drv26058write_fnE","espp::Drv2605::write_fn"],[22,2,1,"_CPPv4N4espp12EventManagerE","espp::EventManager"],[22,3,1,"_CPPv4N4espp12EventManager13add_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::add_publisher"],[22,4,1,"_CPPv4N4espp12EventManager13add_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::add_publisher::component"],[22,4,1,"_CPPv4N4espp12EventManager13add_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::add_publisher::topic"],[22,3,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fn","espp::EventManager::add_subscriber"],[22,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fn","espp::EventManager::add_subscriber::callback"],[22,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fn","espp::EventManager::add_subscriber::component"],[22,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fn","espp::EventManager::add_subscriber::topic"],[22,8,1,"_CPPv4N4espp12EventManager17event_callback_fnE","espp::EventManager::event_callback_fn"],[22,3,1,"_CPPv4N4espp12EventManager3getEv","espp::EventManager::get"],[22,3,1,"_CPPv4N4espp12EventManager7publishERKNSt6stringERKNSt6vectorI7uint8_tEE","espp::EventManager::publish"],[22,4,1,"_CPPv4N4espp12EventManager7publishERKNSt6stringERKNSt6vectorI7uint8_tEE","espp::EventManager::publish::data"],[22,4,1,"_CPPv4N4espp12EventManager7publishERKNSt6stringERKNSt6vectorI7uint8_tEE","espp::EventManager::publish::topic"],[22,3,1,"_CPPv4N4espp12EventManager16remove_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::remove_publisher"],[22,4,1,"_CPPv4N4espp12EventManager16remove_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::remove_publisher::component"],[22,4,1,"_CPPv4N4espp12EventManager16remove_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::remove_publisher::topic"],[22,3,1,"_CPPv4N4espp12EventManager17remove_subscriberERKNSt6stringERKNSt6stringE","espp::EventManager::remove_subscriber"],[22,4,1,"_CPPv4N4espp12EventManager17remove_subscriberERKNSt6stringERKNSt6stringE","espp::EventManager::remove_subscriber::component"],[22,4,1,"_CPPv4N4espp12EventManager17remove_subscriberERKNSt6stringERKNSt6stringE","espp::EventManager::remove_subscriber::topic"],[22,3,1,"_CPPv4N4espp12EventManager13set_log_levelEN6Logger9VerbosityE","espp::EventManager::set_log_level"],[22,4,1,"_CPPv4N4espp12EventManager13set_log_levelEN6Logger9VerbosityE","espp::EventManager::set_log_level::level"],[23,2,1,"_CPPv4N4espp10FileSystemE","espp::FileSystem"],[23,2,1,"_CPPv4N4espp10FileSystem10ListConfigE","espp::FileSystem::ListConfig"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig9date_timeE","espp::FileSystem::ListConfig::date_time"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig5groupE","espp::FileSystem::ListConfig::group"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig15number_of_linksE","espp::FileSystem::ListConfig::number_of_links"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig5ownerE","espp::FileSystem::ListConfig::owner"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig11permissionsE","espp::FileSystem::ListConfig::permissions"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig9recursiveE","espp::FileSystem::ListConfig::recursive"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig4sizeE","espp::FileSystem::ListConfig::size"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig4typeE","espp::FileSystem::ListConfig::type"],[23,3,1,"_CPPv4N4espp10FileSystem3getEv","espp::FileSystem::get"],[23,3,1,"_CPPv4N4espp10FileSystem14get_free_spaceEv","espp::FileSystem::get_free_space"],[23,3,1,"_CPPv4N4espp10FileSystem15get_mount_pointEv","espp::FileSystem::get_mount_point"],[23,3,1,"_CPPv4N4espp10FileSystem19get_partition_labelEv","espp::FileSystem::get_partition_label"],[23,3,1,"_CPPv4N4espp10FileSystem13get_root_pathEv","espp::FileSystem::get_root_path"],[23,3,1,"_CPPv4N4espp10FileSystem15get_total_spaceEv","espp::FileSystem::get_total_space"],[23,3,1,"_CPPv4N4espp10FileSystem14get_used_spaceEv","espp::FileSystem::get_used_space"],[23,3,1,"_CPPv4N4espp10FileSystem14human_readableE6size_t","espp::FileSystem::human_readable"],[23,4,1,"_CPPv4N4espp10FileSystem14human_readableE6size_t","espp::FileSystem::human_readable::bytes"],[23,3,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory"],[23,3,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory"],[23,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::config"],[23,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::config"],[23,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::path"],[23,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::path"],[23,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::prefix"],[23,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::prefix"],[23,3,1,"_CPPv4I0EN4espp10FileSystem9to_time_tENSt6time_tE2TP","espp::FileSystem::to_time_t"],[23,5,1,"_CPPv4I0EN4espp10FileSystem9to_time_tENSt6time_tE2TP","espp::FileSystem::to_time_t::TP"],[23,4,1,"_CPPv4I0EN4espp10FileSystem9to_time_tENSt6time_tE2TP","espp::FileSystem::to_time_t::tp"],[30,2,1,"_CPPv4N4espp16FtpClientSessionE","espp::FtpClientSession"],[30,3,1,"_CPPv4NK4espp16FtpClientSession17current_directoryEv","espp::FtpClientSession::current_directory"],[30,3,1,"_CPPv4NK4espp16FtpClientSession2idEv","espp::FtpClientSession::id"],[30,3,1,"_CPPv4NK4espp16FtpClientSession8is_aliveEv","espp::FtpClientSession::is_alive"],[30,3,1,"_CPPv4NK4espp16FtpClientSession12is_connectedEv","espp::FtpClientSession::is_connected"],[30,3,1,"_CPPv4NK4espp16FtpClientSession26is_passive_data_connectionEv","espp::FtpClientSession::is_passive_data_connection"],[30,2,1,"_CPPv4N4espp9FtpServerE","espp::FtpServer"],[30,3,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer"],[30,4,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer::ip_address"],[30,4,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer::port"],[30,4,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer::root"],[30,3,1,"_CPPv4N4espp9FtpServer5startEv","espp::FtpServer::start"],[30,3,1,"_CPPv4N4espp9FtpServer4stopEv","espp::FtpServer::stop"],[30,3,1,"_CPPv4N4espp9FtpServerD0Ev","espp::FtpServer::~FtpServer"],[47,2,1,"_CPPv4N4espp8GaussianE","espp::Gaussian"],[47,2,1,"_CPPv4N4espp8Gaussian6ConfigE","espp::Gaussian::Config"],[47,1,1,"_CPPv4N4espp8Gaussian6Config5alphaE","espp::Gaussian::Config::alpha"],[47,1,1,"_CPPv4N4espp8Gaussian6Config4betaE","espp::Gaussian::Config::beta"],[47,1,1,"_CPPv4N4espp8Gaussian6Config5gammaE","espp::Gaussian::Config::gamma"],[47,3,1,"_CPPv4N4espp8Gaussian8GaussianERK6Config","espp::Gaussian::Gaussian"],[47,4,1,"_CPPv4N4espp8Gaussian8GaussianERK6Config","espp::Gaussian::Gaussian::config"],[47,3,1,"_CPPv4N4espp8Gaussian5alphaEf","espp::Gaussian::alpha"],[47,3,1,"_CPPv4NK4espp8Gaussian5alphaEv","espp::Gaussian::alpha"],[47,4,1,"_CPPv4N4espp8Gaussian5alphaEf","espp::Gaussian::alpha::a"],[47,3,1,"_CPPv4NK4espp8Gaussian2atEf","espp::Gaussian::at"],[47,4,1,"_CPPv4NK4espp8Gaussian2atEf","espp::Gaussian::at::t"],[47,3,1,"_CPPv4N4espp8Gaussian4betaEf","espp::Gaussian::beta"],[47,3,1,"_CPPv4NK4espp8Gaussian4betaEv","espp::Gaussian::beta"],[47,4,1,"_CPPv4N4espp8Gaussian4betaEf","espp::Gaussian::beta::b"],[47,3,1,"_CPPv4N4espp8Gaussian5gammaEf","espp::Gaussian::gamma"],[47,3,1,"_CPPv4NK4espp8Gaussian5gammaEv","espp::Gaussian::gamma"],[47,4,1,"_CPPv4N4espp8Gaussian5gammaEf","espp::Gaussian::gamma::g"],[47,3,1,"_CPPv4NK4espp8GaussianclEf","espp::Gaussian::operator()"],[47,4,1,"_CPPv4NK4espp8GaussianclEf","espp::Gaussian::operator()::t"],[11,2,1,"_CPPv4N4espp3HsvE","espp::Hsv"],[11,3,1,"_CPPv4N4espp3Hsv3HsvERK3Hsv","espp::Hsv::Hsv"],[11,3,1,"_CPPv4N4espp3Hsv3HsvERK3Rgb","espp::Hsv::Hsv"],[11,3,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv"],[11,4,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv::h"],[11,4,1,"_CPPv4N4espp3Hsv3HsvERK3Hsv","espp::Hsv::Hsv::hsv"],[11,4,1,"_CPPv4N4espp3Hsv3HsvERK3Rgb","espp::Hsv::Hsv::rgb"],[11,4,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv::s"],[11,4,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv::v"],[11,1,1,"_CPPv4N4espp3Hsv1hE","espp::Hsv::h"],[11,3,1,"_CPPv4NK4espp3Hsv3rgbEv","espp::Hsv::rgb"],[11,1,1,"_CPPv4N4espp3Hsv1sE","espp::Hsv::s"],[11,1,1,"_CPPv4N4espp3Hsv1vE","espp::Hsv::v"],[15,2,1,"_CPPv4N4espp7Ili9341E","espp::Ili9341"],[15,3,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear"],[15,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::color"],[15,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::height"],[15,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::width"],[15,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::x"],[15,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::y"],[15,3,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill"],[15,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::area"],[15,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::color_map"],[15,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::drv"],[15,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::flags"],[15,3,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush"],[15,4,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush::area"],[15,4,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush::color_map"],[15,4,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush::drv"],[15,3,1,"_CPPv4N4espp7Ili934110get_offsetERiRi","espp::Ili9341::get_offset"],[15,4,1,"_CPPv4N4espp7Ili934110get_offsetERiRi","espp::Ili9341::get_offset::x"],[15,4,1,"_CPPv4N4espp7Ili934110get_offsetERiRi","espp::Ili9341::get_offset::y"],[15,3,1,"_CPPv4N4espp7Ili934110initializeERKN15display_drivers6ConfigE","espp::Ili9341::initialize"],[15,4,1,"_CPPv4N4espp7Ili934110initializeERKN15display_drivers6ConfigE","espp::Ili9341::initialize::config"],[15,3,1,"_CPPv4N4espp7Ili934112send_commandE7uint8_t","espp::Ili9341::send_command"],[15,4,1,"_CPPv4N4espp7Ili934112send_commandE7uint8_t","espp::Ili9341::send_command::command"],[15,3,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data"],[15,4,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data::data"],[15,4,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data::flags"],[15,4,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data::length"],[15,3,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area"],[15,3,1,"_CPPv4N4espp7Ili934116set_drawing_areaEPK9lv_area_t","espp::Ili9341::set_drawing_area"],[15,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaEPK9lv_area_t","espp::Ili9341::set_drawing_area::area"],[15,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::xe"],[15,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::xs"],[15,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::ye"],[15,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::ys"],[15,3,1,"_CPPv4N4espp7Ili934110set_offsetEii","espp::Ili9341::set_offset"],[15,4,1,"_CPPv4N4espp7Ili934110set_offsetEii","espp::Ili9341::set_offset::x"],[15,4,1,"_CPPv4N4espp7Ili934110set_offsetEii","espp::Ili9341::set_offset::y"],[41,2,1,"_CPPv4N4espp8JoystickE","espp::Joystick"],[41,2,1,"_CPPv4N4espp8Joystick6ConfigE","espp::Joystick::Config"],[41,1,1,"_CPPv4N4espp8Joystick6Config8deadzoneE","espp::Joystick::Config::deadzone"],[41,1,1,"_CPPv4N4espp8Joystick6Config15deadzone_radiusE","espp::Joystick::Config::deadzone_radius"],[41,1,1,"_CPPv4N4espp8Joystick6Config10get_valuesE","espp::Joystick::Config::get_values"],[41,1,1,"_CPPv4N4espp8Joystick6Config9log_levelE","espp::Joystick::Config::log_level"],[41,1,1,"_CPPv4N4espp8Joystick6Config13x_calibrationE","espp::Joystick::Config::x_calibration"],[41,1,1,"_CPPv4N4espp8Joystick6Config13y_calibrationE","espp::Joystick::Config::y_calibration"],[41,6,1,"_CPPv4N4espp8Joystick8DeadzoneE","espp::Joystick::Deadzone"],[41,7,1,"_CPPv4N4espp8Joystick8Deadzone8CIRCULARE","espp::Joystick::Deadzone::CIRCULAR"],[41,7,1,"_CPPv4N4espp8Joystick8Deadzone11RECTANGULARE","espp::Joystick::Deadzone::RECTANGULAR"],[41,3,1,"_CPPv4N4espp8Joystick8JoystickERK6Config","espp::Joystick::Joystick"],[41,4,1,"_CPPv4N4espp8Joystick8JoystickERK6Config","espp::Joystick::Joystick::config"],[41,8,1,"_CPPv4N4espp8Joystick13get_values_fnE","espp::Joystick::get_values_fn"],[41,3,1,"_CPPv4NK4espp8Joystick8positionEv","espp::Joystick::position"],[41,3,1,"_CPPv4NK4espp8Joystick3rawEv","espp::Joystick::raw"],[41,3,1,"_CPPv4N4espp8Joystick15set_calibrationERKN16FloatRangeMapper6ConfigERKN16FloatRangeMapper6ConfigE","espp::Joystick::set_calibration"],[41,4,1,"_CPPv4N4espp8Joystick15set_calibrationERKN16FloatRangeMapper6ConfigERKN16FloatRangeMapper6ConfigE","espp::Joystick::set_calibration::x_calibration"],[41,4,1,"_CPPv4N4espp8Joystick15set_calibrationERKN16FloatRangeMapper6ConfigERKN16FloatRangeMapper6ConfigE","espp::Joystick::set_calibration::y_calibration"],[41,3,1,"_CPPv4N4espp8Joystick12set_deadzoneE8Deadzonef","espp::Joystick::set_deadzone"],[41,4,1,"_CPPv4N4espp8Joystick12set_deadzoneE8Deadzonef","espp::Joystick::set_deadzone::deadzone"],[41,4,1,"_CPPv4N4espp8Joystick12set_deadzoneE8Deadzonef","espp::Joystick::set_deadzone::radius"],[41,3,1,"_CPPv4N4espp8Joystick6updateEv","espp::Joystick::update"],[41,3,1,"_CPPv4NK4espp8Joystick1xEv","espp::Joystick::x"],[41,3,1,"_CPPv4NK4espp8Joystick1yEv","espp::Joystick::y"],[61,2,1,"_CPPv4N4espp9JpegFrameE","espp::JpegFrame"],[61,3,1,"_CPPv4N4espp9JpegFrame9JpegFrameEPKc6size_t","espp::JpegFrame::JpegFrame"],[61,3,1,"_CPPv4N4espp9JpegFrame9JpegFrameERK13RtpJpegPacket","espp::JpegFrame::JpegFrame"],[61,4,1,"_CPPv4N4espp9JpegFrame9JpegFrameEPKc6size_t","espp::JpegFrame::JpegFrame::data"],[61,4,1,"_CPPv4N4espp9JpegFrame9JpegFrameERK13RtpJpegPacket","espp::JpegFrame::JpegFrame::packet"],[61,4,1,"_CPPv4N4espp9JpegFrame9JpegFrameEPKc6size_t","espp::JpegFrame::JpegFrame::size"],[61,3,1,"_CPPv4N4espp9JpegFrame8add_scanERK13RtpJpegPacket","espp::JpegFrame::add_scan"],[61,4,1,"_CPPv4N4espp9JpegFrame8add_scanERK13RtpJpegPacket","espp::JpegFrame::add_scan::packet"],[61,3,1,"_CPPv4N4espp9JpegFrame6appendERK13RtpJpegPacket","espp::JpegFrame::append"],[61,4,1,"_CPPv4N4espp9JpegFrame6appendERK13RtpJpegPacket","espp::JpegFrame::append::packet"],[61,3,1,"_CPPv4NK4espp9JpegFrame8get_dataEv","espp::JpegFrame::get_data"],[61,3,1,"_CPPv4NK4espp9JpegFrame10get_headerEv","espp::JpegFrame::get_header"],[61,3,1,"_CPPv4NK4espp9JpegFrame10get_heightEv","espp::JpegFrame::get_height"],[61,3,1,"_CPPv4NK4espp9JpegFrame13get_scan_dataEv","espp::JpegFrame::get_scan_data"],[61,3,1,"_CPPv4NK4espp9JpegFrame9get_widthEv","espp::JpegFrame::get_width"],[61,3,1,"_CPPv4NK4espp9JpegFrame11is_completeEv","espp::JpegFrame::is_complete"],[61,2,1,"_CPPv4N4espp10JpegHeaderE","espp::JpegHeader"],[61,3,1,"_CPPv4N4espp10JpegHeader10JpegHeaderENSt11string_viewE","espp::JpegHeader::JpegHeader"],[61,3,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader"],[61,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderENSt11string_viewE","espp::JpegHeader::JpegHeader::data"],[61,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::height"],[61,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::q0_table"],[61,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::q1_table"],[61,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::width"],[61,3,1,"_CPPv4NK4espp10JpegHeader8get_dataEv","espp::JpegHeader::get_data"],[61,3,1,"_CPPv4NK4espp10JpegHeader10get_heightEv","espp::JpegHeader::get_height"],[61,3,1,"_CPPv4NK4espp10JpegHeader22get_quantization_tableEi","espp::JpegHeader::get_quantization_table"],[61,4,1,"_CPPv4NK4espp10JpegHeader22get_quantization_tableEi","espp::JpegHeader::get_quantization_table::index"],[61,3,1,"_CPPv4NK4espp10JpegHeader9get_widthEv","espp::JpegHeader::get_width"],[42,2,1,"_CPPv4N4espp3LedE","espp::Led"],[42,2,1,"_CPPv4N4espp3Led13ChannelConfigE","espp::Led::ChannelConfig"],[42,1,1,"_CPPv4N4espp3Led13ChannelConfig7channelE","espp::Led::ChannelConfig::channel"],[42,1,1,"_CPPv4N4espp3Led13ChannelConfig4dutyE","espp::Led::ChannelConfig::duty"],[42,1,1,"_CPPv4N4espp3Led13ChannelConfig4gpioE","espp::Led::ChannelConfig::gpio"],[42,1,1,"_CPPv4N4espp3Led13ChannelConfig13output_invertE","espp::Led::ChannelConfig::output_invert"],[42,1,1,"_CPPv4N4espp3Led13ChannelConfig10speed_modeE","espp::Led::ChannelConfig::speed_mode"],[42,1,1,"_CPPv4N4espp3Led13ChannelConfig5timerE","espp::Led::ChannelConfig::timer"],[42,2,1,"_CPPv4N4espp3Led6ConfigE","espp::Led::Config"],[42,1,1,"_CPPv4N4espp3Led6Config8channelsE","espp::Led::Config::channels"],[42,1,1,"_CPPv4N4espp3Led6Config15duty_resolutionE","espp::Led::Config::duty_resolution"],[42,1,1,"_CPPv4N4espp3Led6Config12frequency_hzE","espp::Led::Config::frequency_hz"],[42,1,1,"_CPPv4N4espp3Led6Config9log_levelE","espp::Led::Config::log_level"],[42,1,1,"_CPPv4N4espp3Led6Config10speed_modeE","espp::Led::Config::speed_mode"],[42,1,1,"_CPPv4N4espp3Led6Config5timerE","espp::Led::Config::timer"],[42,3,1,"_CPPv4N4espp3Led3LedERK6Config","espp::Led::Led"],[42,4,1,"_CPPv4N4espp3Led3LedERK6Config","espp::Led::Led::config"],[42,3,1,"_CPPv4N4espp3Led10can_changeE14ledc_channel_t","espp::Led::can_change"],[42,4,1,"_CPPv4N4espp3Led10can_changeE14ledc_channel_t","espp::Led::can_change::channel"],[42,3,1,"_CPPv4N4espp3Led8get_dutyE14ledc_channel_t","espp::Led::get_duty"],[42,4,1,"_CPPv4N4espp3Led8get_dutyE14ledc_channel_t","espp::Led::get_duty::channel"],[42,3,1,"_CPPv4N4espp3Led8set_dutyE14ledc_channel_tf","espp::Led::set_duty"],[42,4,1,"_CPPv4N4espp3Led8set_dutyE14ledc_channel_tf","espp::Led::set_duty::channel"],[42,4,1,"_CPPv4N4espp3Led8set_dutyE14ledc_channel_tf","espp::Led::set_duty::duty_percent"],[42,3,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time"],[42,4,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time::channel"],[42,4,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time::duty_percent"],[42,4,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time::fade_time_ms"],[42,3,1,"_CPPv4N4espp3LedD0Ev","espp::Led::~Led"],[43,2,1,"_CPPv4N4espp8LedStripE","espp::LedStrip"],[43,1,1,"_CPPv4N4espp8LedStrip18APA102_START_FRAMEE","espp::LedStrip::APA102_START_FRAME"],[43,6,1,"_CPPv4N4espp8LedStrip9ByteOrderE","espp::LedStrip::ByteOrder"],[43,7,1,"_CPPv4N4espp8LedStrip9ByteOrder3BGRE","espp::LedStrip::ByteOrder::BGR"],[43,7,1,"_CPPv4N4espp8LedStrip9ByteOrder3GRBE","espp::LedStrip::ByteOrder::GRB"],[43,7,1,"_CPPv4N4espp8LedStrip9ByteOrder3RGBE","espp::LedStrip::ByteOrder::RGB"],[43,2,1,"_CPPv4N4espp8LedStrip6ConfigE","espp::LedStrip::Config"],[43,1,1,"_CPPv4N4espp8LedStrip6Config10byte_orderE","espp::LedStrip::Config::byte_order"],[43,1,1,"_CPPv4N4espp8LedStrip6Config9end_frameE","espp::LedStrip::Config::end_frame"],[43,1,1,"_CPPv4N4espp8LedStrip6Config9log_levelE","espp::LedStrip::Config::log_level"],[43,1,1,"_CPPv4N4espp8LedStrip6Config8num_ledsE","espp::LedStrip::Config::num_leds"],[43,1,1,"_CPPv4N4espp8LedStrip6Config15send_brightnessE","espp::LedStrip::Config::send_brightness"],[43,1,1,"_CPPv4N4espp8LedStrip6Config11start_frameE","espp::LedStrip::Config::start_frame"],[43,1,1,"_CPPv4N4espp8LedStrip6Config5writeE","espp::LedStrip::Config::write"],[43,3,1,"_CPPv4N4espp8LedStrip8LedStripERK6Config","espp::LedStrip::LedStrip"],[43,4,1,"_CPPv4N4espp8LedStrip8LedStripERK6Config","espp::LedStrip::LedStrip::config"],[43,3,1,"_CPPv4NK4espp8LedStrip10byte_orderEv","espp::LedStrip::byte_order"],[43,3,1,"_CPPv4NK4espp8LedStrip8num_ledsEv","espp::LedStrip::num_leds"],[43,3,1,"_CPPv4N4espp8LedStrip7set_allE3Hsvf","espp::LedStrip::set_all"],[43,3,1,"_CPPv4N4espp8LedStrip7set_allE3Rgbf","espp::LedStrip::set_all"],[43,3,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::b"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE3Hsvf","espp::LedStrip::set_all::brightness"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE3Rgbf","espp::LedStrip::set_all::brightness"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::brightness"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::g"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE3Hsvf","espp::LedStrip::set_all::hsv"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::r"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE3Rgbf","espp::LedStrip::set_all::rgb"],[43,3,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel"],[43,3,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel"],[43,3,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::b"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel::brightness"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel::brightness"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::brightness"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::g"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel::hsv"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel::index"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel::index"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::index"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::r"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel::rgb"],[43,3,1,"_CPPv4N4espp8LedStrip10shift_leftEi","espp::LedStrip::shift_left"],[43,4,1,"_CPPv4N4espp8LedStrip10shift_leftEi","espp::LedStrip::shift_left::shift_by"],[43,3,1,"_CPPv4N4espp8LedStrip11shift_rightEi","espp::LedStrip::shift_right"],[43,4,1,"_CPPv4N4espp8LedStrip11shift_rightEi","espp::LedStrip::shift_right::shift_by"],[43,3,1,"_CPPv4N4espp8LedStrip4showEv","espp::LedStrip::show"],[43,8,1,"_CPPv4N4espp8LedStrip8write_fnE","espp::LedStrip::write_fn"],[10,2,1,"_CPPv4N4espp9LineInputE","espp::LineInput"],[10,8,1,"_CPPv4N4espp9LineInput7HistoryE","espp::LineInput::History"],[10,3,1,"_CPPv4N4espp9LineInput9LineInputEv","espp::LineInput::LineInput"],[10,3,1,"_CPPv4NK4espp9LineInput11get_historyEv","espp::LineInput::get_history"],[10,3,1,"_CPPv4N4espp9LineInput14get_user_inputERNSt7istreamE9prompt_fn","espp::LineInput::get_user_input"],[10,4,1,"_CPPv4N4espp9LineInput14get_user_inputERNSt7istreamE9prompt_fn","espp::LineInput::get_user_input::is"],[10,4,1,"_CPPv4N4espp9LineInput14get_user_inputERNSt7istreamE9prompt_fn","espp::LineInput::get_user_input::prompt"],[10,8,1,"_CPPv4N4espp9LineInput9prompt_fnE","espp::LineInput::prompt_fn"],[10,3,1,"_CPPv4N4espp9LineInput11set_historyERK7History","espp::LineInput::set_history"],[10,4,1,"_CPPv4N4espp9LineInput11set_historyERK7History","espp::LineInput::set_history::history"],[10,3,1,"_CPPv4N4espp9LineInput16set_history_sizeE6size_t","espp::LineInput::set_history_size"],[10,4,1,"_CPPv4N4espp9LineInput16set_history_sizeE6size_t","espp::LineInput::set_history_size::new_size"],[10,3,1,"_CPPv4N4espp9LineInputD0Ev","espp::LineInput::~LineInput"],[44,2,1,"_CPPv4N4espp6LoggerE","espp::Logger"],[44,2,1,"_CPPv4N4espp6Logger6ConfigE","espp::Logger::Config"],[44,1,1,"_CPPv4N4espp6Logger6Config5levelE","espp::Logger::Config::level"],[44,1,1,"_CPPv4N4espp6Logger6Config10rate_limitE","espp::Logger::Config::rate_limit"],[44,1,1,"_CPPv4N4espp6Logger6Config3tagE","espp::Logger::Config::tag"],[44,3,1,"_CPPv4N4espp6Logger6LoggerERK6Config","espp::Logger::Logger"],[44,4,1,"_CPPv4N4espp6Logger6LoggerERK6Config","espp::Logger::Logger::config"],[44,6,1,"_CPPv4N4espp6Logger9VerbosityE","espp::Logger::Verbosity"],[44,7,1,"_CPPv4N4espp6Logger9Verbosity5DEBUGE","espp::Logger::Verbosity::DEBUG"],[44,7,1,"_CPPv4N4espp6Logger9Verbosity5ERRORE","espp::Logger::Verbosity::ERROR"],[44,7,1,"_CPPv4N4espp6Logger9Verbosity4INFOE","espp::Logger::Verbosity::INFO"],[44,7,1,"_CPPv4N4espp6Logger9Verbosity4NONEE","espp::Logger::Verbosity::NONE"],[44,7,1,"_CPPv4N4espp6Logger9Verbosity4WARNE","espp::Logger::Verbosity::WARN"],[44,3,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug"],[44,5,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited"],[44,5,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error"],[44,5,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited"],[44,5,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format"],[44,5,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info"],[44,5,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited"],[44,5,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited::rt_fmt_str"],[44,3,1,"_CPPv4N4espp6Logger13set_verbosityEK9Verbosity","espp::Logger::set_verbosity"],[44,4,1,"_CPPv4N4espp6Logger13set_verbosityEK9Verbosity","espp::Logger::set_verbosity::level"],[44,3,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn"],[44,5,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited"],[44,5,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited::rt_fmt_str"],[27,2,1,"_CPPv4N4espp13LowpassFilterE","espp::LowpassFilter"],[27,2,1,"_CPPv4N4espp13LowpassFilter6ConfigE","espp::LowpassFilter::Config"],[27,1,1,"_CPPv4N4espp13LowpassFilter6Config27normalized_cutoff_frequencyE","espp::LowpassFilter::Config::normalized_cutoff_frequency"],[27,1,1,"_CPPv4N4espp13LowpassFilter6Config8q_factorE","espp::LowpassFilter::Config::q_factor"],[27,3,1,"_CPPv4N4espp13LowpassFilter13LowpassFilterERK6Config","espp::LowpassFilter::LowpassFilter"],[27,4,1,"_CPPv4N4espp13LowpassFilter13LowpassFilterERK6Config","espp::LowpassFilter::LowpassFilter::config"],[27,3,1,"_CPPv4N4espp13LowpassFilterclEf","espp::LowpassFilter::operator()"],[27,4,1,"_CPPv4N4espp13LowpassFilterclEf","espp::LowpassFilter::operator()::input"],[27,3,1,"_CPPv4N4espp13LowpassFilter6updateEKf","espp::LowpassFilter::update"],[27,3,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update"],[27,4,1,"_CPPv4N4espp13LowpassFilter6updateEKf","espp::LowpassFilter::update::input"],[27,4,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update::input"],[27,4,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update::length"],[27,4,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update::output"],[40,2,1,"_CPPv4N4espp8Mcp23x17E","espp::Mcp23x17"],[40,2,1,"_CPPv4N4espp8Mcp23x176ConfigE","espp::Mcp23x17::Config"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config14device_addressE","espp::Mcp23x17::Config::device_address"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config9log_levelE","espp::Mcp23x17::Config::log_level"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config21port_a_direction_maskE","espp::Mcp23x17::Config::port_a_direction_mask"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config21port_a_interrupt_maskE","espp::Mcp23x17::Config::port_a_interrupt_mask"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config21port_b_direction_maskE","espp::Mcp23x17::Config::port_b_direction_mask"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config21port_b_interrupt_maskE","espp::Mcp23x17::Config::port_b_interrupt_mask"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config4readE","espp::Mcp23x17::Config::read"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config5writeE","espp::Mcp23x17::Config::write"],[40,1,1,"_CPPv4N4espp8Mcp23x1715DEFAULT_ADDRESSE","espp::Mcp23x17::DEFAULT_ADDRESS"],[40,3,1,"_CPPv4N4espp8Mcp23x178Mcp23x17ERK6Config","espp::Mcp23x17::Mcp23x17"],[40,4,1,"_CPPv4N4espp8Mcp23x178Mcp23x17ERK6Config","espp::Mcp23x17::Mcp23x17::config"],[40,6,1,"_CPPv4N4espp8Mcp23x174PortE","espp::Mcp23x17::Port"],[40,7,1,"_CPPv4N4espp8Mcp23x174Port1AE","espp::Mcp23x17::Port::A"],[40,7,1,"_CPPv4N4espp8Mcp23x174Port1BE","espp::Mcp23x17::Port::B"],[40,3,1,"_CPPv4N4espp8Mcp23x1721get_interrupt_captureE4Port","espp::Mcp23x17::get_interrupt_capture"],[40,4,1,"_CPPv4N4espp8Mcp23x1721get_interrupt_captureE4Port","espp::Mcp23x17::get_interrupt_capture::port"],[40,3,1,"_CPPv4N4espp8Mcp23x178get_pinsE4Port","espp::Mcp23x17::get_pins"],[40,4,1,"_CPPv4N4espp8Mcp23x178get_pinsE4Port","espp::Mcp23x17::get_pins::port"],[40,8,1,"_CPPv4N4espp8Mcp23x177read_fnE","espp::Mcp23x17::read_fn"],[40,3,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_t","espp::Mcp23x17::set_direction"],[40,4,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_t","espp::Mcp23x17::set_direction::mask"],[40,4,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_t","espp::Mcp23x17::set_direction::port"],[40,3,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_t","espp::Mcp23x17::set_input_polarity"],[40,4,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_t","espp::Mcp23x17::set_input_polarity::mask"],[40,4,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_t","espp::Mcp23x17::set_input_polarity::port"],[40,3,1,"_CPPv4N4espp8Mcp23x1720set_interrupt_mirrorEb","espp::Mcp23x17::set_interrupt_mirror"],[40,4,1,"_CPPv4N4espp8Mcp23x1720set_interrupt_mirrorEb","espp::Mcp23x17::set_interrupt_mirror::mirror"],[40,3,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_t","espp::Mcp23x17::set_interrupt_on_change"],[40,4,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_t","espp::Mcp23x17::set_interrupt_on_change::mask"],[40,4,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_t","espp::Mcp23x17::set_interrupt_on_change::port"],[40,3,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_t","espp::Mcp23x17::set_interrupt_on_value"],[40,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_t","espp::Mcp23x17::set_interrupt_on_value::pin_mask"],[40,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_t","espp::Mcp23x17::set_interrupt_on_value::port"],[40,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_t","espp::Mcp23x17::set_interrupt_on_value::val_mask"],[40,3,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_polarityEb","espp::Mcp23x17::set_interrupt_polarity"],[40,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_polarityEb","espp::Mcp23x17::set_interrupt_polarity::active_high"],[40,3,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_t","espp::Mcp23x17::set_pins"],[40,4,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_t","espp::Mcp23x17::set_pins::output"],[40,4,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_t","espp::Mcp23x17::set_pins::port"],[40,3,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_t","espp::Mcp23x17::set_pull_up"],[40,4,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_t","espp::Mcp23x17::set_pull_up::mask"],[40,4,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_t","espp::Mcp23x17::set_pull_up::port"],[40,8,1,"_CPPv4N4espp8Mcp23x178write_fnE","espp::Mcp23x17::write_fn"],[21,2,1,"_CPPv4N4espp6Mt6701E","espp::Mt6701"],[21,1,1,"_CPPv4N4espp6Mt670121COUNTS_PER_REVOLUTIONE","espp::Mt6701::COUNTS_PER_REVOLUTION"],[21,1,1,"_CPPv4N4espp6Mt670123COUNTS_PER_REVOLUTION_FE","espp::Mt6701::COUNTS_PER_REVOLUTION_F"],[21,1,1,"_CPPv4N4espp6Mt670117COUNTS_TO_DEGREESE","espp::Mt6701::COUNTS_TO_DEGREES"],[21,1,1,"_CPPv4N4espp6Mt670117COUNTS_TO_RADIANSE","espp::Mt6701::COUNTS_TO_RADIANS"],[21,2,1,"_CPPv4N4espp6Mt67016ConfigE","espp::Mt6701::Config"],[21,1,1,"_CPPv4N4espp6Mt67016Config14device_addressE","espp::Mt6701::Config::device_address"],[21,1,1,"_CPPv4N4espp6Mt67016Config4readE","espp::Mt6701::Config::read"],[21,1,1,"_CPPv4N4espp6Mt67016Config13update_periodE","espp::Mt6701::Config::update_period"],[21,1,1,"_CPPv4N4espp6Mt67016Config15velocity_filterE","espp::Mt6701::Config::velocity_filter"],[21,1,1,"_CPPv4N4espp6Mt67016Config5writeE","espp::Mt6701::Config::write"],[21,1,1,"_CPPv4N4espp6Mt670115DEFAULT_ADDRESSE","espp::Mt6701::DEFAULT_ADDRESS"],[21,3,1,"_CPPv4N4espp6Mt67016Mt6701ERK6Config","espp::Mt6701::Mt6701"],[21,4,1,"_CPPv4N4espp6Mt67016Mt6701ERK6Config","espp::Mt6701::Mt6701::config"],[21,1,1,"_CPPv4N4espp6Mt670118SECONDS_PER_MINUTEE","espp::Mt6701::SECONDS_PER_MINUTE"],[21,3,1,"_CPPv4NK4espp6Mt670115get_accumulatorEv","espp::Mt6701::get_accumulator"],[21,3,1,"_CPPv4NK4espp6Mt67019get_countEv","espp::Mt6701::get_count"],[21,3,1,"_CPPv4NK4espp6Mt670111get_degreesEv","espp::Mt6701::get_degrees"],[21,3,1,"_CPPv4NK4espp6Mt670122get_mechanical_degreesEv","espp::Mt6701::get_mechanical_degrees"],[21,3,1,"_CPPv4NK4espp6Mt670122get_mechanical_radiansEv","espp::Mt6701::get_mechanical_radians"],[21,3,1,"_CPPv4NK4espp6Mt670111get_radiansEv","espp::Mt6701::get_radians"],[21,3,1,"_CPPv4NK4espp6Mt67017get_rpmEv","espp::Mt6701::get_rpm"],[21,3,1,"_CPPv4NK4espp6Mt670117needs_zero_searchEv","espp::Mt6701::needs_zero_search"],[21,8,1,"_CPPv4N4espp6Mt67017read_fnE","espp::Mt6701::read_fn"],[21,8,1,"_CPPv4N4espp6Mt670118velocity_filter_fnE","espp::Mt6701::velocity_filter_fn"],[21,8,1,"_CPPv4N4espp6Mt67018write_fnE","espp::Mt6701::write_fn"],[57,2,1,"_CPPv4N4espp4NdefE","espp::Ndef"],[57,6,1,"_CPPv4N4espp4Ndef7BleRoleE","espp::Ndef::BleRole"],[57,7,1,"_CPPv4N4espp4Ndef7BleRole12CENTRAL_ONLYE","espp::Ndef::BleRole::CENTRAL_ONLY"],[57,7,1,"_CPPv4N4espp4Ndef7BleRole18CENTRAL_PERIPHERALE","espp::Ndef::BleRole::CENTRAL_PERIPHERAL"],[57,7,1,"_CPPv4N4espp4Ndef7BleRole18PERIPHERAL_CENTRALE","espp::Ndef::BleRole::PERIPHERAL_CENTRAL"],[57,7,1,"_CPPv4N4espp4Ndef7BleRole15PERIPHERAL_ONLYE","espp::Ndef::BleRole::PERIPHERAL_ONLY"],[57,6,1,"_CPPv4N4espp4Ndef12BtAppearanceE","espp::Ndef::BtAppearance"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance5CLOCKE","espp::Ndef::BtAppearance::CLOCK"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance8COMPUTERE","espp::Ndef::BtAppearance::COMPUTER"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance7DISPLAYE","espp::Ndef::BtAppearance::DISPLAY"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance7GAMEPADE","espp::Ndef::BtAppearance::GAMEPAD"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance6GAMINGE","espp::Ndef::BtAppearance::GAMING"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance11GENERIC_HIDE","espp::Ndef::BtAppearance::GENERIC_HID"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance8JOYSTICKE","espp::Ndef::BtAppearance::JOYSTICK"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance8KEYBOARDE","espp::Ndef::BtAppearance::KEYBOARD"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance5MOUSEE","espp::Ndef::BtAppearance::MOUSE"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance5PHONEE","espp::Ndef::BtAppearance::PHONE"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance14REMOTE_CONTROLE","espp::Ndef::BtAppearance::REMOTE_CONTROL"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance8TOUCHPADE","espp::Ndef::BtAppearance::TOUCHPAD"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance7UNKNOWNE","espp::Ndef::BtAppearance::UNKNOWN"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance5WATCHE","espp::Ndef::BtAppearance::WATCH"],[57,6,1,"_CPPv4N4espp4Ndef5BtEirE","espp::Ndef::BtEir"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir10APPEARANCEE","espp::Ndef::BtEir::APPEARANCE"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir15CLASS_OF_DEVICEE","espp::Ndef::BtEir::CLASS_OF_DEVICE"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir5FLAGSE","espp::Ndef::BtEir::FLAGS"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir7LE_ROLEE","espp::Ndef::BtEir::LE_ROLE"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir18LE_SC_CONFIRMATIONE","espp::Ndef::BtEir::LE_SC_CONFIRMATION"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir12LE_SC_RANDOME","espp::Ndef::BtEir::LE_SC_RANDOM"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir15LONG_LOCAL_NAMEE","espp::Ndef::BtEir::LONG_LOCAL_NAME"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir3MACE","espp::Ndef::BtEir::MAC"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir22SECURITY_MANAGER_FLAGSE","espp::Ndef::BtEir::SECURITY_MANAGER_FLAGS"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir19SECURITY_MANAGER_TKE","espp::Ndef::BtEir::SECURITY_MANAGER_TK"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir16SHORT_LOCAL_NAMEE","espp::Ndef::BtEir::SHORT_LOCAL_NAME"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir12SP_HASH_C192E","espp::Ndef::BtEir::SP_HASH_C192"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir12SP_HASH_C256E","espp::Ndef::BtEir::SP_HASH_C256"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir12SP_HASH_R256E","espp::Ndef::BtEir::SP_HASH_R256"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir14SP_RANDOM_R192E","espp::Ndef::BtEir::SP_RANDOM_R192"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir14TX_POWER_LEVELE","espp::Ndef::BtEir::TX_POWER_LEVEL"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir22UUIDS_128_BIT_COMPLETEE","espp::Ndef::BtEir::UUIDS_128_BIT_COMPLETE"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir21UUIDS_128_BIT_PARTIALE","espp::Ndef::BtEir::UUIDS_128_BIT_PARTIAL"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir21UUIDS_16_BIT_COMPLETEE","espp::Ndef::BtEir::UUIDS_16_BIT_COMPLETE"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir20UUIDS_16_BIT_PARTIALE","espp::Ndef::BtEir::UUIDS_16_BIT_PARTIAL"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir21UUIDS_32_BIT_COMPLETEE","espp::Ndef::BtEir::UUIDS_32_BIT_COMPLETE"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir20UUIDS_32_BIT_PARTIALE","espp::Ndef::BtEir::UUIDS_32_BIT_PARTIAL"],[57,6,1,"_CPPv4N4espp4Ndef6BtTypeE","espp::Ndef::BtType"],[57,7,1,"_CPPv4N4espp4Ndef6BtType3BLEE","espp::Ndef::BtType::BLE"],[57,7,1,"_CPPv4N4espp4Ndef6BtType5BREDRE","espp::Ndef::BtType::BREDR"],[57,3,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef"],[57,4,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef::payload"],[57,4,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef::tnf"],[57,4,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef::type"],[57,6,1,"_CPPv4N4espp4Ndef3TNFE","espp::Ndef::TNF"],[57,7,1,"_CPPv4N4espp4Ndef3TNF12ABSOLUTE_URIE","espp::Ndef::TNF::ABSOLUTE_URI"],[57,7,1,"_CPPv4N4espp4Ndef3TNF5EMPTYE","espp::Ndef::TNF::EMPTY"],[57,7,1,"_CPPv4N4espp4Ndef3TNF13EXTERNAL_TYPEE","espp::Ndef::TNF::EXTERNAL_TYPE"],[57,7,1,"_CPPv4N4espp4Ndef3TNF10MIME_MEDIAE","espp::Ndef::TNF::MIME_MEDIA"],[57,7,1,"_CPPv4N4espp4Ndef3TNF8RESERVEDE","espp::Ndef::TNF::RESERVED"],[57,7,1,"_CPPv4N4espp4Ndef3TNF9UNCHANGEDE","espp::Ndef::TNF::UNCHANGED"],[57,7,1,"_CPPv4N4espp4Ndef3TNF7UNKNOWNE","espp::Ndef::TNF::UNKNOWN"],[57,7,1,"_CPPv4N4espp4Ndef3TNF10WELL_KNOWNE","espp::Ndef::TNF::WELL_KNOWN"],[57,6,1,"_CPPv4N4espp4Ndef3UicE","espp::Ndef::Uic"],[57,7,1,"_CPPv4N4espp4Ndef3Uic6BTGOEPE","espp::Ndef::Uic::BTGOEP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic7BTL2CAPE","espp::Ndef::Uic::BTL2CAP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic5BTSPPE","espp::Ndef::Uic::BTSPP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3DAVE","espp::Ndef::Uic::DAV"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4FILEE","espp::Ndef::Uic::FILE"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3FTPE","espp::Ndef::Uic::FTP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4FTPSE","espp::Ndef::Uic::FTPS"],[57,7,1,"_CPPv4N4espp4Ndef3Uic8FTP_ANONE","espp::Ndef::Uic::FTP_ANON"],[57,7,1,"_CPPv4N4espp4Ndef3Uic7FTP_FTPE","espp::Ndef::Uic::FTP_FTP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4HTTPE","espp::Ndef::Uic::HTTP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic5HTTPSE","espp::Ndef::Uic::HTTPS"],[57,7,1,"_CPPv4N4espp4Ndef3Uic9HTTPS_WWWE","espp::Ndef::Uic::HTTPS_WWW"],[57,7,1,"_CPPv4N4espp4Ndef3Uic8HTTP_WWWE","espp::Ndef::Uic::HTTP_WWW"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4IMAPE","espp::Ndef::Uic::IMAP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic8IRDAOBEXE","espp::Ndef::Uic::IRDAOBEX"],[57,7,1,"_CPPv4N4espp4Ndef3Uic6MAILTOE","espp::Ndef::Uic::MAILTO"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4NEWSE","espp::Ndef::Uic::NEWS"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3NFSE","espp::Ndef::Uic::NFS"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4NONEE","espp::Ndef::Uic::NONE"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3POPE","espp::Ndef::Uic::POP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4RSTPE","espp::Ndef::Uic::RSTP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4SFTPE","espp::Ndef::Uic::SFTP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3SIPE","espp::Ndef::Uic::SIP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4SIPSE","espp::Ndef::Uic::SIPS"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3SMBE","espp::Ndef::Uic::SMB"],[57,7,1,"_CPPv4N4espp4Ndef3Uic7TCPOBEXE","espp::Ndef::Uic::TCPOBEX"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3TELE","espp::Ndef::Uic::TEL"],[57,7,1,"_CPPv4N4espp4Ndef3Uic6TELNETE","espp::Ndef::Uic::TELNET"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4TFTPE","espp::Ndef::Uic::TFTP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3URNE","espp::Ndef::Uic::URN"],[57,7,1,"_CPPv4N4espp4Ndef3Uic7URN_EPCE","espp::Ndef::Uic::URN_EPC"],[57,7,1,"_CPPv4N4espp4Ndef3Uic10URN_EPC_IDE","espp::Ndef::Uic::URN_EPC_ID"],[57,7,1,"_CPPv4N4espp4Ndef3Uic11URN_EPC_PATE","espp::Ndef::Uic::URN_EPC_PAT"],[57,7,1,"_CPPv4N4espp4Ndef3Uic11URN_EPC_RAWE","espp::Ndef::Uic::URN_EPC_RAW"],[57,7,1,"_CPPv4N4espp4Ndef3Uic11URN_EPC_TAGE","espp::Ndef::Uic::URN_EPC_TAG"],[57,7,1,"_CPPv4N4espp4Ndef3Uic7URN_NFCE","espp::Ndef::Uic::URN_NFC"],[57,6,1,"_CPPv4N4espp4Ndef22WifiAuthenticationTypeE","espp::Ndef::WifiAuthenticationType"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType4OPENE","espp::Ndef::WifiAuthenticationType::OPEN"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType6SHAREDE","espp::Ndef::WifiAuthenticationType::SHARED"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType15WPA2_ENTERPRISEE","espp::Ndef::WifiAuthenticationType::WPA2_ENTERPRISE"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType13WPA2_PERSONALE","espp::Ndef::WifiAuthenticationType::WPA2_PERSONAL"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType14WPA_ENTERPRISEE","espp::Ndef::WifiAuthenticationType::WPA_ENTERPRISE"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType12WPA_PERSONALE","espp::Ndef::WifiAuthenticationType::WPA_PERSONAL"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType17WPA_WPA2_PERSONALE","espp::Ndef::WifiAuthenticationType::WPA_WPA2_PERSONAL"],[57,2,1,"_CPPv4N4espp4Ndef10WifiConfigE","espp::Ndef::WifiConfig"],[57,1,1,"_CPPv4N4espp4Ndef10WifiConfig14authenticationE","espp::Ndef::WifiConfig::authentication"],[57,1,1,"_CPPv4N4espp4Ndef10WifiConfig10encryptionE","espp::Ndef::WifiConfig::encryption"],[57,1,1,"_CPPv4N4espp4Ndef10WifiConfig3keyE","espp::Ndef::WifiConfig::key"],[57,1,1,"_CPPv4N4espp4Ndef10WifiConfig11mac_addressE","espp::Ndef::WifiConfig::mac_address"],[57,1,1,"_CPPv4N4espp4Ndef10WifiConfig4ssidE","espp::Ndef::WifiConfig::ssid"],[57,6,1,"_CPPv4N4espp4Ndef18WifiEncryptionTypeE","espp::Ndef::WifiEncryptionType"],[57,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType3AESE","espp::Ndef::WifiEncryptionType::AES"],[57,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType4NONEE","espp::Ndef::WifiEncryptionType::NONE"],[57,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType4TKIPE","espp::Ndef::WifiEncryptionType::TKIP"],[57,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType3WEPE","espp::Ndef::WifiEncryptionType::WEP"],[57,3,1,"_CPPv4NK4espp4Ndef8get_sizeEv","espp::Ndef::get_size"],[57,3,1,"_CPPv4N4espp4Ndef21make_android_launcherENSt11string_viewE","espp::Ndef::make_android_launcher"],[57,4,1,"_CPPv4N4espp4Ndef21make_android_launcherENSt11string_viewE","espp::Ndef::make_android_launcher::uri"],[57,3,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearance","espp::Ndef::make_le_oob_pairing"],[57,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearance","espp::Ndef::make_le_oob_pairing::appearance"],[57,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearance","espp::Ndef::make_le_oob_pairing::mac_addr"],[57,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearance","espp::Ndef::make_le_oob_pairing::name"],[57,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearance","espp::Ndef::make_le_oob_pairing::role"],[57,3,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewE","espp::Ndef::make_oob_pairing"],[57,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewE","espp::Ndef::make_oob_pairing::device_class"],[57,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewE","espp::Ndef::make_oob_pairing::mac_addr"],[57,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewE","espp::Ndef::make_oob_pairing::name"],[57,3,1,"_CPPv4N4espp4Ndef9make_textENSt11string_viewE","espp::Ndef::make_text"],[57,4,1,"_CPPv4N4espp4Ndef9make_textENSt11string_viewE","espp::Ndef::make_text::text"],[57,3,1,"_CPPv4N4espp4Ndef8make_uriENSt11string_viewE3Uic","espp::Ndef::make_uri"],[57,4,1,"_CPPv4N4espp4Ndef8make_uriENSt11string_viewE3Uic","espp::Ndef::make_uri::uic"],[57,4,1,"_CPPv4N4espp4Ndef8make_uriENSt11string_viewE3Uic","espp::Ndef::make_uri::uri"],[57,3,1,"_CPPv4N4espp4Ndef16make_wifi_configERK10WifiConfig","espp::Ndef::make_wifi_config"],[57,4,1,"_CPPv4N4espp4Ndef16make_wifi_configERK10WifiConfig","espp::Ndef::make_wifi_config::config"],[57,3,1,"_CPPv4N4espp4Ndef7payloadEv","espp::Ndef::payload"],[57,3,1,"_CPPv4N4espp4Ndef9serializeEv","espp::Ndef::serialize"],[5,2,1,"_CPPv4N4espp10OneshotAdcE","espp::OneshotAdc"],[5,2,1,"_CPPv4N4espp10OneshotAdc6ConfigE","espp::OneshotAdc::Config"],[5,1,1,"_CPPv4N4espp10OneshotAdc6Config8channelsE","espp::OneshotAdc::Config::channels"],[5,1,1,"_CPPv4N4espp10OneshotAdc6Config9log_levelE","espp::OneshotAdc::Config::log_level"],[5,1,1,"_CPPv4N4espp10OneshotAdc6Config4unitE","espp::OneshotAdc::Config::unit"],[5,3,1,"_CPPv4N4espp10OneshotAdc10OneshotAdcERK6Config","espp::OneshotAdc::OneshotAdc"],[5,4,1,"_CPPv4N4espp10OneshotAdc10OneshotAdcERK6Config","espp::OneshotAdc::OneshotAdc::config"],[5,3,1,"_CPPv4N4espp10OneshotAdc7read_mvERK9AdcConfig","espp::OneshotAdc::read_mv"],[5,4,1,"_CPPv4N4espp10OneshotAdc7read_mvERK9AdcConfig","espp::OneshotAdc::read_mv::config"],[5,3,1,"_CPPv4N4espp10OneshotAdc8read_rawERK9AdcConfig","espp::OneshotAdc::read_raw"],[5,4,1,"_CPPv4N4espp10OneshotAdc8read_rawERK9AdcConfig","espp::OneshotAdc::read_raw::config"],[5,3,1,"_CPPv4N4espp10OneshotAdcD0Ev","espp::OneshotAdc::~OneshotAdc"],[59,2,1,"_CPPv4N4espp3PidE","espp::Pid"],[59,2,1,"_CPPv4N4espp3Pid6ConfigE","espp::Pid::Config"],[59,1,1,"_CPPv4N4espp3Pid6Config14integrator_maxE","espp::Pid::Config::integrator_max"],[59,1,1,"_CPPv4N4espp3Pid6Config14integrator_minE","espp::Pid::Config::integrator_min"],[59,1,1,"_CPPv4N4espp3Pid6Config2kdE","espp::Pid::Config::kd"],[59,1,1,"_CPPv4N4espp3Pid6Config2kiE","espp::Pid::Config::ki"],[59,1,1,"_CPPv4N4espp3Pid6Config2kpE","espp::Pid::Config::kp"],[59,1,1,"_CPPv4N4espp3Pid6Config9log_levelE","espp::Pid::Config::log_level"],[59,1,1,"_CPPv4N4espp3Pid6Config10output_maxE","espp::Pid::Config::output_max"],[59,1,1,"_CPPv4N4espp3Pid6Config10output_minE","espp::Pid::Config::output_min"],[59,3,1,"_CPPv4N4espp3Pid3PidERK6Config","espp::Pid::Pid"],[59,4,1,"_CPPv4N4espp3Pid3PidERK6Config","espp::Pid::Pid::config"],[59,3,1,"_CPPv4N4espp3Pid12change_gainsERK6Configb","espp::Pid::change_gains"],[59,4,1,"_CPPv4N4espp3Pid12change_gainsERK6Configb","espp::Pid::change_gains::config"],[59,4,1,"_CPPv4N4espp3Pid12change_gainsERK6Configb","espp::Pid::change_gains::reset_state"],[59,3,1,"_CPPv4N4espp3Pid5clearEv","espp::Pid::clear"],[59,3,1,"_CPPv4NK4espp3Pid10get_configEv","espp::Pid::get_config"],[59,3,1,"_CPPv4NK4espp3Pid9get_errorEv","espp::Pid::get_error"],[59,3,1,"_CPPv4NK4espp3Pid14get_integratorEv","espp::Pid::get_integrator"],[59,3,1,"_CPPv4N4espp3PidclEf","espp::Pid::operator()"],[59,4,1,"_CPPv4N4espp3PidclEf","espp::Pid::operator()::error"],[59,3,1,"_CPPv4N4espp3Pid10set_configERK6Configb","espp::Pid::set_config"],[59,4,1,"_CPPv4N4espp3Pid10set_configERK6Configb","espp::Pid::set_config::config"],[59,4,1,"_CPPv4N4espp3Pid10set_configERK6Configb","espp::Pid::set_config::reset_state"],[59,3,1,"_CPPv4N4espp3Pid6updateEf","espp::Pid::update"],[59,4,1,"_CPPv4N4espp3Pid6updateEf","espp::Pid::update::error"],[49,2,1,"_CPPv4I0EN4espp11RangeMapperE","espp::RangeMapper"],[49,2,1,"_CPPv4N4espp11RangeMapper6ConfigE","espp::RangeMapper::Config"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config6centerE","espp::RangeMapper::Config::center"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config8deadbandE","espp::RangeMapper::Config::deadband"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config12invert_inputE","espp::RangeMapper::Config::invert_input"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config13invert_outputE","espp::RangeMapper::Config::invert_output"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config7maximumE","espp::RangeMapper::Config::maximum"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config7minimumE","espp::RangeMapper::Config::minimum"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config13output_centerE","espp::RangeMapper::Config::output_center"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config12output_rangeE","espp::RangeMapper::Config::output_range"],[49,3,1,"_CPPv4N4espp11RangeMapper11RangeMapperERK6Config","espp::RangeMapper::RangeMapper"],[49,4,1,"_CPPv4N4espp11RangeMapper11RangeMapperERK6Config","espp::RangeMapper::RangeMapper::config"],[49,5,1,"_CPPv4I0EN4espp11RangeMapperE","espp::RangeMapper::T"],[49,3,1,"_CPPv4N4espp11RangeMapper9configureERK6Config","espp::RangeMapper::configure"],[49,4,1,"_CPPv4N4espp11RangeMapper9configureERK6Config","espp::RangeMapper::configure::config"],[49,3,1,"_CPPv4NK4espp11RangeMapper17get_output_centerEv","espp::RangeMapper::get_output_center"],[49,3,1,"_CPPv4NK4espp11RangeMapper14get_output_maxEv","espp::RangeMapper::get_output_max"],[49,3,1,"_CPPv4NK4espp11RangeMapper14get_output_minEv","espp::RangeMapper::get_output_min"],[49,3,1,"_CPPv4NK4espp11RangeMapper16get_output_rangeEv","espp::RangeMapper::get_output_range"],[49,3,1,"_CPPv4N4espp11RangeMapper3mapERK1T","espp::RangeMapper::map"],[49,4,1,"_CPPv4N4espp11RangeMapper3mapERK1T","espp::RangeMapper::map::v"],[11,2,1,"_CPPv4N4espp3RgbE","espp::Rgb"],[11,3,1,"_CPPv4N4espp3Rgb3RgbERK3Hsv","espp::Rgb::Rgb"],[11,3,1,"_CPPv4N4espp3Rgb3RgbERK3Rgb","espp::Rgb::Rgb"],[11,3,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb"],[11,4,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb::b"],[11,4,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb::g"],[11,4,1,"_CPPv4N4espp3Rgb3RgbERK3Hsv","espp::Rgb::Rgb::hsv"],[11,4,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb::r"],[11,4,1,"_CPPv4N4espp3Rgb3RgbERK3Rgb","espp::Rgb::Rgb::rgb"],[11,1,1,"_CPPv4N4espp3Rgb1bE","espp::Rgb::b"],[11,1,1,"_CPPv4N4espp3Rgb1gE","espp::Rgb::g"],[11,3,1,"_CPPv4NK4espp3Rgb3hsvEv","espp::Rgb::hsv"],[11,3,1,"_CPPv4NK4espp3RgbplERK3Rgb","espp::Rgb::operator+"],[11,4,1,"_CPPv4NK4espp3RgbplERK3Rgb","espp::Rgb::operator+::rhs"],[11,3,1,"_CPPv4N4espp3RgbpLERK3Rgb","espp::Rgb::operator+="],[11,4,1,"_CPPv4N4espp3RgbpLERK3Rgb","espp::Rgb::operator+=::rhs"],[11,1,1,"_CPPv4N4espp3Rgb1rE","espp::Rgb::r"],[60,2,1,"_CPPv4N4espp3RmtE","espp::Rmt"],[60,2,1,"_CPPv4N4espp3Rmt6ConfigE","espp::Rmt::Config"],[60,1,1,"_CPPv4N4espp3Rmt6Config10block_sizeE","espp::Rmt::Config::block_size"],[60,1,1,"_CPPv4N4espp3Rmt6Config9clock_srcE","espp::Rmt::Config::clock_src"],[60,1,1,"_CPPv4N4espp3Rmt6Config11dma_enabledE","espp::Rmt::Config::dma_enabled"],[60,1,1,"_CPPv4N4espp3Rmt6Config8gpio_numE","espp::Rmt::Config::gpio_num"],[60,1,1,"_CPPv4N4espp3Rmt6Config9log_levelE","espp::Rmt::Config::log_level"],[60,1,1,"_CPPv4N4espp3Rmt6Config13resolution_hzE","espp::Rmt::Config::resolution_hz"],[60,1,1,"_CPPv4N4espp3Rmt6Config23transaction_queue_depthE","espp::Rmt::Config::transaction_queue_depth"],[60,3,1,"_CPPv4N4espp3Rmt3RmtERK6Config","espp::Rmt::Rmt"],[60,4,1,"_CPPv4N4espp3Rmt3RmtERK6Config","espp::Rmt::Rmt::config"],[60,3,1,"_CPPv4N4espp3Rmt8transmitEPK7uint8_t6size_t","espp::Rmt::transmit"],[60,4,1,"_CPPv4N4espp3Rmt8transmitEPK7uint8_t6size_t","espp::Rmt::transmit::data"],[60,4,1,"_CPPv4N4espp3Rmt8transmitEPK7uint8_t6size_t","espp::Rmt::transmit::length"],[60,3,1,"_CPPv4N4espp3RmtD0Ev","espp::Rmt::~Rmt"],[60,2,1,"_CPPv4N4espp10RmtEncoderE","espp::RmtEncoder"],[60,2,1,"_CPPv4N4espp10RmtEncoder6ConfigE","espp::RmtEncoder::Config"],[60,1,1,"_CPPv4N4espp10RmtEncoder6Config20bytes_encoder_configE","espp::RmtEncoder::Config::bytes_encoder_config"],[60,1,1,"_CPPv4N4espp10RmtEncoder6Config3delE","espp::RmtEncoder::Config::del"],[60,1,1,"_CPPv4N4espp10RmtEncoder6Config6encodeE","espp::RmtEncoder::Config::encode"],[60,1,1,"_CPPv4N4espp10RmtEncoder6Config5resetE","espp::RmtEncoder::Config::reset"],[60,3,1,"_CPPv4N4espp10RmtEncoder10RmtEncoderERK6Config","espp::RmtEncoder::RmtEncoder"],[60,4,1,"_CPPv4N4espp10RmtEncoder10RmtEncoderERK6Config","espp::RmtEncoder::RmtEncoder::config"],[60,8,1,"_CPPv4N4espp10RmtEncoder9delete_fnE","espp::RmtEncoder::delete_fn"],[60,8,1,"_CPPv4N4espp10RmtEncoder9encode_fnE","espp::RmtEncoder::encode_fn"],[60,3,1,"_CPPv4NK4espp10RmtEncoder6handleEv","espp::RmtEncoder::handle"],[60,8,1,"_CPPv4N4espp10RmtEncoder8reset_fnE","espp::RmtEncoder::reset_fn"],[60,3,1,"_CPPv4N4espp10RmtEncoderD0Ev","espp::RmtEncoder::~RmtEncoder"],[61,2,1,"_CPPv4N4espp10RtcpPacketE","espp::RtcpPacket"],[61,2,1,"_CPPv4N4espp13RtpJpegPacketE","espp::RtpJpegPacket"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::data"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::frag_type"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::frag_type"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::height"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::height"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::offset"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q0"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q1"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::scan_data"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::scan_data"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::type_specific"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::type_specific"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::width"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::width"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket8get_dataEv","espp::RtpJpegPacket::get_data"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket10get_heightEv","espp::RtpJpegPacket::get_height"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket13get_jpeg_dataEv","espp::RtpJpegPacket::get_jpeg_data"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket16get_mjpeg_headerEv","espp::RtpJpegPacket::get_mjpeg_header"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket16get_num_q_tablesEv","espp::RtpJpegPacket::get_num_q_tables"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket10get_offsetEv","espp::RtpJpegPacket::get_offset"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket10get_packetEv","espp::RtpJpegPacket::get_packet"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket11get_payloadEv","espp::RtpJpegPacket::get_payload"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket5get_qEv","espp::RtpJpegPacket::get_q"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket11get_q_tableEi","espp::RtpJpegPacket::get_q_table"],[61,4,1,"_CPPv4NK4espp13RtpJpegPacket11get_q_tableEi","espp::RtpJpegPacket::get_q_table::index"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket14get_rpt_headerEv","espp::RtpJpegPacket::get_rpt_header"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket19get_rtp_header_sizeEv","espp::RtpJpegPacket::get_rtp_header_size"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket17get_type_specificEv","espp::RtpJpegPacket::get_type_specific"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket11get_versionEv","espp::RtpJpegPacket::get_version"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket9get_widthEv","espp::RtpJpegPacket::get_width"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket12has_q_tablesEv","espp::RtpJpegPacket::has_q_tables"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket9serializeEv","espp::RtpJpegPacket::serialize"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket11set_payloadENSt11string_viewE","espp::RtpJpegPacket::set_payload"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket11set_payloadENSt11string_viewE","espp::RtpJpegPacket::set_payload::payload"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket11set_versionEi","espp::RtpJpegPacket::set_version"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket11set_versionEi","espp::RtpJpegPacket::set_version::version"],[61,2,1,"_CPPv4N4espp9RtpPacketE","espp::RtpPacket"],[61,3,1,"_CPPv4N4espp9RtpPacket9RtpPacketE6size_t","espp::RtpPacket::RtpPacket"],[61,3,1,"_CPPv4N4espp9RtpPacket9RtpPacketENSt11string_viewE","espp::RtpPacket::RtpPacket"],[61,3,1,"_CPPv4N4espp9RtpPacket9RtpPacketEv","espp::RtpPacket::RtpPacket"],[61,4,1,"_CPPv4N4espp9RtpPacket9RtpPacketENSt11string_viewE","espp::RtpPacket::RtpPacket::data"],[61,4,1,"_CPPv4N4espp9RtpPacket9RtpPacketE6size_t","espp::RtpPacket::RtpPacket::payload_size"],[61,3,1,"_CPPv4NK4espp9RtpPacket8get_dataEv","espp::RtpPacket::get_data"],[61,3,1,"_CPPv4N4espp9RtpPacket10get_packetEv","espp::RtpPacket::get_packet"],[61,3,1,"_CPPv4NK4espp9RtpPacket11get_payloadEv","espp::RtpPacket::get_payload"],[61,3,1,"_CPPv4NK4espp9RtpPacket14get_rpt_headerEv","espp::RtpPacket::get_rpt_header"],[61,3,1,"_CPPv4NK4espp9RtpPacket19get_rtp_header_sizeEv","espp::RtpPacket::get_rtp_header_size"],[61,3,1,"_CPPv4NK4espp9RtpPacket11get_versionEv","espp::RtpPacket::get_version"],[61,3,1,"_CPPv4N4espp9RtpPacket9serializeEv","espp::RtpPacket::serialize"],[61,3,1,"_CPPv4N4espp9RtpPacket11set_payloadENSt11string_viewE","espp::RtpPacket::set_payload"],[61,4,1,"_CPPv4N4espp9RtpPacket11set_payloadENSt11string_viewE","espp::RtpPacket::set_payload::payload"],[61,3,1,"_CPPv4N4espp9RtpPacket11set_versionEi","espp::RtpPacket::set_version"],[61,4,1,"_CPPv4N4espp9RtpPacket11set_versionEi","espp::RtpPacket::set_version::version"],[61,2,1,"_CPPv4N4espp10RtspClientE","espp::RtspClient"],[61,2,1,"_CPPv4N4espp10RtspClient6ConfigE","espp::RtspClient::Config"],[61,1,1,"_CPPv4N4espp10RtspClient6Config9log_levelE","espp::RtspClient::Config::log_level"],[61,1,1,"_CPPv4N4espp10RtspClient6Config13on_jpeg_frameE","espp::RtspClient::Config::on_jpeg_frame"],[61,1,1,"_CPPv4N4espp10RtspClient6Config4pathE","espp::RtspClient::Config::path"],[61,1,1,"_CPPv4N4espp10RtspClient6Config9rtsp_portE","espp::RtspClient::Config::rtsp_port"],[61,1,1,"_CPPv4N4espp10RtspClient6Config14server_addressE","espp::RtspClient::Config::server_address"],[61,3,1,"_CPPv4N4espp10RtspClient10RtspClientERK6Config","espp::RtspClient::RtspClient"],[61,4,1,"_CPPv4N4espp10RtspClient10RtspClientERK6Config","espp::RtspClient::RtspClient::config"],[61,3,1,"_CPPv4N4espp10RtspClient7connectERNSt10error_codeE","espp::RtspClient::connect"],[61,4,1,"_CPPv4N4espp10RtspClient7connectERNSt10error_codeE","espp::RtspClient::connect::ec"],[61,3,1,"_CPPv4N4espp10RtspClient8describeERNSt10error_codeE","espp::RtspClient::describe"],[61,4,1,"_CPPv4N4espp10RtspClient8describeERNSt10error_codeE","espp::RtspClient::describe::ec"],[61,3,1,"_CPPv4N4espp10RtspClient10disconnectERNSt10error_codeE","espp::RtspClient::disconnect"],[61,4,1,"_CPPv4N4espp10RtspClient10disconnectERNSt10error_codeE","espp::RtspClient::disconnect::ec"],[61,8,1,"_CPPv4N4espp10RtspClient21jpeg_frame_callback_tE","espp::RtspClient::jpeg_frame_callback_t"],[61,3,1,"_CPPv4N4espp10RtspClient5pauseERNSt10error_codeE","espp::RtspClient::pause"],[61,4,1,"_CPPv4N4espp10RtspClient5pauseERNSt10error_codeE","espp::RtspClient::pause::ec"],[61,3,1,"_CPPv4N4espp10RtspClient4playERNSt10error_codeE","espp::RtspClient::play"],[61,4,1,"_CPPv4N4espp10RtspClient4playERNSt10error_codeE","espp::RtspClient::play::ec"],[61,3,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request"],[61,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::ec"],[61,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::extra_headers"],[61,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::method"],[61,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::path"],[61,3,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup"],[61,3,1,"_CPPv4N4espp10RtspClient5setupERNSt10error_codeE","espp::RtspClient::setup"],[61,4,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup::ec"],[61,4,1,"_CPPv4N4espp10RtspClient5setupERNSt10error_codeE","espp::RtspClient::setup::ec"],[61,4,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup::rtcp_port"],[61,4,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup::rtp_port"],[61,3,1,"_CPPv4N4espp10RtspClient8teardownERNSt10error_codeE","espp::RtspClient::teardown"],[61,4,1,"_CPPv4N4espp10RtspClient8teardownERNSt10error_codeE","espp::RtspClient::teardown::ec"],[61,3,1,"_CPPv4N4espp10RtspClientD0Ev","espp::RtspClient::~RtspClient"],[61,2,1,"_CPPv4N4espp10RtspServerE","espp::RtspServer"],[61,2,1,"_CPPv4N4espp10RtspServer6ConfigE","espp::RtspServer::Config"],[61,1,1,"_CPPv4N4espp10RtspServer6Config9log_levelE","espp::RtspServer::Config::log_level"],[61,1,1,"_CPPv4N4espp10RtspServer6Config13max_data_sizeE","espp::RtspServer::Config::max_data_size"],[61,1,1,"_CPPv4N4espp10RtspServer6Config4pathE","espp::RtspServer::Config::path"],[61,1,1,"_CPPv4N4espp10RtspServer6Config4portE","espp::RtspServer::Config::port"],[61,1,1,"_CPPv4N4espp10RtspServer6Config14server_addressE","espp::RtspServer::Config::server_address"],[61,3,1,"_CPPv4N4espp10RtspServer10RtspServerERK6Config","espp::RtspServer::RtspServer"],[61,4,1,"_CPPv4N4espp10RtspServer10RtspServerERK6Config","espp::RtspServer::RtspServer::config"],[61,3,1,"_CPPv4N4espp10RtspServer10send_frameERK9JpegFrame","espp::RtspServer::send_frame"],[61,4,1,"_CPPv4N4espp10RtspServer10send_frameERK9JpegFrame","espp::RtspServer::send_frame::frame"],[61,3,1,"_CPPv4N4espp10RtspServer21set_session_log_levelEN6Logger9VerbosityE","espp::RtspServer::set_session_log_level"],[61,4,1,"_CPPv4N4espp10RtspServer21set_session_log_levelEN6Logger9VerbosityE","espp::RtspServer::set_session_log_level::log_level"],[61,3,1,"_CPPv4N4espp10RtspServer5startEv","espp::RtspServer::start"],[61,3,1,"_CPPv4N4espp10RtspServer4stopEv","espp::RtspServer::stop"],[61,3,1,"_CPPv4N4espp10RtspServerD0Ev","espp::RtspServer::~RtspServer"],[61,2,1,"_CPPv4N4espp11RtspSessionE","espp::RtspSession"],[61,2,1,"_CPPv4N4espp11RtspSession6ConfigE","espp::RtspSession::Config"],[61,1,1,"_CPPv4N4espp11RtspSession6Config9log_levelE","espp::RtspSession::Config::log_level"],[61,1,1,"_CPPv4N4espp11RtspSession6Config9rtsp_pathE","espp::RtspSession::Config::rtsp_path"],[61,1,1,"_CPPv4N4espp11RtspSession6Config14server_addressE","espp::RtspSession::Config::server_address"],[61,3,1,"_CPPv4N4espp11RtspSession11RtspSessionENSt10unique_ptrI9TcpSocketEERK6Config","espp::RtspSession::RtspSession"],[61,4,1,"_CPPv4N4espp11RtspSession11RtspSessionENSt10unique_ptrI9TcpSocketEERK6Config","espp::RtspSession::RtspSession::config"],[61,4,1,"_CPPv4N4espp11RtspSession11RtspSessionENSt10unique_ptrI9TcpSocketEERK6Config","espp::RtspSession::RtspSession::control_socket"],[61,3,1,"_CPPv4NK4espp11RtspSession14get_session_idEv","espp::RtspSession::get_session_id"],[61,3,1,"_CPPv4NK4espp11RtspSession9is_activeEv","espp::RtspSession::is_active"],[61,3,1,"_CPPv4NK4espp11RtspSession9is_closedEv","espp::RtspSession::is_closed"],[61,3,1,"_CPPv4NK4espp11RtspSession12is_connectedEv","espp::RtspSession::is_connected"],[61,3,1,"_CPPv4N4espp11RtspSession5pauseEv","espp::RtspSession::pause"],[61,3,1,"_CPPv4N4espp11RtspSession4playEv","espp::RtspSession::play"],[61,3,1,"_CPPv4N4espp11RtspSession16send_rtcp_packetERK10RtcpPacket","espp::RtspSession::send_rtcp_packet"],[61,4,1,"_CPPv4N4espp11RtspSession16send_rtcp_packetERK10RtcpPacket","espp::RtspSession::send_rtcp_packet::packet"],[61,3,1,"_CPPv4N4espp11RtspSession15send_rtp_packetERK9RtpPacket","espp::RtspSession::send_rtp_packet"],[61,4,1,"_CPPv4N4espp11RtspSession15send_rtp_packetERK9RtpPacket","espp::RtspSession::send_rtp_packet::packet"],[61,3,1,"_CPPv4N4espp11RtspSession8teardownEv","espp::RtspSession::teardown"],[53,2,1,"_CPPv4N4espp6SocketE","espp::Socket"],[53,2,1,"_CPPv4N4espp6Socket4InfoE","espp::Socket::Info"],[53,1,1,"_CPPv4N4espp6Socket4Info7addressE","espp::Socket::Info::address"],[53,3,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK11sockaddr_in","espp::Socket::Info::from_sockaddr"],[53,3,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK12sockaddr_in6","espp::Socket::Info::from_sockaddr"],[53,3,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK16sockaddr_storage","espp::Socket::Info::from_sockaddr"],[53,4,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK11sockaddr_in","espp::Socket::Info::from_sockaddr::source_address"],[53,4,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK12sockaddr_in6","espp::Socket::Info::from_sockaddr::source_address"],[53,4,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK16sockaddr_storage","espp::Socket::Info::from_sockaddr::source_address"],[53,3,1,"_CPPv4N4espp6Socket4Info9init_ipv4ERKNSt6stringE6size_t","espp::Socket::Info::init_ipv4"],[53,4,1,"_CPPv4N4espp6Socket4Info9init_ipv4ERKNSt6stringE6size_t","espp::Socket::Info::init_ipv4::addr"],[53,4,1,"_CPPv4N4espp6Socket4Info9init_ipv4ERKNSt6stringE6size_t","espp::Socket::Info::init_ipv4::prt"],[53,3,1,"_CPPv4N4espp6Socket4Info8ipv4_ptrEv","espp::Socket::Info::ipv4_ptr"],[53,3,1,"_CPPv4N4espp6Socket4Info8ipv6_ptrEv","espp::Socket::Info::ipv6_ptr"],[53,1,1,"_CPPv4N4espp6Socket4Info4portE","espp::Socket::Info::port"],[53,3,1,"_CPPv4N4espp6Socket4Info6updateEv","espp::Socket::Info::update"],[53,3,1,"_CPPv4N4espp6Socket6SocketE4TypeRKN6Logger6ConfigE","espp::Socket::Socket"],[53,3,1,"_CPPv4N4espp6Socket6SocketEiRKN6Logger6ConfigE","espp::Socket::Socket"],[53,4,1,"_CPPv4N4espp6Socket6SocketE4TypeRKN6Logger6ConfigE","espp::Socket::Socket::logger_config"],[53,4,1,"_CPPv4N4espp6Socket6SocketEiRKN6Logger6ConfigE","espp::Socket::Socket::logger_config"],[53,4,1,"_CPPv4N4espp6Socket6SocketEiRKN6Logger6ConfigE","espp::Socket::Socket::socket_fd"],[53,4,1,"_CPPv4N4espp6Socket6SocketE4TypeRKN6Logger6ConfigE","espp::Socket::Socket::type"],[53,3,1,"_CPPv4N4espp6Socket19add_multicast_groupERKNSt6stringE","espp::Socket::add_multicast_group"],[53,4,1,"_CPPv4N4espp6Socket19add_multicast_groupERKNSt6stringE","espp::Socket::add_multicast_group::multicast_group"],[53,3,1,"_CPPv4N4espp6Socket12enable_reuseEv","espp::Socket::enable_reuse"],[53,3,1,"_CPPv4N4espp6Socket13get_ipv4_infoEv","espp::Socket::get_ipv4_info"],[53,3,1,"_CPPv4N4espp6Socket8is_validEi","espp::Socket::is_valid"],[53,3,1,"_CPPv4NK4espp6Socket8is_validEv","espp::Socket::is_valid"],[53,4,1,"_CPPv4N4espp6Socket8is_validEi","espp::Socket::is_valid::socket_fd"],[53,3,1,"_CPPv4N4espp6Socket14make_multicastE7uint8_t7uint8_t","espp::Socket::make_multicast"],[53,4,1,"_CPPv4N4espp6Socket14make_multicastE7uint8_t7uint8_t","espp::Socket::make_multicast::loopback_enabled"],[53,4,1,"_CPPv4N4espp6Socket14make_multicastE7uint8_t7uint8_t","espp::Socket::make_multicast::time_to_live"],[53,8,1,"_CPPv4N4espp6Socket19receive_callback_fnE","espp::Socket::receive_callback_fn"],[53,8,1,"_CPPv4N4espp6Socket20response_callback_fnE","espp::Socket::response_callback_fn"],[53,3,1,"_CPPv4N4espp6Socket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::Socket::set_receive_timeout"],[53,4,1,"_CPPv4N4espp6Socket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::Socket::set_receive_timeout::timeout"],[53,3,1,"_CPPv4N4espp6SocketD0Ev","espp::Socket::~Socket"],[28,2,1,"_CPPv4I_6size_t0EN4espp9SosFilterE","espp::SosFilter"],[28,5,1,"_CPPv4I_6size_t0EN4espp9SosFilterE","espp::SosFilter::N"],[28,5,1,"_CPPv4I_6size_t0EN4espp9SosFilterE","espp::SosFilter::SectionImpl"],[28,3,1,"_CPPv4N4espp9SosFilter9SosFilterERKNSt5arrayI16TransferFunctionIXL3EEE1NEE","espp::SosFilter::SosFilter"],[28,4,1,"_CPPv4N4espp9SosFilter9SosFilterERKNSt5arrayI16TransferFunctionIXL3EEE1NEE","espp::SosFilter::SosFilter::config"],[28,3,1,"_CPPv4N4espp9SosFilterclEf","espp::SosFilter::operator()"],[28,4,1,"_CPPv4N4espp9SosFilterclEf","espp::SosFilter::operator()::input"],[28,3,1,"_CPPv4N4espp9SosFilter6updateEf","espp::SosFilter::update"],[28,4,1,"_CPPv4N4espp9SosFilter6updateEf","espp::SosFilter::update::input"],[58,2,1,"_CPPv4N4espp6St25dvE","espp::St25dv"],[58,2,1,"_CPPv4N4espp6St25dv6ConfigE","espp::St25dv::Config"],[58,1,1,"_CPPv4N4espp6St25dv6Config9log_levelE","espp::St25dv::Config::log_level"],[58,1,1,"_CPPv4N4espp6St25dv6Config4readE","espp::St25dv::Config::read"],[58,1,1,"_CPPv4N4espp6St25dv6Config5writeE","espp::St25dv::Config::write"],[58,1,1,"_CPPv4N4espp6St25dv12DATA_ADDRESSE","espp::St25dv::DATA_ADDRESS"],[58,2,1,"_CPPv4N4espp6St25dv7EH_CTRLE","espp::St25dv::EH_CTRL"],[58,2,1,"_CPPv4N4espp6St25dv3GPOE","espp::St25dv::GPO"],[58,2,1,"_CPPv4N4espp6St25dv6IT_STSE","espp::St25dv::IT_STS"],[58,2,1,"_CPPv4N4espp6St25dv6IT_STSE","espp::St25dv::IT_STS"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS13FIELD_FALLINGE","espp::St25dv::IT_STS::FIELD_FALLING"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS13FIELD_FALLINGE","espp::St25dv::IT_STS::FIELD_FALLING"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS12FIELD_RISINGE","espp::St25dv::IT_STS::FIELD_RISING"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS12FIELD_RISINGE","espp::St25dv::IT_STS::FIELD_RISING"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS11RF_ACTIVITYE","espp::St25dv::IT_STS::RF_ACTIVITY"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS11RF_ACTIVITYE","espp::St25dv::IT_STS::RF_ACTIVITY"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_GET_MSGE","espp::St25dv::IT_STS::RF_GET_MSG"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_GET_MSGE","espp::St25dv::IT_STS::RF_GET_MSG"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS12RF_INTTERUPTE","espp::St25dv::IT_STS::RF_INTTERUPT"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS12RF_INTTERUPTE","espp::St25dv::IT_STS::RF_INTTERUPT"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_PUT_MSGE","espp::St25dv::IT_STS::RF_PUT_MSG"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_PUT_MSGE","espp::St25dv::IT_STS::RF_PUT_MSG"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS7RF_USERE","espp::St25dv::IT_STS::RF_USER"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS7RF_USERE","espp::St25dv::IT_STS::RF_USER"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS8RF_WRITEE","espp::St25dv::IT_STS::RF_WRITE"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS8RF_WRITEE","espp::St25dv::IT_STS::RF_WRITE"],[58,2,1,"_CPPv4N4espp6St25dv7MB_CTRLE","espp::St25dv::MB_CTRL"],[58,1,1,"_CPPv4N4espp6St25dv19PhonyNameDueToError6lengthE","espp::St25dv::PhonyNameDueToError::length"],[58,1,1,"_CPPv4N4espp6St25dv19PhonyNameDueToError8length16E","espp::St25dv::PhonyNameDueToError::length16"],[58,1,1,"_CPPv4N4espp6St25dv19PhonyNameDueToError4typeE","espp::St25dv::PhonyNameDueToError::type"],[58,1,1,"_CPPv4N4espp6St25dv12SYST_ADDRESSE","espp::St25dv::SYST_ADDRESS"],[58,3,1,"_CPPv4N4espp6St25dv6St25dvERK6Config","espp::St25dv::St25dv"],[58,4,1,"_CPPv4N4espp6St25dv6St25dvERK6Config","espp::St25dv::St25dv::config"],[58,3,1,"_CPPv4N4espp6St25dv14get_ftm_lengthEv","espp::St25dv::get_ftm_length"],[58,3,1,"_CPPv4N4espp6St25dv20get_interrupt_statusEv","espp::St25dv::get_interrupt_status"],[58,3,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_t","espp::St25dv::read"],[58,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_t","espp::St25dv::read::data"],[58,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_t","espp::St25dv::read::length"],[58,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_t","espp::St25dv::read::offset"],[58,8,1,"_CPPv4N4espp6St25dv7read_fnE","espp::St25dv::read_fn"],[58,3,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_t","espp::St25dv::receive"],[58,4,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_t","espp::St25dv::receive::data"],[58,4,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_t","espp::St25dv::receive::length"],[58,3,1,"_CPPv4N4espp6St25dv10set_recordER4Ndef","espp::St25dv::set_record"],[58,4,1,"_CPPv4N4espp6St25dv10set_recordER4Ndef","espp::St25dv::set_record::record"],[58,3,1,"_CPPv4N4espp6St25dv24start_fast_transfer_modeEv","espp::St25dv::start_fast_transfer_mode"],[58,3,1,"_CPPv4N4espp6St25dv23stop_fast_transfer_modeEv","espp::St25dv::stop_fast_transfer_mode"],[58,3,1,"_CPPv4N4espp6St25dv8transferEP7uint8_t7uint8_t","espp::St25dv::transfer"],[58,4,1,"_CPPv4N4espp6St25dv8transferEP7uint8_t7uint8_t","espp::St25dv::transfer::data"],[58,4,1,"_CPPv4N4espp6St25dv8transferEP7uint8_t7uint8_t","espp::St25dv::transfer::length"],[58,3,1,"_CPPv4N4espp6St25dv5writeENSt11string_viewE","espp::St25dv::write"],[58,4,1,"_CPPv4N4espp6St25dv5writeENSt11string_viewE","espp::St25dv::write::payload"],[58,8,1,"_CPPv4N4espp6St25dv8write_fnE","espp::St25dv::write_fn"],[15,2,1,"_CPPv4N4espp6St7789E","espp::St7789"],[15,3,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear"],[15,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::color"],[15,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::height"],[15,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::width"],[15,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::x"],[15,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::y"],[15,3,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill"],[15,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::area"],[15,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::color_map"],[15,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::drv"],[15,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::flags"],[15,3,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush"],[15,4,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush::area"],[15,4,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush::color_map"],[15,4,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush::drv"],[15,3,1,"_CPPv4N4espp6St778910get_offsetERiRi","espp::St7789::get_offset"],[15,4,1,"_CPPv4N4espp6St778910get_offsetERiRi","espp::St7789::get_offset::x"],[15,4,1,"_CPPv4N4espp6St778910get_offsetERiRi","espp::St7789::get_offset::y"],[15,3,1,"_CPPv4N4espp6St778910initializeERKN15display_drivers6ConfigE","espp::St7789::initialize"],[15,4,1,"_CPPv4N4espp6St778910initializeERKN15display_drivers6ConfigE","espp::St7789::initialize::config"],[15,3,1,"_CPPv4N4espp6St778912send_commandE7uint8_t","espp::St7789::send_command"],[15,4,1,"_CPPv4N4espp6St778912send_commandE7uint8_t","espp::St7789::send_command::command"],[15,3,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data"],[15,4,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data::data"],[15,4,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data::flags"],[15,4,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data::length"],[15,3,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area"],[15,3,1,"_CPPv4N4espp6St778916set_drawing_areaEPK9lv_area_t","espp::St7789::set_drawing_area"],[15,4,1,"_CPPv4N4espp6St778916set_drawing_areaEPK9lv_area_t","espp::St7789::set_drawing_area::area"],[15,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::xe"],[15,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::xs"],[15,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::ye"],[15,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::ys"],[15,3,1,"_CPPv4N4espp6St778910set_offsetEii","espp::St7789::set_offset"],[15,4,1,"_CPPv4N4espp6St778910set_offsetEii","espp::St7789::set_offset::x"],[15,4,1,"_CPPv4N4espp6St778910set_offsetEii","espp::St7789::set_offset::y"],[64,2,1,"_CPPv4N4espp4TaskE","espp::Task"],[64,2,1,"_CPPv4N4espp4Task6ConfigE","espp::Task::Config"],[64,1,1,"_CPPv4N4espp4Task6Config8callbackE","espp::Task::Config::callback"],[64,1,1,"_CPPv4N4espp4Task6Config7core_idE","espp::Task::Config::core_id"],[64,1,1,"_CPPv4N4espp4Task6Config9log_levelE","espp::Task::Config::log_level"],[64,1,1,"_CPPv4N4espp4Task6Config4nameE","espp::Task::Config::name"],[64,1,1,"_CPPv4N4espp4Task6Config8priorityE","espp::Task::Config::priority"],[64,1,1,"_CPPv4N4espp4Task6Config16stack_size_bytesE","espp::Task::Config::stack_size_bytes"],[64,8,1,"_CPPv4N4espp4Task11callback_fnE","espp::Task::callback_fn"],[64,3,1,"_CPPv4N4espp4Task10is_startedEv","espp::Task::is_started"],[64,3,1,"_CPPv4N4espp4Task11make_uniqueERK6Config","espp::Task::make_unique"],[64,4,1,"_CPPv4N4espp4Task11make_uniqueERK6Config","espp::Task::make_unique::config"],[64,3,1,"_CPPv4N4espp4Task5startEv","espp::Task::start"],[64,3,1,"_CPPv4N4espp4Task4stopEv","espp::Task::stop"],[64,3,1,"_CPPv4N4espp4TaskD0Ev","espp::Task::~Task"],[51,2,1,"_CPPv4N4espp11TaskMonitorE","espp::TaskMonitor"],[51,2,1,"_CPPv4N4espp11TaskMonitor6ConfigE","espp::TaskMonitor::Config"],[51,1,1,"_CPPv4N4espp11TaskMonitor6Config6periodE","espp::TaskMonitor::Config::period"],[51,1,1,"_CPPv4N4espp11TaskMonitor6Config21task_stack_size_bytesE","espp::TaskMonitor::Config::task_stack_size_bytes"],[51,3,1,"_CPPv4N4espp11TaskMonitor15get_latest_infoEv","espp::TaskMonitor::get_latest_info"],[54,2,1,"_CPPv4N4espp9TcpSocketE","espp::TcpSocket"],[54,2,1,"_CPPv4N4espp9TcpSocket6ConfigE","espp::TcpSocket::Config"],[54,1,1,"_CPPv4N4espp9TcpSocket6Config9log_levelE","espp::TcpSocket::Config::log_level"],[54,2,1,"_CPPv4N4espp9TcpSocket13ConnectConfigE","espp::TcpSocket::ConnectConfig"],[54,1,1,"_CPPv4N4espp9TcpSocket13ConnectConfig10ip_addressE","espp::TcpSocket::ConnectConfig::ip_address"],[54,1,1,"_CPPv4N4espp9TcpSocket13ConnectConfig4portE","espp::TcpSocket::ConnectConfig::port"],[54,3,1,"_CPPv4N4espp9TcpSocket9TcpSocketERK6Config","espp::TcpSocket::TcpSocket"],[54,4,1,"_CPPv4N4espp9TcpSocket9TcpSocketERK6Config","espp::TcpSocket::TcpSocket::config"],[54,3,1,"_CPPv4N4espp9TcpSocket6acceptEv","espp::TcpSocket::accept"],[54,3,1,"_CPPv4N4espp9TcpSocket19add_multicast_groupERKNSt6stringE","espp::TcpSocket::add_multicast_group"],[54,4,1,"_CPPv4N4espp9TcpSocket19add_multicast_groupERKNSt6stringE","espp::TcpSocket::add_multicast_group::multicast_group"],[54,3,1,"_CPPv4N4espp9TcpSocket4bindEi","espp::TcpSocket::bind"],[54,4,1,"_CPPv4N4espp9TcpSocket4bindEi","espp::TcpSocket::bind::port"],[54,3,1,"_CPPv4N4espp9TcpSocket5closeEv","espp::TcpSocket::close"],[54,3,1,"_CPPv4N4espp9TcpSocket7connectERK13ConnectConfig","espp::TcpSocket::connect"],[54,4,1,"_CPPv4N4espp9TcpSocket7connectERK13ConnectConfig","espp::TcpSocket::connect::connect_config"],[54,3,1,"_CPPv4N4espp9TcpSocket12enable_reuseEv","espp::TcpSocket::enable_reuse"],[54,3,1,"_CPPv4N4espp9TcpSocket13get_ipv4_infoEv","espp::TcpSocket::get_ipv4_info"],[54,3,1,"_CPPv4NK4espp9TcpSocket15get_remote_infoEv","espp::TcpSocket::get_remote_info"],[54,3,1,"_CPPv4NK4espp9TcpSocket12is_connectedEv","espp::TcpSocket::is_connected"],[54,3,1,"_CPPv4N4espp9TcpSocket8is_validEi","espp::TcpSocket::is_valid"],[54,3,1,"_CPPv4NK4espp9TcpSocket8is_validEv","espp::TcpSocket::is_valid"],[54,4,1,"_CPPv4N4espp9TcpSocket8is_validEi","espp::TcpSocket::is_valid::socket_fd"],[54,3,1,"_CPPv4N4espp9TcpSocket6listenEi","espp::TcpSocket::listen"],[54,4,1,"_CPPv4N4espp9TcpSocket6listenEi","espp::TcpSocket::listen::max_pending_connections"],[54,3,1,"_CPPv4N4espp9TcpSocket14make_multicastE7uint8_t7uint8_t","espp::TcpSocket::make_multicast"],[54,4,1,"_CPPv4N4espp9TcpSocket14make_multicastE7uint8_t7uint8_t","espp::TcpSocket::make_multicast::loopback_enabled"],[54,4,1,"_CPPv4N4espp9TcpSocket14make_multicastE7uint8_t7uint8_t","espp::TcpSocket::make_multicast::time_to_live"],[54,3,1,"_CPPv4N4espp9TcpSocket7receiveEP7uint8_t6size_t","espp::TcpSocket::receive"],[54,3,1,"_CPPv4N4espp9TcpSocket7receiveERNSt6vectorI7uint8_tEE6size_t","espp::TcpSocket::receive"],[54,4,1,"_CPPv4N4espp9TcpSocket7receiveEP7uint8_t6size_t","espp::TcpSocket::receive::data"],[54,4,1,"_CPPv4N4espp9TcpSocket7receiveERNSt6vectorI7uint8_tEE6size_t","espp::TcpSocket::receive::data"],[54,4,1,"_CPPv4N4espp9TcpSocket7receiveEP7uint8_t6size_t","espp::TcpSocket::receive::max_num_bytes"],[54,4,1,"_CPPv4N4espp9TcpSocket7receiveERNSt6vectorI7uint8_tEE6size_t","espp::TcpSocket::receive::max_num_bytes"],[54,8,1,"_CPPv4N4espp9TcpSocket19receive_callback_fnE","espp::TcpSocket::receive_callback_fn"],[54,3,1,"_CPPv4N4espp9TcpSocket6reinitEv","espp::TcpSocket::reinit"],[54,8,1,"_CPPv4N4espp9TcpSocket20response_callback_fnE","espp::TcpSocket::response_callback_fn"],[54,3,1,"_CPPv4N4espp9TcpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::TcpSocket::set_receive_timeout"],[54,4,1,"_CPPv4N4espp9TcpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::TcpSocket::set_receive_timeout::timeout"],[54,3,1,"_CPPv4N4espp9TcpSocket8transmitENSt11string_viewERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit"],[54,3,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorI7uint8_tEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit"],[54,3,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorIcEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit"],[54,4,1,"_CPPv4N4espp9TcpSocket8transmitENSt11string_viewERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::data"],[54,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorI7uint8_tEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::data"],[54,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorIcEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::data"],[54,4,1,"_CPPv4N4espp9TcpSocket8transmitENSt11string_viewERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::transmit_config"],[54,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorI7uint8_tEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::transmit_config"],[54,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorIcEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::transmit_config"],[54,3,1,"_CPPv4N4espp9TcpSocketD0Ev","espp::TcpSocket::~TcpSocket"],[65,2,1,"_CPPv4N4espp10ThermistorE","espp::Thermistor"],[65,2,1,"_CPPv4N4espp10Thermistor6ConfigE","espp::Thermistor::Config"],[65,1,1,"_CPPv4N4espp10Thermistor6Config4betaE","espp::Thermistor::Config::beta"],[65,1,1,"_CPPv4N4espp10Thermistor6Config14divider_configE","espp::Thermistor::Config::divider_config"],[65,1,1,"_CPPv4N4espp10Thermistor6Config21fixed_resistance_ohmsE","espp::Thermistor::Config::fixed_resistance_ohms"],[65,1,1,"_CPPv4N4espp10Thermistor6Config9log_levelE","espp::Thermistor::Config::log_level"],[65,1,1,"_CPPv4N4espp10Thermistor6Config23nominal_resistance_ohmsE","espp::Thermistor::Config::nominal_resistance_ohms"],[65,1,1,"_CPPv4N4espp10Thermistor6Config7read_mvE","espp::Thermistor::Config::read_mv"],[65,1,1,"_CPPv4N4espp10Thermistor6Config9supply_mvE","espp::Thermistor::Config::supply_mv"],[65,6,1,"_CPPv4N4espp10Thermistor21ResistorDividerConfigE","espp::Thermistor::ResistorDividerConfig"],[65,7,1,"_CPPv4N4espp10Thermistor21ResistorDividerConfig5LOWERE","espp::Thermistor::ResistorDividerConfig::LOWER"],[65,7,1,"_CPPv4N4espp10Thermistor21ResistorDividerConfig5UPPERE","espp::Thermistor::ResistorDividerConfig::UPPER"],[65,3,1,"_CPPv4N4espp10Thermistor10ThermistorERK6Config","espp::Thermistor::Thermistor"],[65,4,1,"_CPPv4N4espp10Thermistor10ThermistorERK6Config","espp::Thermistor::Thermistor::config"],[65,3,1,"_CPPv4N4espp10Thermistor11get_celsiusEv","espp::Thermistor::get_celsius"],[65,3,1,"_CPPv4N4espp10Thermistor14get_fahrenheitEv","espp::Thermistor::get_fahrenheit"],[65,3,1,"_CPPv4N4espp10Thermistor10get_kelvinEv","espp::Thermistor::get_kelvin"],[65,3,1,"_CPPv4N4espp10Thermistor14get_resistanceEv","espp::Thermistor::get_resistance"],[65,8,1,"_CPPv4N4espp10Thermistor10read_mv_fnE","espp::Thermistor::read_mv_fn"],[37,2,1,"_CPPv4N4espp13TouchpadInputE","espp::TouchpadInput"],[37,2,1,"_CPPv4N4espp13TouchpadInput6ConfigE","espp::TouchpadInput::Config"],[37,1,1,"_CPPv4N4espp13TouchpadInput6Config8invert_xE","espp::TouchpadInput::Config::invert_x"],[37,1,1,"_CPPv4N4espp13TouchpadInput6Config8invert_yE","espp::TouchpadInput::Config::invert_y"],[37,1,1,"_CPPv4N4espp13TouchpadInput6Config9log_levelE","espp::TouchpadInput::Config::log_level"],[37,1,1,"_CPPv4N4espp13TouchpadInput6Config7swap_xyE","espp::TouchpadInput::Config::swap_xy"],[37,1,1,"_CPPv4N4espp13TouchpadInput6Config13touchpad_readE","espp::TouchpadInput::Config::touchpad_read"],[37,3,1,"_CPPv4N4espp13TouchpadInput13TouchpadInputERK6Config","espp::TouchpadInput::TouchpadInput"],[37,4,1,"_CPPv4N4espp13TouchpadInput13TouchpadInputERK6Config","espp::TouchpadInput::TouchpadInput::config"],[37,8,1,"_CPPv4N4espp13TouchpadInput16touchpad_read_fnE","espp::TouchpadInput::touchpad_read_fn"],[37,3,1,"_CPPv4N4espp13TouchpadInputD0Ev","espp::TouchpadInput::~TouchpadInput"],[55,2,1,"_CPPv4N4espp9UdpSocketE","espp::UdpSocket"],[55,2,1,"_CPPv4N4espp9UdpSocket6ConfigE","espp::UdpSocket::Config"],[55,1,1,"_CPPv4N4espp9UdpSocket6Config9log_levelE","espp::UdpSocket::Config::log_level"],[55,2,1,"_CPPv4N4espp9UdpSocket13ReceiveConfigE","espp::UdpSocket::ReceiveConfig"],[55,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig11buffer_sizeE","espp::UdpSocket::ReceiveConfig::buffer_size"],[55,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig21is_multicast_endpointE","espp::UdpSocket::ReceiveConfig::is_multicast_endpoint"],[55,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig15multicast_groupE","espp::UdpSocket::ReceiveConfig::multicast_group"],[55,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig19on_receive_callbackE","espp::UdpSocket::ReceiveConfig::on_receive_callback"],[55,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig4portE","espp::UdpSocket::ReceiveConfig::port"],[55,2,1,"_CPPv4N4espp9UdpSocket10SendConfigE","espp::UdpSocket::SendConfig"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig10ip_addressE","espp::UdpSocket::SendConfig::ip_address"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig21is_multicast_endpointE","espp::UdpSocket::SendConfig::is_multicast_endpoint"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig20on_response_callbackE","espp::UdpSocket::SendConfig::on_response_callback"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig4portE","espp::UdpSocket::SendConfig::port"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig13response_sizeE","espp::UdpSocket::SendConfig::response_size"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig16response_timeoutE","espp::UdpSocket::SendConfig::response_timeout"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig17wait_for_responseE","espp::UdpSocket::SendConfig::wait_for_response"],[55,3,1,"_CPPv4N4espp9UdpSocket9UdpSocketERK6Config","espp::UdpSocket::UdpSocket"],[55,4,1,"_CPPv4N4espp9UdpSocket9UdpSocketERK6Config","espp::UdpSocket::UdpSocket::config"],[55,3,1,"_CPPv4N4espp9UdpSocket19add_multicast_groupERKNSt6stringE","espp::UdpSocket::add_multicast_group"],[55,4,1,"_CPPv4N4espp9UdpSocket19add_multicast_groupERKNSt6stringE","espp::UdpSocket::add_multicast_group::multicast_group"],[55,3,1,"_CPPv4N4espp9UdpSocket12enable_reuseEv","espp::UdpSocket::enable_reuse"],[55,3,1,"_CPPv4N4espp9UdpSocket13get_ipv4_infoEv","espp::UdpSocket::get_ipv4_info"],[55,3,1,"_CPPv4N4espp9UdpSocket8is_validEi","espp::UdpSocket::is_valid"],[55,3,1,"_CPPv4NK4espp9UdpSocket8is_validEv","espp::UdpSocket::is_valid"],[55,4,1,"_CPPv4N4espp9UdpSocket8is_validEi","espp::UdpSocket::is_valid::socket_fd"],[55,3,1,"_CPPv4N4espp9UdpSocket14make_multicastE7uint8_t7uint8_t","espp::UdpSocket::make_multicast"],[55,4,1,"_CPPv4N4espp9UdpSocket14make_multicastE7uint8_t7uint8_t","espp::UdpSocket::make_multicast::loopback_enabled"],[55,4,1,"_CPPv4N4espp9UdpSocket14make_multicastE7uint8_t7uint8_t","espp::UdpSocket::make_multicast::time_to_live"],[55,3,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive"],[55,4,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive::data"],[55,4,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive::max_num_bytes"],[55,4,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive::remote_info"],[55,8,1,"_CPPv4N4espp9UdpSocket19receive_callback_fnE","espp::UdpSocket::receive_callback_fn"],[55,8,1,"_CPPv4N4espp9UdpSocket20response_callback_fnE","espp::UdpSocket::response_callback_fn"],[55,3,1,"_CPPv4N4espp9UdpSocket4sendENSt11string_viewERK10SendConfig","espp::UdpSocket::send"],[55,3,1,"_CPPv4N4espp9UdpSocket4sendERKNSt6vectorI7uint8_tEERK10SendConfig","espp::UdpSocket::send"],[55,4,1,"_CPPv4N4espp9UdpSocket4sendENSt11string_viewERK10SendConfig","espp::UdpSocket::send::data"],[55,4,1,"_CPPv4N4espp9UdpSocket4sendERKNSt6vectorI7uint8_tEERK10SendConfig","espp::UdpSocket::send::data"],[55,4,1,"_CPPv4N4espp9UdpSocket4sendENSt11string_viewERK10SendConfig","espp::UdpSocket::send::send_config"],[55,4,1,"_CPPv4N4espp9UdpSocket4sendERKNSt6vectorI7uint8_tEERK10SendConfig","espp::UdpSocket::send::send_config"],[55,3,1,"_CPPv4N4espp9UdpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::UdpSocket::set_receive_timeout"],[55,4,1,"_CPPv4N4espp9UdpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::UdpSocket::set_receive_timeout::timeout"],[55,3,1,"_CPPv4N4espp9UdpSocket15start_receivingERN4Task6ConfigERK13ReceiveConfig","espp::UdpSocket::start_receiving"],[55,4,1,"_CPPv4N4espp9UdpSocket15start_receivingERN4Task6ConfigERK13ReceiveConfig","espp::UdpSocket::start_receiving::receive_config"],[55,4,1,"_CPPv4N4espp9UdpSocket15start_receivingERN4Task6ConfigERK13ReceiveConfig","espp::UdpSocket::start_receiving::task_config"],[55,3,1,"_CPPv4N4espp9UdpSocketD0Ev","espp::UdpSocket::~UdpSocket"],[50,2,1,"_CPPv4I0EN4espp8Vector2dE","espp::Vector2d"],[50,5,1,"_CPPv4I0EN4espp8Vector2dE","espp::Vector2d::T"],[50,3,1,"_CPPv4N4espp8Vector2d8Vector2dE1T1T","espp::Vector2d::Vector2d"],[50,3,1,"_CPPv4N4espp8Vector2d8Vector2dERK8Vector2d","espp::Vector2d::Vector2d"],[50,4,1,"_CPPv4N4espp8Vector2d8Vector2dERK8Vector2d","espp::Vector2d::Vector2d::other"],[50,4,1,"_CPPv4N4espp8Vector2d8Vector2dE1T1T","espp::Vector2d::Vector2d::x"],[50,4,1,"_CPPv4N4espp8Vector2d8Vector2dE1T1T","espp::Vector2d::Vector2d::y"],[50,3,1,"_CPPv4NK4espp8Vector2d3dotERK8Vector2d","espp::Vector2d::dot"],[50,4,1,"_CPPv4NK4espp8Vector2d3dotERK8Vector2d","espp::Vector2d::dot::other"],[50,3,1,"_CPPv4NK4espp8Vector2d9magnitudeEv","espp::Vector2d::magnitude"],[50,3,1,"_CPPv4NK4espp8Vector2d17magnitude_squaredEv","espp::Vector2d::magnitude_squared"],[50,3,1,"_CPPv4NK4espp8Vector2d10normalizedEv","espp::Vector2d::normalized"],[50,3,1,"_CPPv4NK4espp8Vector2dmlERK1T","espp::Vector2d::operator*"],[50,4,1,"_CPPv4NK4espp8Vector2dmlERK1T","espp::Vector2d::operator*::v"],[50,3,1,"_CPPv4N4espp8Vector2dmLERK1T","espp::Vector2d::operator*="],[50,4,1,"_CPPv4N4espp8Vector2dmLERK1T","espp::Vector2d::operator*=::v"],[50,3,1,"_CPPv4NK4espp8Vector2dplERK8Vector2d","espp::Vector2d::operator+"],[50,4,1,"_CPPv4NK4espp8Vector2dplERK8Vector2d","espp::Vector2d::operator+::rhs"],[50,3,1,"_CPPv4N4espp8Vector2dpLERK8Vector2d","espp::Vector2d::operator+="],[50,4,1,"_CPPv4N4espp8Vector2dpLERK8Vector2d","espp::Vector2d::operator+=::rhs"],[50,3,1,"_CPPv4NK4espp8Vector2dmiERK8Vector2d","espp::Vector2d::operator-"],[50,3,1,"_CPPv4NK4espp8Vector2dmiEv","espp::Vector2d::operator-"],[50,4,1,"_CPPv4NK4espp8Vector2dmiERK8Vector2d","espp::Vector2d::operator-::rhs"],[50,3,1,"_CPPv4N4espp8Vector2dmIERK8Vector2d","espp::Vector2d::operator-="],[50,4,1,"_CPPv4N4espp8Vector2dmIERK8Vector2d","espp::Vector2d::operator-=::rhs"],[50,3,1,"_CPPv4NK4espp8Vector2ddvERK1T","espp::Vector2d::operator/"],[50,3,1,"_CPPv4NK4espp8Vector2ddvERK8Vector2d","espp::Vector2d::operator/"],[50,4,1,"_CPPv4NK4espp8Vector2ddvERK1T","espp::Vector2d::operator/::v"],[50,4,1,"_CPPv4NK4espp8Vector2ddvERK8Vector2d","espp::Vector2d::operator/::v"],[50,3,1,"_CPPv4N4espp8Vector2ddVERK1T","espp::Vector2d::operator/="],[50,3,1,"_CPPv4N4espp8Vector2ddVERK8Vector2d","espp::Vector2d::operator/="],[50,4,1,"_CPPv4N4espp8Vector2ddVERK1T","espp::Vector2d::operator/=::v"],[50,4,1,"_CPPv4N4espp8Vector2ddVERK8Vector2d","espp::Vector2d::operator/=::v"],[50,3,1,"_CPPv4N4espp8Vector2daSERK8Vector2d","espp::Vector2d::operator="],[50,4,1,"_CPPv4N4espp8Vector2daSERK8Vector2d","espp::Vector2d::operator=::other"],[50,3,1,"_CPPv4N4espp8Vector2dixEi","espp::Vector2d::operator[]"],[50,4,1,"_CPPv4N4espp8Vector2dixEi","espp::Vector2d::operator[]::index"],[50,3,1,"_CPPv4I0_PNSt9enable_ifINSt17is_floating_pointI1UE5valueEE4typeEENK4espp8Vector2d7rotatedE8Vector2d1T","espp::Vector2d::rotated"],[50,5,1,"_CPPv4I0_PNSt9enable_ifINSt17is_floating_pointI1UE5valueEE4typeEENK4espp8Vector2d7rotatedE8Vector2d1T","espp::Vector2d::rotated::U"],[50,4,1,"_CPPv4I0_PNSt9enable_ifINSt17is_floating_pointI1UE5valueEE4typeEENK4espp8Vector2d7rotatedE8Vector2d1T","espp::Vector2d::rotated::radians"],[50,3,1,"_CPPv4N4espp8Vector2d1xE1T","espp::Vector2d::x"],[50,3,1,"_CPPv4NK4espp8Vector2d1xEv","espp::Vector2d::x"],[50,4,1,"_CPPv4N4espp8Vector2d1xE1T","espp::Vector2d::x::v"],[50,3,1,"_CPPv4N4espp8Vector2d1yE1T","espp::Vector2d::y"],[50,3,1,"_CPPv4NK4espp8Vector2d1yEv","espp::Vector2d::y"],[50,4,1,"_CPPv4N4espp8Vector2d1yE1T","espp::Vector2d::y::v"],[67,2,1,"_CPPv4N4espp6WifiApE","espp::WifiAp"],[67,2,1,"_CPPv4N4espp6WifiAp6ConfigE","espp::WifiAp::Config"],[67,1,1,"_CPPv4N4espp6WifiAp6Config7channelE","espp::WifiAp::Config::channel"],[67,1,1,"_CPPv4N4espp6WifiAp6Config9log_levelE","espp::WifiAp::Config::log_level"],[67,1,1,"_CPPv4N4espp6WifiAp6Config22max_number_of_stationsE","espp::WifiAp::Config::max_number_of_stations"],[67,1,1,"_CPPv4N4espp6WifiAp6Config8passwordE","espp::WifiAp::Config::password"],[67,1,1,"_CPPv4N4espp6WifiAp6Config4ssidE","espp::WifiAp::Config::ssid"],[67,3,1,"_CPPv4N4espp6WifiAp6WifiApERK6Config","espp::WifiAp::WifiAp"],[67,4,1,"_CPPv4N4espp6WifiAp6WifiApERK6Config","espp::WifiAp::WifiAp::config"],[68,2,1,"_CPPv4N4espp7WifiStaE","espp::WifiSta"],[68,2,1,"_CPPv4N4espp7WifiSta6ConfigE","espp::WifiSta::Config"],[68,1,1,"_CPPv4N4espp7WifiSta6Config6ap_macE","espp::WifiSta::Config::ap_mac"],[68,1,1,"_CPPv4N4espp7WifiSta6Config7channelE","espp::WifiSta::Config::channel"],[68,1,1,"_CPPv4N4espp7WifiSta6Config9log_levelE","espp::WifiSta::Config::log_level"],[68,1,1,"_CPPv4N4espp7WifiSta6Config19num_connect_retriesE","espp::WifiSta::Config::num_connect_retries"],[68,1,1,"_CPPv4N4espp7WifiSta6Config12on_connectedE","espp::WifiSta::Config::on_connected"],[68,1,1,"_CPPv4N4espp7WifiSta6Config15on_disconnectedE","espp::WifiSta::Config::on_disconnected"],[68,1,1,"_CPPv4N4espp7WifiSta6Config9on_got_ipE","espp::WifiSta::Config::on_got_ip"],[68,1,1,"_CPPv4N4espp7WifiSta6Config8passwordE","espp::WifiSta::Config::password"],[68,1,1,"_CPPv4N4espp7WifiSta6Config10set_ap_macE","espp::WifiSta::Config::set_ap_mac"],[68,1,1,"_CPPv4N4espp7WifiSta6Config4ssidE","espp::WifiSta::Config::ssid"],[68,3,1,"_CPPv4N4espp7WifiSta7WifiStaERK6Config","espp::WifiSta::WifiSta"],[68,4,1,"_CPPv4N4espp7WifiSta7WifiStaERK6Config","espp::WifiSta::WifiSta::config"],[68,8,1,"_CPPv4N4espp7WifiSta16connect_callbackE","espp::WifiSta::connect_callback"],[68,8,1,"_CPPv4N4espp7WifiSta19disconnect_callbackE","espp::WifiSta::disconnect_callback"],[68,8,1,"_CPPv4N4espp7WifiSta11ip_callbackE","espp::WifiSta::ip_callback"],[68,3,1,"_CPPv4N4espp7WifiSta12is_connectedEv","espp::WifiSta::is_connected"],[68,3,1,"_CPPv4N4espp7WifiStaD0Ev","espp::WifiSta::~WifiSta"],[13,2,1,"_CPPv4N4espp21__csv_documentation__E","espp::__csv_documentation__"],[62,2,1,"_CPPv4N4espp31__serialization_documentation__E","espp::__serialization_documentation__"],[63,2,1,"_CPPv4N4espp31__state_machine_documentation__E","espp::__state_machine_documentation__"],[63,2,1,"_CPPv4N4espp13state_machine16DeepHistoryStateE","espp::state_machine::DeepHistoryState"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState5entryEv","espp::state_machine::DeepHistoryState::entry"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState4exitEv","espp::state_machine::DeepHistoryState::exit"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState12exitChildrenEv","espp::state_machine::DeepHistoryState::exitChildren"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14getActiveChildEv","espp::state_machine::DeepHistoryState::getActiveChild"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState13getActiveLeafEv","espp::state_machine::DeepHistoryState::getActiveLeaf"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState10getInitialEv","espp::state_machine::DeepHistoryState::getInitial"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14getParentStateEv","espp::state_machine::DeepHistoryState::getParentState"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState11handleEventEP9EventBase","espp::state_machine::DeepHistoryState::handleEvent"],[63,4,1,"_CPPv4N4espp13state_machine16DeepHistoryState11handleEventEP9EventBase","espp::state_machine::DeepHistoryState::handleEvent::event"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState10initializeEv","espp::state_machine::DeepHistoryState::initialize"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState10makeActiveEv","espp::state_machine::DeepHistoryState::makeActive"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setActiveChildEP9StateBase","espp::state_machine::DeepHistoryState::setActiveChild"],[63,4,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setActiveChildEP9StateBase","espp::state_machine::DeepHistoryState::setActiveChild::childState"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setDeepHistoryEv","espp::state_machine::DeepHistoryState::setDeepHistory"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setParentStateEP9StateBase","espp::state_machine::DeepHistoryState::setParentState"],[63,4,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setParentStateEP9StateBase","espp::state_machine::DeepHistoryState::setParentState::parent"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState17setShallowHistoryEv","espp::state_machine::DeepHistoryState::setShallowHistory"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState4tickEv","espp::state_machine::DeepHistoryState::tick"],[63,2,1,"_CPPv4N4espp13state_machine9EventBaseE","espp::state_machine::EventBase"],[63,2,1,"_CPPv4N4espp13state_machine19ShallowHistoryStateE","espp::state_machine::ShallowHistoryState"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState5entryEv","espp::state_machine::ShallowHistoryState::entry"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState4exitEv","espp::state_machine::ShallowHistoryState::exit"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState12exitChildrenEv","espp::state_machine::ShallowHistoryState::exitChildren"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14getActiveChildEv","espp::state_machine::ShallowHistoryState::getActiveChild"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState13getActiveLeafEv","espp::state_machine::ShallowHistoryState::getActiveLeaf"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState10getInitialEv","espp::state_machine::ShallowHistoryState::getInitial"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14getParentStateEv","espp::state_machine::ShallowHistoryState::getParentState"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState11handleEventEP9EventBase","espp::state_machine::ShallowHistoryState::handleEvent"],[63,4,1,"_CPPv4N4espp13state_machine19ShallowHistoryState11handleEventEP9EventBase","espp::state_machine::ShallowHistoryState::handleEvent::event"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState10initializeEv","espp::state_machine::ShallowHistoryState::initialize"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState10makeActiveEv","espp::state_machine::ShallowHistoryState::makeActive"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setActiveChildEP9StateBase","espp::state_machine::ShallowHistoryState::setActiveChild"],[63,4,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setActiveChildEP9StateBase","espp::state_machine::ShallowHistoryState::setActiveChild::childState"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setDeepHistoryEv","espp::state_machine::ShallowHistoryState::setDeepHistory"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setParentStateEP9StateBase","espp::state_machine::ShallowHistoryState::setParentState"],[63,4,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setParentStateEP9StateBase","espp::state_machine::ShallowHistoryState::setParentState::parent"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState17setShallowHistoryEv","espp::state_machine::ShallowHistoryState::setShallowHistory"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState4tickEv","espp::state_machine::ShallowHistoryState::tick"],[63,2,1,"_CPPv4N4espp13state_machine9StateBaseE","espp::state_machine::StateBase"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase5entryEv","espp::state_machine::StateBase::entry"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase4exitEv","espp::state_machine::StateBase::exit"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase12exitChildrenEv","espp::state_machine::StateBase::exitChildren"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase14getActiveChildEv","espp::state_machine::StateBase::getActiveChild"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase13getActiveLeafEv","espp::state_machine::StateBase::getActiveLeaf"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase10getInitialEv","espp::state_machine::StateBase::getInitial"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase14getParentStateEv","espp::state_machine::StateBase::getParentState"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase11handleEventEP9EventBase","espp::state_machine::StateBase::handleEvent"],[63,4,1,"_CPPv4N4espp13state_machine9StateBase11handleEventEP9EventBase","espp::state_machine::StateBase::handleEvent::event"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase10initializeEv","espp::state_machine::StateBase::initialize"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase10makeActiveEv","espp::state_machine::StateBase::makeActive"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase14setActiveChildEP9StateBase","espp::state_machine::StateBase::setActiveChild"],[63,4,1,"_CPPv4N4espp13state_machine9StateBase14setActiveChildEP9StateBase","espp::state_machine::StateBase::setActiveChild::childState"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase14setDeepHistoryEv","espp::state_machine::StateBase::setDeepHistory"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase14setParentStateEP9StateBase","espp::state_machine::StateBase::setParentState"],[63,4,1,"_CPPv4N4espp13state_machine9StateBase14setParentStateEP9StateBase","espp::state_machine::StateBase::setParentState::parent"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase17setShallowHistoryEv","espp::state_machine::StateBase::setShallowHistory"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase4tickEv","espp::state_machine::StateBase::tick"]]},objnames:{"0":["c","macro","C macro"],"1":["cpp","member","C++ member"],"2":["cpp","class","C++ class"],"3":["cpp","function","C++ function"],"4":["cpp","functionParam","C++ function parameter"],"5":["cpp","templateParam","C++ template parameter"],"6":["cpp","enum","C++ enum"],"7":["cpp","enumerator","C++ enumerator"],"8":["cpp","type","C++ type"]},objtypes:{"0":"c:macro","1":"cpp:member","2":"cpp:class","3":"cpp:function","4":"cpp:functionParam","5":"cpp:templateParam","6":"cpp:enum","7":"cpp:enumerator","8":"cpp:type"},terms:{"0":[1,2,6,7,9,10,11,12,13,14,15,17,18,21,22,23,24,25,27,32,33,38,40,41,42,43,44,45,47,49,50,51,53,54,55,57,58,59,60,61,64,65,68],"00":18,"000":65,"000f":7,"00b":57,"01":[14,32],"010f":7,"01f":[18,21],"02":6,"024v":1,"02x":58,"03":[44,51],"04":32,"048v":1,"04x":2,"05f":43,"067488":65,"06f":64,"0755":23,"096v":1,"0b00000001":58,"0b00000010":58,"0b00000011":38,"0b00000100":58,"0b00001000":58,"0b0000110":21,"0b00010000":58,"0b00100000":58,"0b00111111":38,"0b0100000":40,"0b01000000":58,"0b0110110":18,"0b10000000":58,"0b11":38,"0b11111":43,"0f":[6,7,12,18,21,22,32,41,42,43,44,45,47,51,59,60],"0s":42,"0x00":[38,40,58],"0x0000":15,"0x000000":58,"0x060504030201":58,"0x10":2,"0x48":1,"0x58":38,"0xa6":58,"0xae":58,"0xff":[2,43,58],"0xffffffffffff":57,"1":[1,2,3,6,7,10,11,12,13,14,15,17,18,21,22,23,24,25,33,38,40,41,42,44,45,47,49,53,54,55,57,58,59,61,62,64,65,67],"10":[2,7,10,14,17,42,44,51,62,64,65],"100":[15,22,40,41,42,59,65],"1000":[3,7,15,17,42,59,61,65],"10000":65,"1000000":60,"10000000":60,"100m":[15,42,51,59,64,68],"1024":[1,2,3,7,9,12,18,21,33,38,40,43,51,54,55,58,60,64,65],"10k":65,"10m":[2,42,54,64,65],"10mhz":60,"12":2,"123":33,"127":[54,55,57],"128":[1,2,54,55,57,61],"12800":15,"128x":2,"13":[38,67],"135":15,"14":38,"144v":1,"14763":65,"15":[2,38,62,65],"1500":61,"152":65,"16":[1,2,15,38,57,58],"1600":1,"16384":[15,18,21],"1678892742599":33,"16kb":58,"16x":2,"1700":[12,41],"18":60,"192":57,"1b":57,"1f":[17,22,41,42,59],"1s":[9,32,33,43,44,51,54,55,59,61,63,64],"2":[1,2,3,7,9,12,13,14,18,21,22,23,24,25,27,38,41,42,44,47,50,51,54,55,57,58,59,60,61],"20":[3,7,15,23,65],"200":[32,61],"200m":[1,58,64],"20143":18,"2046":57,"20df":18,"20m":12,"21":[7,12],"224":[53,54,55],"23017":40,"239":[53,54,55],"23s17":40,"240":15,"2400":1,"2435":61,"2494":65,"24b":58,"25":[22,38,65],"250":1,"250m":17,"255":[11,38,43,53,54,55,57,58,60],"256":[3,57,60,61],"256v":1,"25c":65,"264":61,"265":61,"2657":65,"273":65,"298":65,"2f":[12,22,65],"2pi":[18,21],"2x":2,"3":[1,2,6,7,12,13,14,28,32,38,40,42,54,55,57,60,62,65],"30":65,"300f":7,"300m":44,"31":[12,43,65],"32":[1,2,12,57],"320":[7,15],"32x":2,"33":12,"3300":[1,41,65],"3380":65,"34":[2,7],"3422":65,"3435":65,"3453":65,"3484":60,"3484_datasheet":60,"35981":65,"36":[7,12],"360":[11,18,21,43,60],"36005":18,"37":12,"37ma":38,"38":12,"39":12,"3914752":7,"3940":65,"3950":65,"3986":57,"3f":[1,2,9,17,18,21,33,38,40,44,59,65],"3s":3,"4":[1,2,7,9,12,13,18,21,33,43,45,54,55,57,58,60,64,67],"40":[15,65],"4096":17,"42":[12,62],"43173a3eb323":18,"475":1,"48":[22,57],"4886":38,"48b":58,"490":1,"4b":57,"4kb":58,"4x":2,"5":[1,2,3,7,12,13,18,21,22,25,27,32,33,38,40,43,47,51,54,55,57,58,60,62,65],"50":[15,38,42,58,60,65],"5000":[42,54,55,61],"5001":61,"500m":[3,5,12,22,41,44,51,64],"50c":65,"50m":[18,21,38,40,43,60],"50u":60,"512v":1,"53":15,"53229":65,"5f":[18,21,42,43,47,55,60],"5m":59,"5s":22,"6":[1,2,6,11,12,13,33,54,55,57,60,68],"60":[15,18,21],"61067330":23,"61622309":58,"64":[1,2,60],"649ee61c":18,"64kb":58,"64x":2,"7":[2,7,40,57,62,65],"720":[18,21],"72593":33,"75":[38,65],"8":[1,2,11,14,33,38,40,51,57,58],"80":65,"80552":65,"8192":17,"85":65,"8502":65,"8554":61,"860":1,"8f9a":18,"8x":2,"9":[17,38,60],"920":1,"93hart_equ":65,"9692":10,"9781449324094":57,"9907":65,"9e10":18,"9th":2,"\u03ba":65,"\u03c9":65,"abstract":[35,52,53,64],"boolean":23,"break":63,"byte":[1,2,3,14,15,18,21,23,33,38,40,43,51,53,54,55,57,58,60,61],"case":[18,21,55,60],"char":[23,54,61,64],"class":26,"const":[1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,21,22,23,24,25,27,28,30,32,33,37,38,40,41,42,43,44,45,47,49,50,53,54,55,57,58,59,60,61,64,65,67,68],"default":[1,2,10,12,14,15,32,33,38,40,43,45,47,49,50,51,60,61,62,67,68],"do":[2,5,9,12,13,22,33,51,61,62,63,64],"enum":[1,2,9,12,14,33,38,40,41,43,44,57,65],"final":[12,18,21,38,40,51,57,58,61,63],"float":[1,2,3,5,6,7,9,11,12,14,17,18,21,22,24,25,27,28,32,33,38,40,41,42,43,44,45,46,47,50,51,53,54,55,58,59,60,63,64,65],"function":[1,2,3,5,6,7,9,10,11,12,14,15,17,18,21,22,23,24,25,26,27,28,32,33,34,35,37,38,40,41,42,43,44,45,46,47,49,50,51,52,53,54,55,57,58,59,60,61,63,64,65,67,68],"goto":60,"int":[1,2,5,6,9,10,12,15,17,18,21,22,23,30,38,42,43,50,51,53,54,55,57,58,59,60,61,62,63,64,65],"long":61,"new":[5,6,7,9,10,15,22,24,25,27,28,30,38,41,42,43,44,47,49,50,57,58,59,61,63,64],"public":[1,2,3,5,6,7,9,10,11,12,14,15,17,18,21,22,23,24,25,27,28,30,32,33,37,38,40,41,42,43,44,45,47,49,50,51,53,54,55,57,58,59,60,61,63,64,65,67,68],"return":[1,2,3,5,6,7,9,10,11,12,14,15,17,18,21,22,23,24,25,27,28,30,32,33,38,40,41,42,43,44,45,47,49,50,51,53,54,55,57,58,59,60,61,63,64,65,68],"short":[12,57],"static":[1,2,7,9,10,15,18,21,22,23,32,33,38,40,42,43,46,51,53,54,55,57,58,60,63,64,65],"super":13,"switch":[2,14,60],"throw":[10,23],"true":[2,6,9,12,13,14,15,17,18,21,22,23,30,37,40,41,42,43,44,49,53,54,55,59,60,61,63,64,68],"void":[1,2,3,6,7,9,10,12,14,15,18,21,22,24,27,30,32,33,37,38,40,41,42,43,44,47,49,50,53,54,55,58,59,60,61,63,65,68],"while":[9,10,15,22,42,44,51,61,63,64,68],A:[2,6,9,12,22,29,30,40,43,54,57,61],And:43,As:22,By:10,For:[14,28,33,61,64],IN:33,IT:[23,58],If:[2,5,6,10,11,32,37,42,49,53,54,55,61,63,64,67,68],In:[12,22,38],Is:[53,54,55],It:[2,3,5,7,9,10,12,13,18,21,22,23,30,32,33,38,42,43,59,60,61,63,64,65],NOT:[2,12],No:[2,32,44,57],Not:23,ON:10,ONE:1,On:[2,32],The:[1,2,3,5,6,7,8,9,10,11,12,13,14,17,18,21,22,23,24,25,27,28,29,30,31,32,33,38,40,41,42,43,44,45,46,47,49,50,51,52,53,54,55,57,58,59,60,61,62,63,64,65,67,68],There:[18,20,21,26,34,39,51,63],These:[8,60,61],To:[22,61],Will:[6,18,21,49,51,53,58,61,63],With:41,_1:51,_2:51,_:13,__csv_documentation__:13,__gnu_linux__:[13,62],__linux__:10,__serialization_documentation__:62,__state_machine_documentation__:63,__unnamed11__:58,__unnamed13__:58,__unnamed7__:57,__unnamed9__:57,_activest:63,_build:30,_cli:10,_event_data:63,_in:10,_out:10,_parentst:63,_rate_limit:44,_really_:43,a0:[40,41],a1:41,a2:40,a_0:24,a_1:24,a_2:24,a_gpio:17,a_pin:40,ab:[49,65],abi:[20,35],abi_encod:17,abiencod:[],abil:[44,51],abl:[30,41,54],about:[10,13,51,55,57,58,60,63,65],abov:[2,10,18,21,22,38,43,60],absolut:[18,21,23,57],absolute_uri:57,abxi:12,ac:57,acceler:27,accept:[30,54,61],accepted_socket:[],access:[17,23,35,53,58,63,66,68],accord:[23,38,40,41,42,44,61],accordingli:[9,12],accumul:[17,18,21],accur:59,ack:2,acknowledg:54,across:[3,32],act:57,action:[63,64],activ:[2,6,9,12,40,58,61,63],active_high:[2,40],active_level:9,active_low:[2,12],activeleaf:63,activelevel:9,actual:[1,2,12,15,22,32,33,61,63,65],actual_celsiu:65,actual_kelvin:65,actuat:[33,34],ad0:38,ad1:38,ad:[1,2,7,12,22,50,61],adafruit:[12,33,38,57,60],adc1:65,adc:[12,17,33,35,59],adc_atten_db_11:[3,5,12,41,65],adc_channel_0:[],adc_channel_1:12,adc_channel_2:12,adc_channel_6:[3,5],adc_channel_7:[3,5,65],adc_channel_8:41,adc_channel_9:41,adc_channel_t:[3,5],adc_conv_single_unit_1:[3,65],adc_conv_single_unit_2:[],adc_digi_convert_mode_t:3,adc_typ:0,adc_unit_1:[3,5,65],adc_unit_2:[12,41],adc_unit_t:5,adcconfig:[3,5,12,41,65],add:[6,11,15,50,53,54,55,61],add_multicast_group:[53,54,55],add_publish:22,add_scan:61,add_subscrib:[9,22],addit:[3,11,14,35,41,50,64],additioin:[],addition:[2,9,10,61],addr:[1,12,33,53,58],address:[1,2,15,18,21,30,33,38,40,53,54,55,57,58,61,68],adjust:[32,54],ads1015:1,ads1015config:[1,12],ads1015rat:1,ads1115:1,ads1115config:1,ads1115rat:1,ads1x15:[4,12,35],ads7128:2,ads7138:[4,35],ads_read:[1,2,12],ads_read_task_fn:[1,2,12],ads_task:[1,2,12],ads_writ:[1,2,12],adventur:13,advis:49,ae:57,affect:[18,21,61],affin:64,after:[2,14,41,43,49,53,54,55,58,60,61,68],again:[22,58],against:58,agent:61,alert:2,alert_1000m:33,alert_750m:33,alert_log:2,alert_pin:2,alert_task:2,alertlog:2,algorithm:[6,7,8,11],alias:[18,21],align:43,aliv:30,all:[2,5,6,10,22,23,33,43,44,49,51,55,60,61,63],all_mv:2,alloc:[3,14,51,64],allocatingconfig:[14,15],allocation_flag:14,allow:[1,2,3,5,6,7,10,12,14,17,18,21,32,33,38,40,41,42,43,47,49,52,53,54,55,58,59,60,61,63,64,65],along:[46,58],alow:47,alpaca:[22,35],alpha:[42,47],alreadi:[22,23,24,54,55,61,64],also:[2,10,12,13,14,15,18,21,22,23,32,33,38,51,60,61,63,64],alter_unit:[3,65],altern:[3,23,57],alwai:[3,5,6,18,21,23,33,49,51,61,63],am:18,amount:[3,23,49,50],amp:7,amplitud:47,an:[0,2,5,6,9,10,11,12,17,18,21,22,23,24,25,27,28,29,31,32,33,37,38,40,41,43,45,47,49,51,53,54,55,57,60,61,63,64,68],analog:[2,3,5,33,41],analog_input:2,analogev:2,analogjoystickconfig:12,analyz:51,anaolg:12,android:[57,58],angl:[7,18,21],angle_filt:7,angle_openloop:7,angle_pid_config:7,ani:[2,5,6,7,9,10,13,18,21,30,43,53,54,55,60,61,63,64],anonym:[22,57],anoth:[10,22,23,50],answer:10,any_edg:9,anyth:[13,44,51,62,63],anywher:10,ap:[35,66,68],ap_mac:68,apa102_start_fram:43,apa:57,api:35,app:[57,58],app_main:51,appear:57,append:[2,61],appli:[3,41],applic:[35,61],appropri:[6,54,55],approxim:[2,41,46],ar:[2,4,6,7,8,10,12,15,16,17,20,22,23,26,32,33,34,38,39,40,41,43,44,49,51,52,54,57,58,59,60,61,62,63,64,66],arari:62,arbitrari:10,area:[14,15],arg:44,argument:[30,44],arithmet:24,around:[3,5,6,9,10,13,14,23,37,41,42,44,45,47,49,53,60,62,63,64],arrai:[1,2,15,18,21,24,27,28,33,38,40,45,53,54,55,58,62],arrow:10,articl:65,artifact:60,as5600:[20,35],as5600_ds000365_5:18,as5600_read:18,as5600_writ:18,asid:42,ask:64,aspect:10,asset:33,assign:50,associ:[0,3,5,9,12,14,15,17,22,37,38,40,41,42,45,50,51,53,54,55,64],associt:[53,54,55],assum:[10,43,54,55,65],assumpt:[18,21],asymmetr:59,ate:23,atom:[7,12],attach:[15,38],attenu:[0,3,5,12,41,65],attribut:[1,2,18,21,38,40,43,58,60],audio:33,audiovib:33,authent:[30,57],auto:[1,2,3,5,7,9,10,12,13,15,17,18,21,22,23,32,33,38,40,41,42,43,44,51,54,55,58,59,60,62,63,64,65],auto_seq:2,autoc:33,automat:[2,10,11,61,64],autonom:2,autostop:64,avail:[3,17,22,50,58],avdd:2,avdd_volt:2,averag:[2,11],aw9523:[35,39],aw9523_read:38,aw9523_writ:38,aw9523b:38,awaken:13,ax:[12,41],axi:[2,7,12,41],b0:57,b1:57,b25:65,b2:57,b3:57,b4:57,b7:40,b:[6,11,12,13,17,29,38,40,43,47,51,57,58,60,62,64,65],b_0:24,b_1:24,b_2:24,b_bright:38,b_down:38,b_gpio:17,b_led:38,b_pin:40,b_up:38,back:[14,23,54,55,60],backbon:30,background:32,backlight:15,backlight_on_valu:15,backlight_pin:15,backspac:10,bad:[11,65],band:57,bandwidth:54,base:[7,11,18,21,24,25,26,27,28,32,42,43,51,53,58,59,60,61,63,65],base_encod:60,basi:2,basic:10,batteri:22,batteryst:22,becaus:[7,18,21,23,60],been:[2,10,24,33,43,54,55,58,60,61,64],befor:[2,17,23,32,43,54,61,63,64,68],beg:23,begin:[10,22,23,54,55,57,64],behavior:[32,59],being:[1,2,3,5,7,10,12,17,18,21,22,33,38,40,41,43,58,59,60,63,64,65],belong:55,below:[2,7,63],beta:[42,47,65],better:[27,59],between:[11,22,31,45,49,58],beyond:[10,13,60],bezier:[35,48],bezierinfo:45,bgr:43,bi:58,bia:32,biequad:24,binari:23,bind:[30,44,51,54,55,61],biquad:[25,26,28,35],biquad_filt:24,biquadfilt:24,biquadfilterdf1:24,biquadfilterdf2:[18,21,24,25,28],biquadrat:24,bit0:60,bit1:60,bit:[2,12,15,38,40,42,57,58],bitfield:2,bitmask:2,bldc:[34,35],bldc_driver:6,bldc_haptic:32,bldc_motor:[7,8],bldc_type:7,bldcdriver:[6,7],bldchaptic:32,bldcmotor:[7,18,21,32],ble:[57,58],ble_appear:58,ble_oob_record:58,ble_radio_nam:58,ble_rol:58,blend:11,blerol:[57,58],blob:[10,15],block:[2,3,5,10,32,42,43,54,55,60,61,64],block_siz:60,blue:[11,13,43,60],bluetooth:57,board:15,bob:[7,30],bodmer:15,bool:[2,6,9,12,14,15,17,18,21,22,23,30,37,40,41,42,43,49,53,54,55,59,60,61,63,64,68],both:[2,3,12,13,24,32,38,41,42,49,57,60],both_unit:[3,65],bound:[32,54,60],bounded_no_det:32,box:[12,58],boxart:13,bp:2,br:57,breathing_period:42,breathing_start:42,bredr:57,bright:[38,43],bro:13,broadcast:[55,57],broken:61,brushless:[6,7,8],bs:22,bsp:15,bt:[57,58],bt_device_class:58,bt_oob_record:58,bt_radio_nam:58,btappear:[57,58],bteir:57,btgoep:57,btl2cap:57,btspp:57,bttype:57,bu:[2,15],bufer:64,buffer:[2,3,9,14,22,54,60,61,62,64],buffer_s:55,build:[26,35,61],built:[13,54,62,63],bundl:12,buscfg:15,busi:55,butterworth:[26,35],butterworth_filt:25,butterworthfilt:[18,21,25,28],button:[2,12,35,37,38],button_component_nam:9,button_top:9,buzz1:33,buzz2:33,buzz3:33,buzz4:33,buzz5:33,byte_ord:43,byteord:43,bytes_encod:60,bytes_encoder_config:60,bytes_written:[9,62],c:[6,10,13,15,22,23,35,57,60,62,65],c_str:23,cach:61,calcul:[2,7,32,65],calibr:[5,7,33,41],call:[3,5,9,10,11,12,14,17,18,21,22,32,33,41,43,44,51,53,54,55,58,59,60,61,63,64,67,68],call_onc:22,callback:[1,2,3,5,7,9,12,14,17,18,21,22,33,38,40,41,42,43,51,52,53,54,55,58,59,60,61,63,64,65],callback_fn:64,camera:61,can:[2,6,7,8,9,10,11,12,14,15,17,18,21,23,30,31,32,33,41,42,43,44,45,49,51,54,55,57,58,59,60,61,62,63,64,65,67],can_chang:42,cannot:[23,54,58,61,62],capabl:[38,57,58],captur:[2,40],carrier:57,catalog:65,caus:[61,63],cb:[15,22,61],cc:58,cdn:[38,60],cell:13,celsiu:65,center:[12,32,41,49],central:57,central_onli:57,central_peripher:57,certain:[32,63],cf:57,ch04:57,ch0:2,ch1:2,ch2:2,ch3:2,ch4:2,ch5:2,ch6:2,ch7:2,chang:[7,9,11,32,38,40,42,44,47,59,61,63],change_gain:59,channel:[0,1,2,3,5,6,11,12,17,41,42,60,61,65,67,68],channel_id:2,channel_sel:2,channelconfig:42,charact:10,chart:51,chdir:23,check:[2,6,9,23,30,42,53,54,58,61,68],child:63,childstat:63,chip:[1,2,3,17,20,38,39,40,43,58,65],choos:6,chose:65,chrono:[1,2,7,9,14,18,21,33,38,40,42,43,44,51,53,54,55,58,59,60,63,64,65],chrono_liter:[1,2,12,33],chunk:57,cin:[10,63],circl:41,circuit:65,circular:41,clamp:[6,11,59,60],clang:65,class_of_devic:57,classic:57,clean:[23,54,64],cleanup:[23,53],clear:[2,15,17,58,59,61],clear_event_high_flag:2,clear_event_low_flag:2,cli:[35,63],cli_configure_stdin_stdout:[],client:[30,31,35,52,53],client_socket:[54,55],client_task:[54,55],client_task_fn:[54,55],clifilesesson:10,clisess:10,clk_speed:[1,2,12,18,21,33,38,40,58],clock:[2,43,57,60],clock_spe:15,clock_speed_hz:15,clock_src:60,clockwis:[],close:[7,8,18,21,23,32,54,61],close_accepted_socket:[],co:[43,60],coars:32,coarse_values_strong_det:32,code:[4,7,8,10,15,16,17,22,23,41,44,51,52,57,59,60,61,62,63,64,66],coeffici:[24,27,29,47,65],collect:[2,61],color:[10,14,15,35,43,60],color_data:14,color_map:15,column:65,com:[2,6,7,10,13,15,18,23,24,28,32,33,38,44,55,57,58,60,61,63,65,67,68],combin:[53,54,55],combo:53,come:55,comma:13,command:[7,15,30,35],common:[12,15,33,57],common_compon:10,commun:[1,2,12,18,21,33,38,40,54,55,58],compat:61,complet:[2,10,13,33,42,57,61,64],complex:64,complex_root:63,compon:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,17,18,19,20,21,22,23,24,25,27,28,29,30,32,33,34,35,37,38,39,40,41,42,43,44,45,46,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],compos:57,comput:[11,18,21,31,49,57,59,65],compute_voltag:65,condit:[17,42,64],condition_vari:[1,2,3,5,7,12,17,18,21,33,38,40,41,43,58,59,60,63,64,65],conf:[3,5],config:[1,2,3,5,6,7,9,12,14,17,18,21,23,25,27,28,32,33,37,38,40,41,42,43,44,45,47,49,51,53,54,55,57,58,59,60,61,64,65,67,68],config_esp32_wifi_nvs_en:[67,68],config_esp_maximum_retri:68,config_esp_wifi_password:[58,67,68],config_esp_wifi_ssid:[58,67,68],config_freertos_generate_run_time_stat:51,config_freertos_use_trace_facil:51,config_hardware_box:15,config_hardware_ttgo:15,config_hardware_wrover_kit:15,config_rtsp_server_port:61,configur:[0,1,2,3,5,6,7,9,10,12,14,15,17,18,21,23,25,27,28,32,33,37,38,40,41,42,43,44,45,47,49,51,53,54,55,57,58,59,60,61,62,63,64,65,68],configure_alert:2,configure_global_control:38,configure_l:38,configure_pow:6,configure_stdin_stdout:[10,63],confirm:57,connect:[7,9,12,30,33,40,42,54,57,61,67,68],connect_callback:68,connect_config:54,connectconfig:54,consecut:2,constant:59,constexpr:[1,2,15,18,21,32,38,40,58,60,62],construct:[1,2,9,10,11,18,19,21,25,28,33,38,40,44,45,47,51,53,58,61],constructor:[2,10,11,22,32,43,44,50,53,60,61,65],consum:63,contain:[0,9,10,11,12,14,15,17,22,23,29,32,37,45,50,51,55,57,58,59,61,62,63,68],content:23,context:[22,63],continu:[2,4,23,33,35,55,64,65],continuous_adc:3,continuousadc:[3,65],control:[2,6,7,8,15,18,21,22,30,32,33,35,38,40,42,43,45,57,59,61],control_point:45,control_socket:61,controller_driv:15,conveni:[10,12,13,18,21,42,53,62,63],convers:[1,2,3,11,18,21,41,53],convert:[2,5,6,7,11,12,18,21,22,23,41,49,53,61,65],convert_mod:[3,65],convieni:[45,47],cool:44,coordin:[15,37],copi:[10,11,23,50,60,63,64],copy_encod:60,core:64,core_id:[7,64],core_update_period:7,corner:15,correct:[7,63],correspond:[2,15,33,38,65],could:[2,11,13,18,23,59,62,63],couldn:[22,23],count:[1,2,7,9,17,18,21,33,38,40,42,43,44,51,58,59,60,64,65],counter:[17,18,21],counter_clockwis:7,counts_per_revolut:[17,18,21],counts_per_revolution_f:[18,21],counts_to_degre:[18,21],counts_to_radian:[18,21],coupl:[22,41],cout:10,cplusplu:10,cpp:[23,35,44,58,61],cpprefer:[23,44],cpu:51,cr:61,crd:17,creat:[2,7,9,10,11,12,13,15,17,18,21,23,30,32,41,43,44,49,51,54,55,57,58,59,60,61,63,64,65,67,68],create_directori:23,creation:[18,21],credenti:57,cross:[2,44,64],cs:7,cseq:61,csv2:13,csv:[2,23,35],csv_data:13,ctrl:10,cubic:45,curent:[53,63],current:[6,7,9,10,12,15,17,18,21,22,30,31,32,37,38,42,44,47,50,51,52,59,60,61,65,68],current_directori:30,current_duti:42,current_hfsm_period:63,current_limit:7,current_pid_config:7,current_sens:7,currentlyact:63,currentsensor:7,currentsensorconcept:7,cursor:[10,15],curv:45,custom:[14,22,23,33,60,62],cutoff:[7,25,27],cv:[1,2,3,5,7,12,17,18,21,22,33,38,40,41,42,43,54,58,59,60,63,64,65],cv_retval:64,cv_statu:64,cycl:[6,33,42,60],d2:12,d3:12,d4:12,d5:12,d6:12,d:[7,12,22,44,53,54,55],d_current_filt:7,dam:65,daniele77:10,data:[0,1,2,3,5,7,9,11,12,13,14,15,18,21,22,23,24,25,27,28,30,33,37,38,40,41,43,51,53,54,55,57,58,61,62,63,65,68],data_address:58,data_command_pin:15,data_len:[1,2,12,18,21,33,38,40],data_s:60,data_sheet:65,data_str:22,dataformat:2,datasheet:[18,33,38,58,60,65],datasheet_info:65,date:[3,23],date_tim:23,dav:57,db:65,dbm:57,dc:[6,7,8,15],dc_current:[],dc_level_bit:15,dc_pin:15,dc_pin_num:15,de:22,dead_zon:6,deadband:[12,41,49],deadzon:41,deadzone_radiu:41,deal:57,debug:[44,58,63,64],debug_rate_limit:44,decod:[7,18,21,58,61],dedic:12,deep:63,deep_history_st:63,deephistoryst:63,default_address:[1,2,18,21,33,38,40],defautl:47,defin:[22,43,49,60,61,62,63],definit:[19,22],degre:[17,18,21],deinit:[3,68],del:60,delai:[7,24],delet:[5,10,12,17,23,60],delete_fn:60,delimit:13,demo:[10,15],depend:[3,32,49,60,63],depth:60,dequ:10,deriv:[59,63],describ:[14,15,49,54,57,61],descript:[],descriptor:[53,54,55],deseri:[9,22,57,62],design:[12,18,21,32,34,37,43,61,63,65],desir:[0,6,32],destin:23,destroi:[1,2,3,5,6,7,9,12,17,18,21,30,33,38,40,41,43,58,59,60,61,63,64,65],destruct:64,destructor:[10,22,60,61],detail:[7,32,54],detect:9,detent:32,detent_config:32,detentconfig:32,determin:[18,21],determinist:3,dev:15,dev_addr:[1,2,12,18,21,33,38,40],dev_kit:15,devcfg:15,develop:[7,15,57,63],devic:[1,2,15,18,21,32,33,37,38,40,57,58,67],device_address:[1,2,18,21,33,38,40],device_class:57,devkit:15,diagno:33,diagnost:33,did_pub:22,did_sub:[9,22],differ:[2,15,18,19,20,21,22,24,26,33,39,42,43,44,58,59,60,63],digial:27,digit:[2,24,25,28],digital_biquad_filt:[24,28],digital_input:2,digital_output:2,digitalconfig:12,digitalev:2,dim:38,dimension:50,dir_entri:23,direct:[5,12,24,38,40,58],directli:[2,6,8,20,33,34,43,45],directori:[23,30],directory_iter:23,directory_list:23,disabl:[2,6,7,10,17,18,38,58,60],disconnect:[61,68],disconnect_callback:68,discontinu:49,discover:57,discuss:[10,58],displai:[13,35,57,61],display_driv:[15,16],display_event_menu:63,distinguish:62,distribut:[22,49],divid:[11,24,50,59,60,65],divider_config:65,divis:65,dma:[3,60,65],dma_en:60,dnp:2,doc:[6,10,14,30,60,65,67,68],document:[10,13,18,58,60,62,63],doe:[3,5,6,13,17,18,21,23,30,32,38,40,43,53,61,62,63],doesn:[2,23],don:[1,2,3,5,7,12,17,18,21,22,33,38,40,41,43,51,54,55,58,59,60,64,65],done:[22,42,53,54,55],dot:50,doubl:[10,14],double_buff:14,double_click:33,down:[10,12,43,53,54,55,59,63,64],doxygen:30,doxygenfunct:30,dq:[],drain:2,draw:[14,15],drive:[2,7,22,33,34,38,60],driven:[32,34],driver:[1,2,7,8,10,12,14,16,18,21,34,35,37,38,40,43,58,61],driverconcept:7,drv2605:[34,35],drv:15,ds:[2,33],dsiplai:14,dsp:[24,27],dsprelat:[24,28],dual:[12,57],dualconfig:12,dummycurrentsens:7,durat:[1,2,7,9,14,18,21,32,33,38,40,42,43,44,51,53,54,55,58,59,60,63,64,65],duration0:60,duration1:60,dure:[59,63],duti:[6,42],duty_a:6,duty_b:6,duty_c:6,duty_perc:42,duty_resolut:42,dx:13,dynam:[7,32,47,58,59],dynamictask:64,e2:65,e:[10,23,33,43,47,60,63,65],each:[2,3,5,6,11,12,22,23,28,30,32,38,41,44,51,61,62],earli:[1,2,3,5,7,12,17,18,21,33,38,40,41,43,58,59,60,63,64,65],easili:[2,18,52,64],ec:[9,22,23,61,62],eccentr:[33,34],ecm:33,ed:17,edg:[2,9,18,21,32,33,60],edit:10,edr:57,eeprom:58,effici:13,eh_ctrl:58,eight:1,eir:57,either:[12,17,51,65],el_angl:7,elaps:[1,2,9,33,42,44,59,64,65],electr:7,element:[5,50],els:[2,3,5,7,9,23,38,40,62,63,65],em:[9,22],empti:[33,43,57,61,67,68],en:[6,10,23,24,25,28,30,44,53,54,55,57,58,60,65,67,68],enabl:[2,3,5,6,7,9,10,12,14,22,32,38,51,52,54,58,64,67,68],enable_if:[17,50],enable_reus:[53,54,55],encapsul:58,encod:[32,35,61],encode_fn:60,encoded_symbol:60,encoder_typ:19,encoder_update_period:[18,21],encodertyp:17,encrypt:57,end:[2,10,15,22,23,32,33,43,54,55,57,58,63],end_fram:43,endev:63,endif:15,endl:10,endpoint:[53,54,55],energi:57,enforc:63,english:[38,57],enough:64,ensur:[7,10,49,60,67,68],enter:[2,10,63],enterpris:57,entri:[51,63],enumer:[1,2,9,12,14,33,38,40,41,43,44,57,65],eoi:61,epc:57,equal:10,equat:[17,24,65],equival:[10,13,38],erm:[33,34],err:[1,2,12,18,21,23,33,38,40,58],error:[1,2,9,22,23,33,38,44,59,60,61,65],error_cod:[9,22,23,61,62],error_rate_limit:44,esp32:[3,6,10,12,23,30,32,41,60,61,67,68],esp32s2:3,esp32s3:3,esp:[3,5,6,9,10,15,17,24,27,30,35,42,44,55,58,60,61,64,67,68],esp_err_t:[15,60],esp_err_to_nam:[1,2,33,38],esp_error_check:15,esp_lcd_ili9341:15,esp_log:44,esp_ok:[1,2,12,18,21,33,38,40,58,60],esphom:15,espp:[1,2,3,5,6,7,9,10,11,12,14,15,17,18,21,22,23,24,25,27,28,30,31,32,33,37,38,40,41,42,43,44,45,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],espressif:[6,10,15,27,55,60,67,68],etc:[9,23,38,40,43,59,60,62],evalu:[45,47],even:[58,62],evenli:32,event1:22,event1_cb:22,event2:22,event2_cb:22,event:[2,9,35,58,63,68],event_callback_fn:[9,22],event_count:2,event_flag:2,event_high_flag:2,event_low_flag:2,event_manag:22,eventbas:63,eventdata:68,eventmanag:[9,22],everi:[14,18,21,44],everybodi:10,everyth:10,exactli:57,exampl:[4,8,16,52,66],exceed:68,excel:7,except:[10,23],exchang:57,execut:[10,22,63,64],exis:68,exist:[6,10,13,23,61,62,63],exit:[1,2,3,5,7,10,12,17,18,21,33,38,40,41,43,58,59,60,63,64,65],exitact:10,exitchildren:63,exitselect:63,exp:[47,51],expand:35,explicit:[9,10,53,61,65],explicitli:10,expos:[10,13,44],extend:57,extern:[2,10,33,41,57,63],external_typ:57,extra:[60,61],extra_head:61,exttrigedg:33,exttriglvl:33,f:23,f_cutoff:[25,27],f_sampl:[25,27],facil:51,factor:[18,21,27,32,65],fade:42,fade_time_m:42,fahrenheit:65,fail:[1,2,9,12,18,21,33,38,40,58,62,68],fake:64,fall:[2,9,58,60],falling_edg:9,fals:[1,2,3,5,6,7,9,12,15,17,18,21,22,23,30,33,37,38,40,41,42,43,49,51,54,55,58,59,60,61,63,64,65,68],famili:[1,2],far:10,fast:[35,48,58],fast_co:46,fast_ln:46,fast_math:46,fast_sin:46,fast_sqrt:46,fastest:[18,21],fault:6,fclose:23,featur:2,feedback:[32,33,34],feel:7,few:[10,15,22,63],ff:57,fi:[67,68],field:[2,7,23,41,57,58,61],field_fal:58,field_ris:58,figur:[13,23,62,63],file2:23,file:[31,35],file_byt:23,file_cont:23,file_s:23,file_str:23,file_system:23,filenam:13,filesystem:30,fill:[15,24,27,37,41,53,54,55,58],filter:[3,5,7,17,18,21,29,35,65],filter_cutoff_hz:[18,21],filter_fn:[7,18,21],fine:32,fine_values_no_det:32,fine_values_with_det:32,finger563:63,finish:[10,32,60],first:[2,7,22,43,54,55,57,58,61,65],first_row_is_head:13,fish:10,fit:14,fix:65,fixed_length_encod:62,fixed_resistance_ohm:65,flag:[2,15,22,57,58,60],flip:49,floatrangemapp:41,flush:[14,15,23],flush_callback:[14,15],flush_cb:15,flush_fn:14,fmod:42,fmt:[2,3,5,10,12,13,15,17,18,21,22,38,40,41,42,51,54,55,58,59,60,61,62,64,65,68],foc:[6,7],foc_curr:[],foc_typ:7,foctyp:7,folder:[4,8,10,13,16,17,41,44,51,52,59,62,63,64,66],follow:[2,7,24,32,33,43,46,51,57,58,60,63,65],fopen:23,forc:[6,14],force_refresh:14,form:[24,25,61],format:[2,13,15,22,23,35,51,57,61,64,65],formula:65,forum:57,found:[18,21,33,57,58],four:1,frac:[24,47,65],frag_typ:61,fragment:61,frame:[2,43,61],fread:23,free:[14,23,42,60],free_spac:23,freebook:[24,28],freerto:[51,64],frequenc:[3,5,18,21,25,27,32,42],frequency_hz:42,frequent:[14,59],from:[1,2,3,5,6,7,10,11,12,14,15,18,21,22,23,26,30,32,33,34,35,37,38,40,41,42,44,47,49,50,53,54,55,57,58,59,60,61,62,63,64,65,68],from_sockaddr:53,fs:23,fseek:23,ftell:23,fthat:11,ftm:58,ftp:[35,57,61],ftp_anon:57,ftp_client_sess:30,ftp_ftp:57,ftp_server:30,ftpclientsess:30,ftpserver:30,fulfil:[18,21],full:[6,38,43,61],fulli:[33,63,64],fun:22,further:61,futur:[44,57,61],fwrite:23,g:[11,23,33,38,43,47,60,65],g_bright:38,g_down:38,g_led:38,g_up:38,gain:[1,32,59],game:57,gamepad:[57,58],gamma:[42,47],gate:6,gaussian:[35,42,48],gb:13,gbc:13,gener:[2,18,21,26,53,57,60,61,67,68],generatedeventbas:63,generic_hid:57,geometr:11,get:[1,2,3,6,7,9,10,11,12,13,14,15,17,18,21,22,23,30,32,37,40,41,42,43,47,51,53,54,55,57,58,59,60,61,62,63,64,65,68],get_accepted_socket:[],get_accumul:[18,21],get_all_mv:2,get_celsiu:65,get_config:59,get_count:[17,18,21],get_data:61,get_degre:[17,18,21],get_digital_input_valu:2,get_duti:42,get_electrical_angl:7,get_error:59,get_event_data:2,get_event_flag:2,get_event_high_flag:2,get_event_low_flag:2,get_fahrenheit:65,get_free_spac:23,get_ftm_length:58,get_head:61,get_height:61,get_histori:10,get_info:64,get_integr:59,get_interrupt_captur:40,get_interrupt_statu:58,get_ipv4_info:[53,54,55],get_jpeg_data:61,get_kelvin:65,get_mechanical_degre:[18,21],get_mechanical_radian:[18,21],get_mjpeg_head:61,get_mount_point:23,get_mv:[2,3,65],get_num_q_t:61,get_offset:[15,61],get_output_cent:49,get_output_max:49,get_output_min:49,get_output_rang:49,get_packet:61,get_partition_label:23,get_payload:61,get_pin:[38,40],get_posit:32,get_power_supply_limit:6,get_q:61,get_q_tabl:61,get_quantization_t:61,get_radian:[17,18,21],get_rat:3,get_remote_info:54,get_resist:65,get_revolut:17,get_root_path:23,get_rpm:[18,21],get_rpt_head:61,get_rtp_header_s:61,get_scan_data:61,get_session_id:61,get_shaft_angl:7,get_shaft_veloc:7,get_siz:57,get_stat:12,get_total_spac:23,get_type_specif:61,get_used_spac:23,get_user_input:10,get_user_select:63,get_valu:[12,41],get_values_fn:41,get_vers:61,get_voltag:65,get_voltage_limit:6,get_width:61,getactivechild:63,getactiveleaf:63,getiniti:63,getinputhistori:10,getlin:10,getparentst:63,getsocknam:[53,54,55],getter:[50,61],gettimerperiod:63,gettin:41,gimbal:32,github:[10,13,15,32,45,55,58,60,61,63],give:[53,63,64],given:[2,22,25,61,63],glitch:17,global:[3,38],go:[22,23,63],goe:2,gone:64,goodby:10,googl:58,got:[2,22,61,68],gotten:[7,10,68],gpio:[2,6,9,12,17,38,40,42,60],gpio_a:12,gpio_a_h:[6,7],gpio_a_l:[6,7],gpio_b:12,gpio_b_h:[6,7],gpio_b_l:[6,7],gpio_c_h:[6,7],gpio_c_l:[6,7],gpio_config:2,gpio_config_t:2,gpio_down:12,gpio_en:[6,7],gpio_evt_queu:2,gpio_fault:[6,7],gpio_i:12,gpio_install_isr_servic:2,gpio_intr_negedg:2,gpio_isr_handl:2,gpio_isr_handler_add:2,gpio_joystick_select:12,gpio_left:12,gpio_mode_input:2,gpio_num:[9,43,60],gpio_num_18:15,gpio_num_19:15,gpio_num_22:15,gpio_num_23:15,gpio_num_2:9,gpio_num_45:15,gpio_num_48:15,gpio_num_4:15,gpio_num_5:15,gpio_num_6:15,gpio_num_7:15,gpio_num_t:15,gpio_pullup:12,gpio_pullup_dis:2,gpio_pullup_en:[1,2,12,18,21,33,38,40,58],gpio_right:12,gpio_select:12,gpio_start:12,gpio_up:12,gpio_x:12,gpo:58,grab:41,gradient:11,grai:44,graphic:11,grb:43,greater:44,green:[11,43,44,60],ground:12,group:[23,53,54,55,57],grow:[],guarante:43,guard:63,gui:[14,15,51],guid:[10,67,68],h:[10,11,15,44,61],ha:[2,7,10,12,17,18,21,22,23,30,33,38,40,42,43,51,54,55,57,58,60,61,63,64,68],half:[18,21,24],handl:[9,10,30,38,40,43,54,55,60,63,64],handle_all_ev:63,handleev:63,handler:[2,9,55],handov:57,happen:22,haptic:35,haptic_config:32,haptic_motor:32,hapticconfig:32,hardawr:42,hardwar:[7,17,27,38,42,43,61],hart:65,has_q_tabl:61,has_stop:63,has_valu:[3,5,12,41,42,65],hash:57,have:[2,7,10,13,14,22,24,32,33,38,41,42,43,44,51,54,59,60,61,63,64,65,67,68],hc:57,heart:7,height:[14,15,61],hello:[10,58],hello_everysess:10,help:57,helper:53,henri:7,here:[10,13,18,22,33,38,40,58,59],hid:57,high:[2,3,6,9,14,17,32,40,51,60],high_level:9,high_limit:17,high_resolution_clock:[1,2,7,9,18,21,33,38,40,42,43,44,51,58,59,60,64,65],high_threshold_mv:2,high_water_mark:51,higher:[24,27],histori:[10,24,25,27,28,63],history_s:10,hmi:15,hold:[14,57,58],home:37,hop:[53,54,55],host:[2,15,38,57,67],hot:65,how:[7,13,14,17,59,62,63,65],howev:24,hpp:[0,1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,19,21,22,23,24,25,27,28,29,30,32,33,37,38,40,41,42,43,44,45,46,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],hr:57,hs:57,hsfm:63,hsv:[11,43,60],html:[6,10,14,15,24,28,57,60,67,68],http:[2,6,7,10,13,14,15,18,23,24,25,28,32,33,38,44,45,53,54,55,57,58,60,61,63,65,67,68],http_www:57,https_www:57,hue:[11,43,60],human:[13,23],human_read:23,hz:[3,32],i2c:[4,18,20,21,33,35,38,39,40,43,58],i2c_cfg:[1,2,12,18,21,33,38,40,58],i2c_config_t:[1,2,12,18,21,33,38,40,58],i2c_driver_instal:[1,2,12,18,21,33,38,40,58],i2c_freq_hz:[1,2,12,18,21,33,38,40,58],i2c_master_read_from_devic:2,i2c_master_write_read_devic:[1,12,18,21,33,38,40,58],i2c_master_write_to_devic:[1,2,12,18,21,33,38,40,58],i2c_mode_mast:[1,2,12,18,21,33,38,40,58],i2c_num:[1,2,12,18,21,33,38,40,58],i2c_param_config:[1,2,12,18,21,33,38,40,58],i2c_read:33,i2c_scl_io:[1,2,12,18,21,33,38,40,58],i2c_sda_io:[1,2,12,18,21,33,38,40,58],i2c_timeout_m:[1,2,12,18,21,33,38,40,58],i2c_writ:33,i:[2,7,13,17,35,39,43,51,59,62,63,64,65],i_gpio:17,id:[2,30,33,57,61,64],ident:10,identifi:[33,57,61],idf:[3,5,6,9,10,35,42,44,55,60,67,68],ifs:23,ifstream:23,ignor:17,iir:27,il:57,imag:61,imap:57,imax:38,imax_25:38,imax_50:38,imax_75:38,immedi:[63,64],imped:6,impl:[25,28],implement:[2,6,7,8,10,11,24,25,27,28,30,31,32,45,46,47,50,57,61,63],implicit:[18,21],impuls:27,includ:[0,1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,19,21,22,23,24,25,27,28,29,30,32,33,37,38,40,41,42,43,44,45,46,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],incom:54,incomplet:57,increas:[9,17,44,59],increment:[2,17,38],incur:14,independ:[41,50],index:[2,17,43,50,61,65],indic:[38,40,54,55,57,58,64],individu:[41,45],induct:7,infinit:27,info:[1,2,3,5,7,9,12,17,22,32,33,41,43,44,51,53,54,55,59,60,61,65],info_rate_limit:44,inform:[11,14,18,21,25,28,38,40,41,43,45,51,53,54,55,57,58,60,63,65,67,68],infrar:60,inherit:10,init:[41,53,54],init_ipv4:53,initail:[3,65],initi:[1,2,3,5,6,7,9,12,14,15,17,18,21,27,33,37,38,40,41,42,47,49,53,54,55,58,60,63,64,67,68],inlin:[1,2,3,5,6,7,9,10,12,14,15,17,18,21,22,23,24,25,27,28,30,32,33,37,38,40,41,42,43,44,45,47,49,50,51,53,54,55,57,58,59,60,61,63,64,65,67,68],inout:2,input:[2,7,9,10,12,18,21,24,25,27,28,32,33,35,38,40,41,49],input_delay_n:15,input_driv:37,input_valu:2,inquiri:57,insert:10,insid:2,instal:[1,2,9,12,18,21,33,38,40,58],instanc:[22,23],instant:42,instanti:51,instead:[10,30,49,62,63],instruct:27,instrument:[2,33],int16_t:17,int8_t:62,intead:[],integ:[6,17,46,53],integr:59,integrator_max:[7,59],integrator_min:[7,59],intend:[45,63,64],interact:[10,20,22,23,39,61],interest:[12,22],interfac:[6,8,9,14,20,23,30,32,33,35,38,39,40,43,60,61],interfer:32,intermedi:57,intern:[2,10,12,15,17,24,25,27,28,33,38,40,53,63],interpol:11,interrupt:[2,9,17,38,40,58,64],interrupt_typ:9,interrupttyp:9,intr_typ:2,introduc:49,inttrig:33,invalid:[10,11],invalid_argu:10,invers:42,invert:[12,37,38,40,42,49],invert_color:15,invert_i:37,invert_input:49,invert_output:49,invert_x:37,invoc:59,io:[14,15,23,35,45,57],io_conf:2,io_num:2,ip2str:68,ip:[30,53,54,55,61,68],ip_add_membership:[53,54,55],ip_address:[30,54,55,61],ip_callback:68,ip_event_got_ip_t:68,ip_evt:68,ip_info:68,ip_multicast_loop:[53,54,55],ip_multicast_ttl:[53,54,55],ipv4:53,ipv4_ptr:53,ipv6:53,ipv6_ptr:53,ir:60,irdaobex:57,is_a_press:12,is_act:61,is_al:30,is_b_press:12,is_charg:22,is_clos:61,is_complet:61,is_connect:[30,54,61,68],is_dir:23,is_directori:23,is_down_press:12,is_en:6,is_fault:6,is_floating_point:50,is_left_press:12,is_multicast_endpoint:55,is_passive_data_connect:30,is_press:[9,12],is_right_press:12,is_select_press:12,is_start:64,is_start_press:12,is_up_press:12,is_valid:[53,54,55],isr:[2,9],issu:10,istream:10,it_st:58,item:[13,23],iter:[15,22,23,54,55,64],its:[2,3,18,21,22,30,32,38,40,47,51,53,54,55,58,59,63,67],itself:[14,22,37,61,64],join:[53,54,55],joybonnet:[1,12],joystick:[2,12,35,57],joystick_config:12,joystick_i:12,joystick_select:12,joystick_x:12,jpeg:61,jpeg_data:61,jpeg_fram:61,jpeg_frame_callback_t:61,jpeg_head:61,jpegfram:61,jpeghead:61,jpg:13,js1:41,js2:41,jump:49,just:[2,12,18,21,22,57,60,61,62,63,65],k:[10,65],k_bemf:7,kbit:58,kd:[7,32,59],kd_factor_max:32,kd_factor_min:32,keepal:54,kei:[10,57,58,61],kelvin:65,keyboard:[10,57],ki:[7,59],kind:[19,63],know:[14,18,21,22,64],known:[57,63],kohm:40,kp:[7,32,59],kp_factor:32,kv:7,kv_rate:7,label:[15,23],lack:23,lambda:[1,2,12,18,21,33,38,40,44,58,65],landscap:[14,15],landscape_invert:14,larg:61,larger:[3,10,61],last:[12,17,41,43,57,59,63],last_unus:12,latch:60,later:[6,15,17],latest:[6,10,37,41,51,59,60,65,67,68],launch:57,launcher:58,launcher_record:58,lazi:13,lcd:15,lcd_send_lin:15,lcd_spi_post_transfer_callback:15,lcd_spi_pre_transfer_callback:15,lcd_write:15,le:57,le_rol:57,le_sc_confirm:57,le_sc_random:57,lead:[3,11],leaf:63,learn:[33,57],least:[17,43,54],leav:2,led:[2,35,38,60],led_callback:42,led_channel:42,led_encod:[43,60],led_encoder_st:60,led_fade_time_m:42,led_reset_cod:60,led_stip:60,led_strip:[43,60],led_task:42,ledc:42,ledc_channel_5:42,ledc_channel_t:42,ledc_high_speed_mod:42,ledc_mode_t:42,ledc_timer_10_bit:42,ledc_timer_13_bit:42,ledc_timer_2:42,ledc_timer_bit_t:42,ledc_timer_t:42,ledstrip:43,left:[12,15,17,43],legaci:57,legend:13,len:43,length16:58,length:[2,15,24,27,43,50,57,58,60],less:[6,41,57,58,64],let:[10,14,22,51],level0:60,level1:60,level:[6,7,8,9,22,32,33,40,43,44,53,54,55,57,60,61,63,65],leverag:27,lib:33,libarari:62,libfmt:44,librari:[10,22,23,32,33,35,57,62],life:[10,62],lifecycl:14,light:[11,37,44,62,63],like:[22,53],limit:[6,7,10,17,44,57,59],limit_voltag:[6,7],line:35,line_input:10,linear:[33,34],lineinput:10,link:[13,23],links_awaken:13,list:[2,23,33,57],list_directori:23,listconfig:23,listen:[30,54,61],lit:[2,33],littl:[22,42],littlef:23,lk:[1,2,3,5,7,12,17,18,21,22,33,38,40,41,42,43,58,59,60,63,64,65],ll:[1,2,12,18,21,22,33,38,40,43,58],ln:65,load:[12,13,57],local:57,lock:[54,64],lodeston:30,log:[2,7,9,22,32,33,35,37,38,40,42,43,51,58,60,61,64,65],log_level:[1,2,3,5,6,7,9,12,14,17,18,21,32,33,37,38,40,41,42,43,54,55,58,59,60,61,63,64,65,67,68],logger1:44,logger1_thread:44,logger2:44,logger2_thread:44,logger:[1,2,3,5,6,7,9,12,14,17,18,21,22,23,32,33,35,37,38,40,41,42,43,53,54,55,58,59,60,61,63,64,65,67,68],logger_:[14,41],logger_config:53,logger_fn:44,logic:[2,12,55,57],long_local_nam:57,longer:10,loop:[7,8,10,18,21,23,32,44,64],loop_foc:7,loop_iter:44,loopback_en:[53,54,55],loos:22,lose:10,lot:9,low:[2,5,6,7,8,9,12,17,22,40,53,57,60],low_level:9,low_limit:17,low_threshold_mv:2,lower:[17,38,40,65],lowest:64,lowpass:[26,35],lowpass_filt:27,lowpassfilt:27,lra:[33,34],lsb:[2,38],lv_area_t:[14,15],lv_color_t:[14,15],lv_disp_drv_t:[14,15],lv_disp_flush_readi:14,lv_tick_inc:14,lvgl:[14,15,37],lvgl_esp32_driv:15,lvgl_tft:15,m:[1,2,3,5,7,12,17,18,21,22,32,33,38,40,41,42,43,44,54,58,59,60,63,64,65],m_pi:[18,21,51],ma:65,mac:[57,68],mac_addr:57,mac_address:57,machin:35,macro:44,made:58,magic_enum_no_check_support:63,magnet:[20,32,35],magnetic_det:32,magnitud:[41,50,59],magnitude_squar:50,mai:[2,3,9,32,43,57,58,63],mailbox:58,mailto:57,main:[7,14,60],mainli:14,maintain:[14,18,21,58],make:[1,2,7,12,18,21,22,23,33,38,40,53,57,58,61,63,65],make_android_launch:[57,58],make_ev:63,make_le_oob_pair:[57,58],make_multicast:[53,54,55],make_oob_pair:[57,58],make_shar:[7,15],make_text:[57,58],make_uniqu:[1,2,10,12,33,42,51,54,55,60,64],make_uri:[57,58],make_wifi_config:[57,58],makeact:63,malloc_cap_8bit:14,malloc_cap_dma:14,manag:[5,11,12,13,14,23,35,38,40,42,54,55,57,58],mani:[7,9,17,22,54,55,68],manipul:9,manual:[2,10,32,61,63],manual_chid:2,map:[12,41,49,61],mapper:[35,41,48],mario:13,mark:[51,61],marker:61,mask:[38,40],maskaravivek:57,mass:[33,34],master:[1,2,10,12,15,18,21,33,38,40,55,58,60],match:[23,30],math:[35,45,47,49,50],max:[2,6,17,32,33,38,47,49,54,55,59,67],max_connect:54,max_data_s:61,max_glitch_n:17,max_led_curr:38,max_num_byt:[54,55],max_number_of_st:67,max_pending_connect:54,max_receive_s:54,max_transfer_sz:15,maximum:[6,12,18,21,38,41,49,54,55,59,61],maxledcurr:38,maybe_duti:42,maybe_mv:[3,5,65],maybe_r:3,maybe_x_mv:[12,41],maybe_y_mv:[12,41],mb:[23,57],mb_ctrl:58,mcp23x17:[35,39],mcp23x17_read:40,mcp23x17_write:40,mcpwm:[6,32],me:57,mean:[6,11,18,21,24,41,49,51,60,62,64],measur:[3,5,7,17,18,21,41,59,65],mechan:[3,7,18,21,22,30],media:57,mega_man:13,megaman1:13,megaman:13,member:[1,2,3,5,6,7,9,11,12,14,17,18,21,23,25,27,32,33,37,38,40,41,42,43,44,45,47,49,51,53,54,55,57,58,59,60,61,64,65,67,68],memori:[10,14,24,27,42,58,60,64],memset:[1,2,12,15,18,21,33,38,40,58],mention:10,menu:10,menuconfig:23,mere:6,messag:[2,9,22,23,57,58,61,62],method:[7,9,17,23,45,47,59,61,62],metroid1:13,metroid:13,micro:15,micros_per_sec:60,middl:57,millisecond:42,millivolt:65,mime_media:57,min:[2,32,49],minimum:[12,41,49,59],minu:61,minut:[18,21],mireq:15,mirror:40,mirror_i:15,mirror_x:15,miso_io_num:15,mix:11,mjepg:61,mjpeg:61,mkdir:23,mode:[1,2,3,9,12,15,18,21,32,33,38,40,42,57,58],model:[11,63],moder:5,modif:7,modifi:[15,38,61],modul:[],modulo:[18,21],monitor:35,more:[2,3,10,11,14,25,26,28,33,41,42,43,44,47,53,54,55,60,63,65],mosi:15,mosi_io_num:15,most:[3,7,12,18,21,41,59],motion:[7,32],motion_control_typ:7,motioncontroltyp:7,motoion:7,motor:[6,8,18,21,32,34,35],motor_task:7,motor_task_fn:7,motor_typ:33,motorconcept:32,motortyp:33,mount:23,mount_point:23,mous:57,move:[7,10,43,51,60,64],movement:10,ms:14,msb:[2,38],msb_first:60,mt6701:[7,20,35],mt6701_read:[7,21],mt6701_write:[7,21],much:24,multi_rev_no_det:32,multicast:[53,54],multicast_address:[53,54,55],multicast_group:[53,54,55],multipl:[3,5,7,12,32,33,34,44,59,61],multipli:[32,50,59],must:[2,5,7,10,17,22,23,51,53,54,55,57,58,62,63,64,67,68],mutabl:[50,64],mutat:64,mute:2,mutex:[1,2,3,5,7,12,17,18,21,22,33,38,40,41,42,43,54,58,59,60,63,64,65],mux:2,mv:[1,2,3,5,41,65],mystruct:62,n:[2,3,5,10,12,13,17,18,21,22,23,24,28,29,38,40,41,42,51,54,55,58,59,60,61,62,64,65,68],name:[1,2,3,5,7,12,13,17,18,21,22,33,38,40,41,42,43,51,54,55,57,58,59,60,61,62,63,64,65],namespac:[1,2,12,23,33],nanosecond:17,navig:10,ndef:[35,56,58],ndeflib:57,ndefmessag:57,ne:13,nearest:[32,46],necessari:[7,64],need:[3,5,9,10,18,21,22,23,24,32,38,51,57,59,60,63,64],needs_zero_search:[18,21],neg:[43,50,59,65],negat:[12,50],neo_bff_io:43,neo_bff_num_l:43,neopixel_writ:43,network:[35,54,55,57,67],new_duti:42,new_object:62,new_siz:10,new_target:7,newli:64,newlin:51,next:[10,32,60],nf:57,nfault:7,nfc:[35,57,58],nicer:44,nm:7,no_timeout:64,nocolor:10,node:[53,54,55,63],nois:49,nomin:65,nominal_resistance_ohm:65,non:[3,32,49,58],nonallocatingconfig:14,none:[2,14,30,44,57,63],normal:[14,22,24,50],normalizd:[25,27],normalized_cutoff_frequ:[18,21,25,27],note:[1,2,3,5,7,9,10,12,17,18,21,22,23,30,32,33,38,40,41,43,44,54,55,58,59,60,62,63,64,65],noth:[6,51],notifi:[2,61,64],now:[1,2,7,9,13,18,21,22,32,33,38,40,42,43,44,51,54,55,58,59,60,64,65],ntc:65,ntc_smd_standard_series_0402:65,ntcg103jf103ft1:65,nthe:68,nullopt:[42,55],nullptr:[7,10,18,21,23,50,54,55,63,68],num:61,num_connect_retri:68,num_l:43,num_periods_to_run:42,num_pole_pair:7,num_seconds_to_run:[42,44,59,64],num_steps_per_iter:64,num_task:[51,64],num_touch:37,number:[1,2,3,7,9,10,14,15,17,18,21,23,24,27,32,33,37,38,40,42,43,46,53,54,55,57,58,60,61,65,67,68],number_of_link:23,nvs_flash_init:[67,68],o:[2,35,39],object:[7,9,10,11,13,22,43,44,47,51,57,60,61,62,63,65],occur:[22,61,63],off:[2,6,10,17,32,38,44,61,65],offset:[15,58,61],offset_i:15,offset_x:15,ofs:23,ofstream:23,ohm:[7,65],ok:61,oldest:10,on_connect:68,on_disconnect:68,on_got_ip:68,on_jpeg_fram:61,on_off_strong_det:32,on_receive_callback:55,on_response_callback:[54,55],onc:[12,17,18,21,22,61],once_flag:22,one:[2,9,10,18,21,22,30,42,43,54,55,58,60,63],oneshot:[4,35],oneshot_adc:5,oneshotadc:[5,12,41],onli:[2,7,12,13,17,18,21,22,24,41,44,50,55,57,58,60,61,62,63],oob:[57,58],open:[2,7,8,10,23,32,54,57,67,68],open_drain:[2,38],oper:[2,11,23,25,27,28,45,47,50,59,65],oppos:11,opposit:42,optim:[7,24,46],option:[3,5,6,7,10,12,14,15,18,21,37,41,42,43,44,49,53,54,55,58,61,62,64],order:[2,24,25,26,29,35,43,44,54],oreilli:57,org:[24,25,28,53,54,55,65],orient:[7,14],origin:23,oscil:[2,49],osr_128:2,osr_16:2,osr_2:2,osr_32:2,osr_4:2,osr_64:2,osr_8:2,ostream:10,ostringstream:13,other:[7,10,11,14,50,53,54,55,58,59,62,63,64,67],otherwis:[6,9,12,22,30,40,41,42,54,55,57,60,61,63,64,68],our:[42,53,54,55,64],out:[10,13,23,51,53,54,55,57,58,60,62,63,65],output:[2,7,8,10,17,22,23,24,25,27,28,30,37,38,40,42,44,47,49,51,58,59],output_cent:49,output_drive_mode_p0:38,output_invert:42,output_max:[7,49,59],output_min:[7,49,59],output_mod:2,output_rang:49,outputdrivemodep0:38,outputmod:2,outsid:[2,10,11],over:[2,6,20,23,39,42,52,54,55,61,64],overflow:[17,24],overhead:[14,22],overload:23,oversampl:2,oversampling_ratio:2,oversamplingratio:2,overstai:44,overth:2,overwrit:61,own:[3,14,18,21,30,38,40,53,54,55,67],owner:23,p0:38,p0_0:38,p0_1:38,p0_2:38,p0_3:38,p0_5:38,p1:38,p1_0:38,p1_1:38,p1_5:38,p1_6:38,p1_7:38,p1_8:38,p:[2,10,13,59],pack:12,packag:57,packet:[53,54,55,57,61],packet_:61,pad:12,page:[23,65],pair:[7,57,58],panel:37,param:[1,2,7,14,18,21,22,33,37,38,40,41,43,53,54,55,58,60,64,68],paramet:[1,2,3,5,6,7,9,10,11,12,14,15,19,22,23,24,25,27,28,30,32,33,37,38,40,41,42,43,44,45,47,49,50,53,54,55,57,58,59,60,61,63,64,65,67,68],parent:63,pars:[13,51,61],part:[6,15,32,37,65],parti:62,partit:23,partition_label:23,pass:[9,15,22,30,44,49],passiv:30,password:[30,57,67,68],pasv:30,pat:57,path:[23,30,61],paus:[14,61],payload:[57,58,61],payload_s:61,pdf:[2,18,33,38,58,60,65],pend:54,per:[1,2,3,7,18,21],perceiv:11,percent:42,percentag:[6,32,42],perform:[2,3,5,11,23,41,64],perhipher:42,period:[9,12,14,18,21,22,38,40,51,58,63],peripher:[6,17,32,34,42,43,57,60],peripheral_centr:57,peripheral_onli:[57,58],permiss:23,person:57,phase:[6,7],phase_induct:7,phase_resist:7,phone:[57,58],photo:58,pick:17,pico:41,pid:[7,32,35],pid_config:59,pin:[1,2,6,7,9,12,15,33,38,40,42,60,64],pin_bit_mask:2,pin_mask:40,pinout:7,pixel:[14,15,43,61],pixel_buffer_s:[14,15],place:[22,32],plai:[33,61],plan:65,platform:[44,64],play_hapt:32,playback:33,pleas:[10,11,13,28,33,63],plot:2,pn532:57,point:[11,17,23,24,27,32,35,37,42,45,46,50,54,55,57,66,68],pointer:[1,2,14,15,18,21,24,27,32,33,37,38,40,41,43,53,54,58,60,61,63,64,68],pokemon:13,pokemon_blu:13,pokemon_r:13,pokemon_yellow:13,polar:40,pole:7,poll:[12,18,21,38,40,58],pomax:45,pop:57,popul:55,port0:38,port1:38,port:[7,14,30,38,40,53,54,55,61],port_0_direction_mask:38,port_0_interrupt_mask:38,port_1_direction_mask:38,port_1_interrupt_mask:38,port_a:40,port_a_direction_mask:40,port_a_interrupt_mask:40,port_b:40,port_b_direction_mask:40,port_b_interrupt_mask:40,portmax_delai:2,portrait:[14,15],portrait_invert:14,porttick_period_m:[1,2,12,18,21,33,38,40,58],pos_typ:23,posit:[7,15,17,18,21,32,37,41,49],posix:[52,53],possibl:[2,6,14,49,57],post:57,post_cb:15,post_transfer_callback:14,poster:57,potenti:[3,24,30],power:[2,6,7,43,57],power_supply_voltag:[6,7],pranav:13,pre:[15,59,60],pre_cb:15,precis:60,preconfigur:33,predetermin:2,prefer:57,prefix:[2,23],prepend:44,present:[57,61],preset:33,press:[2,9,12,37],prevent:[14,59],previou:[10,42],previous:[6,7,49],primari:60,primarili:10,primary_data:60,print:[2,3,5,10,12,13,17,18,21,22,38,40,41,42,44,51,54,55,58,59,60,61,62,64,65,68],printf:[12,18,21,38,40,58],prior:[58,67,68],prioriti:[3,7,14,44,51,64],privat:10,process:[42,54,55,64],processor:[2,27,64],produc:11,product:[38,50,60,63,65],profil:32,programm:2,programmed_data:58,project:[6,10,30,60,61,67,68],prompt:10,prompt_fn:10,proper:[11,63],properli:[5,61],proport:59,protocol:[30,43,54,55,60],protocol_examples_common:10,prototyp:[22,37],provid:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,20,21,22,23,24,25,26,27,28,29,31,32,34,35,37,38,39,40,41,42,43,44,45,46,47,49,50,51,52,53,54,55,57,58,59,60,61,62,63,64,65,66,68],prt:53,pseudost:63,pub:22,publish:[9,22],pull:[2,38,40],pull_up_en:2,pulldown:9,pulldown_en:9,pullup:9,pullup_en:9,puls:[2,17,60],pulsed_high:2,pulsed_low:2,pulsing_strong_1:33,pulsing_strong_2:33,pure:[17,63],push:2,push_pul:2,push_push:38,put:58,pwm:[6,7,8,33,42],pwmanalog:33,py:41,python:51,q0:61,q0_tabl:61,q1:61,q1_tabl:61,q:[7,27,61],q_current_filt:7,q_factor:27,qt:41,quadhd_io_num:15,quadratur:17,quadwp_io_num:15,qualiti:27,quantiz:61,question:[10,13,42,58],queu:60,queue:[2,9,10,60],queue_siz:15,quickli:63,quit:58,quit_test:[12,18,21,40,58],quote_charact:13,r0:65,r1:[2,65],r25:65,r2:[2,65],r:[11,23,38,43,49,57,60,65],r_0:65,r_bright:38,r_down:38,r_led:38,r_scale:65,r_up:38,race:42,rad:7,radian:[7,17,18,21,50],radio:[57,58],radio_mac_addr:58,radiu:41,rainbow:[43,60],ram:14,ranav:13,random:57,rang:[1,6,11,18,21,23,25,27,32,34,35,41,47,48,65,67],range_mapp:49,rangemapp:[41,49],rate:[1,3,7,18,21,38,40,44],rate_limit:44,ratio:2,ration:45,raw:[1,2,5,7,12,18,21,41,45,53,57,58],rb:23,re:[10,12,18,21,33,53,54,55,60,63,65],reach:[33,54,58,63],read:[1,2,3,5,7,9,10,12,18,21,23,33,37,38,40,41,54,58,65],read_fn:[1,2,18,21,33,38,40,58],read_joystick:[12,41],read_mv:[5,12,41,65],read_mv_fn:65,read_raw:5,read_valu:13,readabl:[13,23],reader:[3,5,41],readthedoc:57,real:[22,33],realli:[13,62,63],realtim:33,reason:[62,64],receic:22,receiv:[2,15,53,54,55,58,61],receive_callback_fn:[53,54,55],receive_config:55,receiveconfig:55,recent:[2,3,7,12,18,21,41,59],recommend:[18,21,22,41],record:[57,58],rectangular:41,recurs:[23,63],recursive_directory_iter:23,recvfrom:[53,55],red:[11,13,43,44,60],redraw:14,reeiv:[],reepres:61,refer:35,reference_wrapp:32,refresh:14,reg:58,reg_addr:[1,12,18,21,33,38,40,58],regard:[18,21],regardless:41,region:2,regist:[1,2,9,18,21,22,33,37,38,40,58,61],registr:22,registri:22,reinit:54,reiniti:54,reistor:38,rel:49,relat:[10,42],releas:9,relev:[23,65],reli:63,reliabl:[18,21,54],remain:44,remot:[35,54,55,57],remote_control:57,remote_info:55,remov:[6,10,22,23],remove_publish:22,remove_subscrib:22,renam:23,render:[14,51],repeatedli:[60,64],replac:10,report:58,repres:[11,18,21,30,42,50,57,58,59,60,61],represent:11,request:[2,30,53,54,55,57,58,61],requir:[7,58],rescal:11,reserv:57,reset:[2,15,17,58,59,60],reset_fn:60,reset_pin:15,reset_st:59,reset_tick:60,resist:[7,65],resistor:[9,38,65],resistordividerconfig:65,resiz:[10,23,51,64],resolut:[42,60],resolution_hz:[43,60],resolv:30,reson:[33,34],resourc:[5,53,54,55,58,60],respect:[4,61,63],respond:[53,54,55],respons:[14,23,27,30,57,59,61],response_callback_fn:[53,54,55],response_s:[54,55],response_timeout:55,restart:63,restartselect:63,restrict:[18,21],result:[2,3,11,50,61],resum:14,ret:15,ret_stat:60,retri:[61,68],retriev:[3,12,37,41],return_to_center_with_det:32,return_to_center_with_detents_and_multiple_revolut:32,reusabl:[10,35],revers:[54,55],revolut:[17,18,21,32],rf:58,rf_activ:58,rf_get_msg:58,rf_intterupt:58,rf_put_msg:58,rf_user:58,rf_write:58,rfc:[57,61],rfid:[57,58],rgb:[11,43,60],rh:[11,50],right:[7,12,30,43,58],rise:[9,33,58,60],rising_edg:9,risk:24,rmdir:23,rmt:[35,43],rmt_bytes_encoder_config_t:60,rmt_channel_handle_t:60,rmt_clk_src_default:60,rmt_clock_source_t:60,rmt_encod:60,rmt_encode_state_t:60,rmt_encoder_handle_t:60,rmt_encoder_t:60,rmt_encoding_complet:60,rmt_encoding_mem_ful:60,rmt_encoding_reset:60,rmt_symbol_word_t:60,rmtencod:[43,60],robust:44,robustli:49,role:57,root:[23,30,63],root_list:23,root_menu:10,root_path:23,rotari:32,rotat:[7,14,15,18,21,32,33,34,43,50,60],round:46,routin:41,row:13,row_index:13,rpm:[7,18,21],rpm_to_rad:7,rstp:57,rt_fmt_str:44,rtcp:61,rtcp_packet:61,rtcp_port:61,rtcppacket:61,rtd:57,rtp:[33,61],rtp_jpeg_packet:61,rtp_packet:61,rtp_port:61,rtpjpegpacket:61,rtppacket:61,rtsp:[35,57],rtsp_client:61,rtsp_path:61,rtsp_port:61,rtsp_server:61,rtsp_session:61,rtspclient:61,rtspserver:61,rtspsession:61,run:[3,7,10,14,18,21,22,30,32,42,44,51],runtim:44,s2:[3,15],s3:[3,12],s:[2,7,8,9,10,11,13,18,21,22,30,32,38,40,41,42,43,44,49,51,55,60,62,63,64,65],s_isdir:23,safe:[42,59],same:[2,5,7,22,57,59],sampl:[1,2,3,7,10,18,21,24,25,27,28,58,59,65],sample_mv:[1,12],sample_r:1,sample_rate_hz:[3,65],sandbox:23,sar:2,sarch:[18,21],satisfi:63,satur:[11,59],sbu:[],scalar:50,scale:[7,47,50,59,65],scaler:47,scan:[2,61,68],scan_data:61,scenario:[67,68],scheme:7,scl:2,scl_io_num:[1,2,12,18,21,33,38,40,58],scl_pullup_en:[1,2,12,18,21,33,38,40,58],sclk:15,sclk_io_num:15,scottbez1:32,screen:15,sda_io_num:[1,2,12,18,21,33,38,40,58],sda_pullup_en:[1,2,12,18,21,33,38,40,58],sdp:61,search:[18,21],second:[1,2,3,7,18,21,25,26,35,38,40,42,44,50,58,61,64,65],secondari:14,seconds_per_minut:[18,21],seconds_since_start:51,section:[11,25,26,35],sectionimpl:28,secur:[57,67,68],security_manager_flag:57,security_manager_tk:57,see:[2,7,10,11,13,14,15,17,24,25,28,33,41,45,51,53,54,55,57,58,60,63,65,67,68],seek_end:23,seek_set:23,seekg:23,seem:[23,61],segment:14,sel:2,select:[2,3,12,30,33,43,57,63],select_bit_mask:2,select_librari:33,select_press:2,select_valu:2,send:[9,14,15,30,43,54,55,58,60,61],send_bright:43,send_command:15,send_config:[54,55],send_data:15,send_fram:61,send_request:61,send_rtcp_packet:61,send_rtp_packet:61,sendconfig:55,sender:[53,54,55],sender_info:[53,54,55],sendto:53,sens:7,sensor:[7,18,21,65],sensor_direct:7,sensorconcept:7,sensordirect:7,sent:[2,15,30,43,54,55,60,61],separ:[12,13,14,51],sequenc:[2,22,33,51,57,58,63],seri:[28,61,65],serial:[9,20,22,33,35,38,39,40,57,58,61],serializa:62,series_second_order_sect:[24,28],serizalizt:13,server:[31,35,52,53],server_address:[54,55,61],server_config:55,server_port:61,server_socket:[54,55],server_task:54,server_task_config:[54,55],server_task_fn:54,server_uri:61,servic:[2,57],session:[10,30,60,61],session_st:60,set:[2,6,7,9,10,15,22,33,38,40,41,42,43,46,47,49,51,53,54,55,57,58,60,61,63,65,67,68],set_al:43,set_analog_alert:2,set_ap_mac:68,set_calibr:41,set_config:59,set_deadzon:41,set_digital_alert:2,set_digital_output_mod:2,set_digital_output_valu:2,set_direct:[38,40],set_drawing_area:15,set_duti:42,set_encod:[43,60],set_fade_with_tim:42,set_histori:10,set_history_s:10,set_input_polar:40,set_interrupt:38,set_interrupt_mirror:40,set_interrupt_on_chang:40,set_interrupt_on_valu:40,set_interrupt_polar:40,set_label:15,set_log_level:22,set_met:15,set_mod:33,set_motion_control_typ:7,set_offset:15,set_payload:61,set_phase_st:6,set_phase_voltag:7,set_pin:[38,40],set_pixel:43,set_pull_up:40,set_pwm:6,set_receive_timeout:[53,54,55],set_record:58,set_session_log_level:61,set_verbos:44,set_vers:61,set_voltag:6,set_waveform:33,setactivechild:63,setcolor:10,setdeephistori:63,setinputhistori:10,setinputhistorys:10,setnocolor:10,setparentst:63,setpoint:[7,32],setshallowhistori:63,setter:[50,61],setup:[2,61],sever:[20,26,39],sftp:57,sgn:46,shaft:[7,18,21],shallow:63,shallow_history_st:63,shallowhistoryst:63,shape:47,share:57,shared_ptr:7,sharp_click:33,sheet:2,shield:12,shift:[43,47],shift_bi:43,shift_left:43,shift_right:43,shifter:47,shop:[38,60],short_local_nam:57,shorten:57,should:[6,7,10,11,12,14,15,23,24,27,40,41,42,43,50,53,54,55,59,60,61,63,64],shouldn:[23,44],show:[10,43,63],showcas:22,shown:44,shut:64,side:[6,31],sign:[17,46,49],signal:[2,12,14,24,25,27,28,33,43,59,60],signatur:64,similar:60,simpl:[0,5,9,22,23,29,30,44,57,59,62,65],simplefoc:7,simpler:[42,60],simpli:[2,3,10,18],simplifi:61,simultan:[10,57],sin:51,sinc:[2,17,18,21,22,23,38,60,61,64,65],sine_pwm:[],singl:[2,5,17,32,43,44],single_unit_1:[3,65],single_unit_2:3,singleton:[22,23],sinusoid:7,sip:57,sixteen:1,size:[1,9,10,12,14,23,33,51,54,55,57,58,60,61,62,64,65],size_t:[1,2,3,7,9,10,12,13,14,15,17,18,21,23,24,25,27,28,33,38,40,42,43,44,51,53,54,55,60,61,62,64,68],sizeof:[1,2,12,15,18,21,33,38,40,58,60,61],sk6085:60,sk6805:60,sk6805_10mhz_bytes_encoder_config:60,sk6805_freq_hz:43,sk6812:43,sleep:[1,2,3,5,7,12,17,18,21,22,33,38,40,41,42,43,44,51,58,59,60,63,64,65],sleep_for:[3,9,15,22,42,43,44,51,54,55,59,61,63,64,68],sleep_until:64,slope:47,slot:33,slow:5,small:[32,47],smart:57,smartknob:32,smb:57,snap:32,snprintf:64,so:[1,2,5,7,10,12,13,15,17,18,21,22,23,26,30,32,33,35,38,40,43,49,51,58,59,60,61,63,64,65],so_recvtimeo:[53,54,55],so_reuseaddr:[53,54,55],so_reuseport:[53,54,55],sockaddr:53,sockaddr_in6:53,sockaddr_in:53,sockaddr_storag:[53,54,55],socket:[30,35,52,61],socket_fd:[53,54,55],soft_bump:33,soft_fuzz:33,softwar:[2,14,22],software_rotation_en:[14,15],some:[1,2,7,10,12,18,20,21,22,23,26,32,33,38,40,44,46,51,53,57,58,60,63,64],someth:[14,64],somewhat:32,sos_filt:28,sosfilt:[25,28],sourc:[55,60],source_address:53,sp:57,sp_hash_c192:57,sp_hash_c256:57,sp_hash_r256:57,sp_random_r192:57,space:[7,11,23,32,43,60],space_vector_pwm:7,sparignli:49,sparkfun:12,spawn:[18,21,30,61,63,64],spawn_endevent_ev:63,spawn_event1_ev:63,spawn_event2_ev:63,spawn_event3_ev:63,spawn_event4_ev:63,specfici:1,special:[19,33,38,60],specif:[11,32,34,37,61,63,64],specifi:[18,21,23,32,44,55,61],speed:[7,18,21,42,54],speed_mod:42,spi2_host:15,spi:[15,18,21,40],spi_bus_add_devic:15,spi_bus_config_t:15,spi_bus_initi:15,spi_device_interface_config_t:15,spi_dma_ch_auto:15,spi_num:15,spi_queue_s:15,spic:15,spics_io_num:15,spike:47,sporad:5,spot:7,sps128:1,sps1600:1,sps16:1,sps2400:1,sps250:1,sps32:1,sps3300:1,sps475:1,sps490:1,sps64:1,sps860:1,sps8:1,sps920:1,squar:50,sr:57,ssid:[57,58,67,68],st25dv04k:58,st25dv:[35,56],st25dv_read:58,st25dv_write:58,st7789_defin:15,st7789v_8h_sourc:15,st:[23,58],st_mode:23,st_size:23,sta:[35,66],stabl:57,stack:[9,51,64],stack_size_byt:[1,2,7,12,18,21,33,38,40,43,51,54,55,58,60,64],stackoverflow:[23,58],stand:7,standalon:[20,39],standard:[23,44,49,61],star:33,start:[1,2,3,5,7,9,10,12,14,15,17,18,21,22,30,32,33,38,40,41,42,43,44,50,51,52,54,55,58,59,60,61,63,64,65],start_fast_transfer_mod:58,start_fram:43,start_receiv:55,startup:[18,21],stat:[23,51],state:[6,9,12,18,21,22,24,25,27,28,33,35,37,38,40,51,58,59,60],state_a:6,state_b:6,state_bas:63,state_c:6,state_machin:63,state_of_charg:22,statebas:63,static_cast:[2,44,60],station:[35,66,67],statist:2,statistics_en:2,statu:[2,58],std:[1,2,3,5,7,9,10,12,13,14,15,17,18,21,22,28,30,32,33,37,38,40,41,42,43,44,45,49,50,51,52,53,54,55,57,58,59,60,61,62,63,64,65,67,68],stdby:7,stdin:63,stdin_out:10,stdout:63,steinhart:65,step:64,still:41,stop:[1,2,3,5,7,12,14,17,18,21,22,30,32,33,38,40,41,42,43,51,54,55,58,59,60,61,63,65,68],stop_fast_transfer_mod:58,storag:[10,53],store:[10,12,15,23,29,47,57,58,61,65],str:13,strcutur:15,stream:[10,13,61],streamer:61,strength:32,strictli:62,string:[9,10,13,22,23,44,51,53,54,55,57,61,62,64,67,68],string_view:[15,23,30,44,54,55,57,58,61,64],strip:[35,60],strong:32,strong_buzz:33,strong_click:33,strongli:62,struct:[1,2,3,5,6,7,9,11,12,14,17,18,21,22,23,25,27,29,32,33,37,38,40,41,42,43,44,45,47,49,51,53,54,55,57,58,59,60,61,62,64,65,67,68],structur:[1,2,7,12,14,15,22,33,37,38,40,41,42,45,47,53,54,55,57,59,63,67,68],sub:[10,22],sub_menu:10,sub_sub_menu:10,subclass:[28,53,61,63],subdirectori:23,submenu:10,submodul:10,subscib:22,subscrib:[9,22],subscript:22,subsequ:[2,57],subset:12,substat:63,subsub:10,subsubmenu:10,subsystem:[3,5,14,42],subtract:50,subystem:68,succeed:[],success:[2,61],successfulli:[17,22,53,54,55,60,61,62],suffix:44,suggest:60,suit:11,super_mario_1:13,super_mario_3:13,super_mario_bros_1:13,super_mario_bros_3:13,suppli:[6,65],supply_mv:65,support:[2,7,10,11,12,17,19,23,33,38,43,52,57,58,61],sure:[7,61],swap:37,swap_xi:37,symlink:[2,33],symmetr:47,syst_address:58,system:[10,13,22,35,51,58,62,63,64,65],sytl:62,t5t:58,t:[1,2,3,5,7,12,13,15,17,18,21,22,23,33,38,40,41,42,43,44,45,47,49,50,51,54,55,57,58,59,60,64,65],t_0:65,ta:12,tabl:[2,23,51,57,61,65],tag:[44,57,58],take:[5,23],taken:23,talk:[38,43],target:[7,68],task1:22,task2:22,task:[1,2,3,5,7,9,12,14,17,18,21,22,30,32,33,35,38,40,41,42,43,54,55,58,59,60,61,63,65],task_1_fn:22,task_2_fn:22,task_callback:51,task_config:55,task_fn:[3,5,12,17,18,21,33,38,40,41,43,51,58,59,60,63,64,65],task_id:51,task_iter:64,task_monitor:51,task_nam:[51,64],task_prior:3,task_stack_size_byt:[9,51],taskmonitor:51,tb:12,tcp:[35,52,61],tcp_socket:54,tcpclientsess:54,tcpobex:57,tcpserver:54,tcpsocket:[53,54,61],tcptransmitconfig:54,tdata:62,tdk:65,tdown:12,tear:[53,54,55,64],teardown:61,tel:57,tell:[43,60],tellg:23,telnet:57,temp:65,temperatur:65,temperature_celsiu:22,templat:[7,17,19,23,25,28,30,32,44,45,49,50,64],termin:[10,63,64],test2:23,test:[3,7],test_dir:23,test_fil:23,test_start:64,texa:[2,33],text:[57,58],text_record:58,tflite:15,tft_driver:15,tft_espi:15,tftp:57,th:[14,29],than:[6,10,14,41,44,58,61],thank:10,thei:[10,12,32,61,63,64],them:[2,11,12,22,47,58,60,61,63,64],therefor:[3,5,10,11,18,21,33,49,64],thermistor:35,thermistor_ntcg_en:65,thi:[1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,21,22,23,24,30,32,33,35,38,40,41,42,43,44,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],thin:47,thing:51,third:62,this_thread:[3,9,15,22,42,43,44,51,54,55,59,61,63,64,68],those:[22,38,44,51,63],though:22,thread:[22,30,32,42,51,54,55,59,61,64],threshold:2,through:[2,7,32,33,43,49,60,63],throughput:3,ti:[2,33],tick:63,tickselect:63,time:[2,5,6,12,18,21,22,23,33,38,40,42,43,44,51,55,58,59,60,63,64,65,68],time_point:23,time_t:[23,30],time_to_l:[53,54,55],timeout:[53,54,55,64],timer:42,tinys3:[7,60],tk:57,tkip:57,tleft:12,tloz_links_awaken:13,tloz_links_awakening_dx:13,tlv:58,tm:51,tmc6300:7,tname:62,tnf:57,to_time_t:[23,30],toler:65,tone:43,too:61,top:63,topic:[9,22],torqu:7,torque_control:7,torquecontroltyp:7,total:[17,23],total_spac:23,touch:37,touchpad:[35,36,57],touchpad_input:37,touchpad_read:37,touchpad_read_fn:37,touchpadinput:37,tp:[23,30],tpd_commercial_ntc:65,trace:51,track:59,transact:60,transaction_queue_depth:60,transceiv:35,transfer:[15,26,31,35,58],transfer_funct:29,transferfunct:[28,29],transform:[7,22],transit:63,transition_click_1:33,transition_hum_1:33,transmiss:[54,60],transmit:[22,43,53,54,55,57],transmit_config:54,transmitconfig:[],transmitt:60,transport:61,trapezoid_120:[],trapezoid_150:[],tree:[55,60,63],trigger:[2,5,32,33,40,58],tright:12,trim_polici:13,trim_whitespac:13,triple_click:33,truncat:10,ts:33,tselect:12,tstart:12,ttl:[53,54,55],tup:12,tupl:65,turn:[2,44],tvalu:62,two:[1,11,12,14,38,40,44,51,60],twothird:1,tx:57,tx_config:[],tx_power_level:57,type5tagtyp:58,type:[1,2,4,7,9,10,12,14,17,18,20,21,22,23,26,32,33,35,37,38,39,40,41,43,44,50,53,54,55,57,58,60,61,62,64,65,68],type_specif:61,typedef:[1,2,7,9,10,14,18,21,22,33,37,38,40,41,43,53,54,55,58,60,64,65,68],typenam:[23,30,44,45,49,50],u:[50,57],ua:6,uart:10,uart_serial_plott:2,ub:6,uc:6,ud:7,udp:[35,52,61],udp_multicast:55,udp_socket:55,udpserv:55,udpsocket:[53,55],uic:[57,58],uint16_t:[1,14,15,30,37,38,57,58,60],uint32_t:[2,12,14,15,42,57,58,61,62],uint64_t:[57,58],uint8_t:[1,2,9,12,14,15,18,21,22,33,37,38,40,43,44,53,54,55,57,58,60,62,67,68],uint:60,unabl:30,unbound:32,unbounded_no_det:32,uncalibr:[12,41],uncent:49,unchang:57,under:[17,23],underflow:17,understand:57,unicast:55,uniqu:[54,61,64],unique_lock:[1,2,3,5,7,12,17,18,21,22,33,38,40,41,42,43,54,58,59,60,63,64,65],unique_ptr:[51,54,61,64],unit:[0,3,5,7,12,17,23,24,41,50,65],univers:10,unknown:[57,68],unless:22,unlimit:10,unlink:23,unmap:41,unord:55,unordered_map:61,unregist:37,unreli:55,until:[2,10,22,23,32,33,42,43,54,55,60,63,64],unus:[12,17,32],unweight:45,unwind:63,up:[2,3,10,12,14,17,23,33,38,40,47,54,58,59,61,63,64],upat:14,updat:[6,7,9,12,14,18,21,24,25,27,28,32,38,40,41,42,44,47,49,50,53,58,59,63],update_detent_config:32,update_period:[7,14,18,21],upper:[15,65],uq:7,uri:[57,58,61],uri_record:58,urn:57,urn_epc:57,urn_epc_id:57,urn_epc_pat:57,urn_epc_raw:57,urn_epc_tag:57,urn_nfc:57,us:[1,2,3,5,6,7,8,9,10,11,12,14,15,17,18,19,21,22,23,24,25,30,31,32,33,34,38,40,41,42,43,44,45,47,49,51,52,53,54,55,57,58,60,61,62,63,64,65],usag:[10,13],used_spac:23,user:[2,3,5,8,9,10,15,17,18,21,30,32,33,38,40,60,61,64],usernam:30,ust:22,util:[23,41,44,46,50,51,53,57,58],uuid:57,uuids_128_bit_complet:57,uuids_128_bit_parti:57,uuids_16_bit_complet:57,uuids_16_bit_parti:57,uuids_32_bit_complet:57,uuids_32_bit_parti:57,v:[7,11,49,50],v_in:65,val_mask:40,valid:[30,33,43,53,54,55,61],valu:[1,2,3,5,9,11,12,13,14,17,18,21,23,27,32,33,38,40,41,42,43,44,45,46,47,49,50,57,58,59,60,61,62,64,65],vari:32,variabl:[15,41,44,64],varieti:2,variou:43,ve:[10,23,64],vector2d:[35,45,48],vector2f:41,vector:[2,3,5,7,9,12,13,22,23,27,41,42,43,50,51,53,54,55,57,61,62,64,65],veloc:[7,18,21],velocity_filt:[7,18,21],velocity_filter_fn:[18,21],velocity_limit:7,velocity_openloop:7,velocity_pid_config:7,veloicti:7,veolciti:[18,21],verbos:[1,2,3,5,6,7,9,12,14,17,18,21,22,32,33,37,38,40,41,42,43,54,55,58,59,60,61,63,64,65,67,68],version:[10,50,61],via:[23,33,38,40],vibe:33,vibrat:[32,33],video:[14,61],view:[54,55,57],vio:7,virtual:[12,63],visual:51,volt:[2,6],voltag:[1,2,3,5,6,7,8,22,65],voltage_limit:6,vram0:14,vram1:14,vram:14,vram_size_byt:14,vram_size_px:14,vtaskgetinfo:51,w:[23,33,44,49],wa:[2,3,5,6,9,10,12,15,17,18,21,22,30,41,53,54,55,60,61,63,64],wai:[1,2,3,5,7,10,12,13,17,18,21,23,32,33,38,40,41,43,57,58,59,60,62,63,64,65],wait:[22,32,54,55,64],wait_for:[1,3,5,12,17,18,21,22,33,38,40,41,42,43,54,58,59,60,63,64],wait_for_respons:[54,55],wait_tim:42,wait_until:[2,7,64,65],want:[1,2,3,5,7,10,12,14,17,18,21,22,32,33,38,40,41,42,43,51,54,55,58,59,60,64,65],warn:[1,2,3,5,6,7,9,12,14,17,18,21,22,23,33,37,38,40,41,42,43,44,54,55,58,59,60,61,64,65,67,68],warn_rate_limit:44,watch:57,water:51,wave:47,waveform:33,we:[1,2,6,7,10,12,18,21,22,23,32,33,38,40,42,43,53,54,55,58,60,63,64,65],weak:32,webgm:63,weight:45,weightedconfig:45,welcom:44,well:[2,12,20,22,26,28,33,47,51,54,57,58,61,63,64],well_known:57,wep:57,were:[6,10,41,53,54,55,59,64],what:[5,6,22,60,63],whatev:[38,40],whe:68,when:[1,2,3,5,7,10,12,15,17,18,19,21,22,32,33,38,40,41,43,49,53,54,55,58,59,60,61,62,63,64,65,68],whenev:63,where:[8,17,32,51,55,63,65],whether:[3,9,12,14,18,21,23,42,43,49,53,54,55,60,61,64,68],which:[1,2,3,5,7,8,9,10,11,12,13,14,18,21,22,23,24,25,26,27,32,33,34,38,39,40,42,43,44,45,46,49,50,51,54,55,57,58,60,61,63,64,65,67,68],who:15,whole:[61,63],wi:[67,68],width:[14,15,32,61],wifi:[35,57,58],wifi_ap:67,wifi_record:58,wifi_sta:68,wifiap:67,wifiauthenticationtyp:57,wificonfig:57,wifiencryptiontyp:57,wifista:68,wiki:[24,25,28,53,54,55,65],wikipedia:[17,24,25,28,53,54,55,65],wind:59,window_size_byt:[3,65],windup:59,wire:60,wireless:58,wish:[10,12],witdth:17,within:[11,18,20,21,22,32,44,49,55,64,65],without:[2,3,7,10,32,51,58,60,61],work:[7,9,10,23,32,51,61,64],world:10,worri:65,would:[17,22,63,64],wpa2:57,wpa2_enterpris:57,wpa2_person:57,wpa:57,wpa_enterpris:57,wpa_person:57,wpa_wpa2_person:57,wrap:[6,17,22,38,60],wrapper:[3,5,9,10,13,14,23,37,41,42,44,45,47,60,62,63],write:[1,2,7,10,12,14,15,18,21,23,27,33,38,40,43,58],write_fn:[1,2,18,21,33,38,40,43,58],write_row:13,written:[43,57,58,63],wrote:[13,23],ws2811:43,ws2812:43,ws2812_10mhz_bytes_encoder_config:60,ws2812_freq_hz:60,ws2812b:60,ws2813:43,www:[2,24,28,33,57,58],x1:50,x2:50,x:[2,10,12,15,24,37,38,40,41,50,51,58,61],x_calibr:[12,41],x_mv:[1,2,12,41],xe:15,xml:30,xml_in:30,xqueuecreat:2,xqueuerec:2,xs:15,y1:50,y2:50,y:[2,12,15,24,37,41,44,47,50,61,67,68],y_calibr:[12,41],y_mv:[1,2,12,41],ye:[15,68],yellow:[13,44],yet:[7,18,21,31,64],yield:60,you:[3,7,10,12,13,14,17,22,23,42,43,44,47,49,51,58,59,60,61,62,63,67,68],your:[22,44,51],yourself:63,ys:15,z:17,zelda1:13,zelda2:13,zelda:13,zelda_2:13,zero:[7,17,43,49,58,65],zero_electric_offset:7},titles:["ADC Types","ADS1x15 I2C ADC","ADS7138 I2C ADC","Continuous ADC","ADC APIs","Oneshot ADC","BLDC Driver","BLDC Motor","BLDC APIs","Button APIs","Command Line Interface (CLI) APIs","Color APIs","Controller APIs","CSV APIs","Display","Display Drivers","Display APIs","ABI Encoder","AS5600 Magnetic Encoder","Encoder Types","Encoder APIs","MT6701 Magnetic Encoder","Event Manager APIs","File System APIs","Biquad Filter","Butterworth Filter","Filter APIs","Lowpass Filter","Second Order Sections (SoS) Filter","Transfer Function API","FTP Server","FTP APIs","BLDC Haptics","DRV2605 Haptic Motor Driver","Haptics APIs","ESPP Documentation","Input APIs","Touchpad Input","AW9523 I/O Expander","IO Expander APIs","MCP23x17 I/O Expander","Joystick APIs","LED APIs","LED Strip APIs","Logging APIs","Bezier","Fast Math","Gaussian","Math APIs","Range Mapper","Vector2d","Monitoring APIs","Network APIs","Sockets","TCP Sockets","UDP Sockets","NFC APIs","NDEF","ST25DV","PID APIs","Remote Control Transceiver (RMT)","RTSP APIs","Serialization APIs","State Machine APIs","Task APIs","Thermistor APIs","WiFi APIs","WiFi Access Point (AP)","WiFi Station (STA)"],titleterms:{"1":[32,43,60],"2":32,"class":[1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,21,22,23,24,25,27,28,30,32,33,37,38,40,41,42,43,44,45,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],"function":[29,30],"long":64,abi:17,abiencod:17,access:67,adc:[0,1,2,3,4,5,41,65],ads1x15:1,ads7138:2,alpaca:62,analog:12,ap:67,apa102:43,api:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68],as5600:18,aw9523:38,basic:[32,44,51,59,64],bench:63,bezier:45,biquad:24,bldc:[6,7,8,32],box:15,breath:42,butterworth:25,button:9,buzz:32,cli:10,click:32,client:[54,55,61],color:11,command:10,complex:[13,59,62,63],config:15,continu:3,control:[12,60],csv:13,data:60,de:62,devic:63,digit:12,displai:[14,15,16],document:35,driver:[6,15,33],drv2605:33,encod:[17,18,19,20,21,60],esp32:15,espp:35,event:22,exampl:[1,2,3,5,7,9,10,12,13,15,17,18,21,22,23,32,33,38,40,41,42,43,44,51,54,55,58,59,60,61,62,63,64,65,67,68],expand:[38,39,40],fast:46,file:[0,1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,19,21,22,23,24,25,27,28,29,30,32,33,37,38,40,41,42,43,44,45,46,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],filesystem:23,filter:[24,25,26,27,28],format:44,ftp:[30,31],gaussian:47,gener:63,get_latest_info:51,haptic:[32,33,34],header:[0,1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,19,21,22,23,24,25,27,28,29,30,32,33,37,38,40,41,42,43,44,45,46,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],hfsm:63,i2c:[1,2,12],i:[38,40],ili9341:15,info:[23,64],input:[36,37],interfac:10,io:39,joystick:41,kit:15,led:[42,43],line:10,linear:[17,42],log:44,logger:44,lowpass:27,machin:63,macro:[10,13,62,63],magnet:[18,21],manag:22,mani:64,mapper:49,math:[46,48],mcp23x17:40,monitor:51,motor:[7,33],mt6701:21,multicast:55,ndef:57,network:52,newlib:23,nfc:56,o:[38,40],oneshot:[5,10],order:28,pid:59,plai:32,point:67,posix:23,rang:49,reader:13,real:63,refer:[0,1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,19,21,22,23,24,25,27,28,29,30,32,33,37,38,40,41,42,43,44,45,46,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],remot:60,request:64,respons:[54,55],rmt:60,rotat:17,rtsp:61,run:[63,64],s3:15,second:28,section:28,serial:62,server:[30,54,55,61],so:28,socket:[53,54,55],spi:43,st25dv:58,st7789:15,sta:68,state:63,station:68,std:23,stop:64,strip:43,structur:62,system:23,task:[51,64],tcp:54,test:63,thermistor:65,thread:44,touchpad:37,transceiv:60,transfer:29,transmit:60,ttgo:15,type:[0,19],udp:55,union:[57,58],usag:[7,32],valid:65,vector2d:50,verbos:44,via:43,wifi:[66,67,68],writer:13,wrover:15,ws2812:60}}) \ No newline at end of file +Search.setIndex({docnames:["adc/adc_types","adc/ads1x15","adc/ads7138","adc/continuous_adc","adc/index","adc/oneshot_adc","bldc/bldc_driver","bldc/bldc_motor","bldc/index","button","cli","color","controller","csv","display/display","display/display_drivers","display/index","encoder/abi_encoder","encoder/as5600","encoder/encoder_types","encoder/index","encoder/mt6701","event_manager","file_system","filters/biquad","filters/butterworth","filters/index","filters/lowpass","filters/sos","filters/transfer_function","ftp/ftp_server","ftp/index","haptics/bldc_haptics","haptics/drv2605","haptics/index","index","input/index","input/touchpad_input","io_expander/aw9523","io_expander/index","io_expander/mcp23x17","joystick","led","led_strip","logger","math/bezier","math/fast_math","math/gaussian","math/index","math/range_mapper","math/vector2d","monitor","network/index","network/socket","network/tcp_socket","network/udp_socket","nfc/index","nfc/ndef","nfc/st25dv","pid","rmt","rtsp","serialization","state_machine","task","thermistor","wifi/index","wifi/wifi_ap","wifi/wifi_sta"],envversion:{"sphinx.domains.c":2,"sphinx.domains.changeset":1,"sphinx.domains.citation":1,"sphinx.domains.cpp":5,"sphinx.domains.index":1,"sphinx.domains.javascript":2,"sphinx.domains.math":2,"sphinx.domains.python":3,"sphinx.domains.rst":2,"sphinx.domains.std":2,"sphinx.ext.todo":2,sphinx:56},filenames:["adc/adc_types.rst","adc/ads1x15.rst","adc/ads7138.rst","adc/continuous_adc.rst","adc/index.rst","adc/oneshot_adc.rst","bldc/bldc_driver.rst","bldc/bldc_motor.rst","bldc/index.rst","button.rst","cli.rst","color.rst","controller.rst","csv.rst","display/display.rst","display/display_drivers.rst","display/index.rst","encoder/abi_encoder.rst","encoder/as5600.rst","encoder/encoder_types.rst","encoder/index.rst","encoder/mt6701.rst","event_manager.rst","file_system.rst","filters/biquad.rst","filters/butterworth.rst","filters/index.rst","filters/lowpass.rst","filters/sos.rst","filters/transfer_function.rst","ftp/ftp_server.rst","ftp/index.rst","haptics/bldc_haptics.rst","haptics/drv2605.rst","haptics/index.rst","index.rst","input/index.rst","input/touchpad_input.rst","io_expander/aw9523.rst","io_expander/index.rst","io_expander/mcp23x17.rst","joystick.rst","led.rst","led_strip.rst","logger.rst","math/bezier.rst","math/fast_math.rst","math/gaussian.rst","math/index.rst","math/range_mapper.rst","math/vector2d.rst","monitor.rst","network/index.rst","network/socket.rst","network/tcp_socket.rst","network/udp_socket.rst","nfc/index.rst","nfc/ndef.rst","nfc/st25dv.rst","pid.rst","rmt.rst","rtsp.rst","serialization.rst","state_machine.rst","task.rst","thermistor.rst","wifi/index.rst","wifi/wifi_ap.rst","wifi/wifi_sta.rst"],objects:{"":[[63,0,1,"c.MAGIC_ENUM_NO_CHECK_SUPPORT","MAGIC_ENUM_NO_CHECK_SUPPORT"],[13,0,1,"c.__gnu_linux__","__gnu_linux__"],[62,0,1,"c.__gnu_linux__","__gnu_linux__"],[10,0,1,"c.__linux__","__linux__"],[57,1,1,"_CPPv4N19PhonyNameDueToError3rawE","PhonyNameDueToError::raw"],[58,1,1,"_CPPv4N19PhonyNameDueToError3rawE","PhonyNameDueToError::raw"],[17,2,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoderE","espp::AbiEncoder"],[17,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder10AbiEncoderERK6Config","espp::AbiEncoder::AbiEncoder"],[17,4,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder10AbiEncoderERK6Config","espp::AbiEncoder::AbiEncoder::config"],[17,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder10AbiEncoderERK6Config","espp::AbiEncoder::AbiEncoder::type"],[17,2,1,"_CPPv4N4espp10AbiEncoder6ConfigE","espp::AbiEncoder::Config"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config6a_gpioE","espp::AbiEncoder::Config::a_gpio"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config6b_gpioE","espp::AbiEncoder::Config::b_gpio"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config21counts_per_revolutionE","espp::AbiEncoder::Config::counts_per_revolution"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config10high_limitE","espp::AbiEncoder::Config::high_limit"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config6i_gpioE","espp::AbiEncoder::Config::i_gpio"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config9log_levelE","espp::AbiEncoder::Config::log_level"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config9low_limitE","espp::AbiEncoder::Config::low_limit"],[17,1,1,"_CPPv4N4espp10AbiEncoder6Config13max_glitch_nsE","espp::AbiEncoder::Config::max_glitch_ns"],[17,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoderE","espp::AbiEncoder::T"],[17,3,1,"_CPPv4N4espp10AbiEncoder5clearEv","espp::AbiEncoder::clear"],[17,3,1,"_CPPv4N4espp10AbiEncoder9get_countEv","espp::AbiEncoder::get_count"],[17,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_degreesENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_degrees"],[17,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_degreesENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_degrees::type"],[17,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_radiansENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_radians"],[17,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_radiansENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_radians::type"],[17,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder15get_revolutionsENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_revolutions"],[17,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder15get_revolutionsENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_revolutions::type"],[17,3,1,"_CPPv4N4espp10AbiEncoder5startEv","espp::AbiEncoder::start"],[17,3,1,"_CPPv4N4espp10AbiEncoder4stopEv","espp::AbiEncoder::stop"],[17,3,1,"_CPPv4N4espp10AbiEncoderD0Ev","espp::AbiEncoder::~AbiEncoder"],[1,2,1,"_CPPv4N4espp7Ads1x15E","espp::Ads1x15"],[1,2,1,"_CPPv4N4espp7Ads1x1513Ads1015ConfigE","espp::Ads1x15::Ads1015Config"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1015Config14device_addressE","espp::Ads1x15::Ads1015Config::device_address"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1015Config4gainE","espp::Ads1x15::Ads1015Config::gain"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1015Config9log_levelE","espp::Ads1x15::Ads1015Config::log_level"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1015Config4readE","espp::Ads1x15::Ads1015Config::read"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1015Config11sample_rateE","espp::Ads1x15::Ads1015Config::sample_rate"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1015Config5writeE","espp::Ads1x15::Ads1015Config::write"],[1,6,1,"_CPPv4N4espp7Ads1x1511Ads1015RateE","espp::Ads1x15::Ads1015Rate"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate6SPS128E","espp::Ads1x15::Ads1015Rate::SPS128"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate7SPS1600E","espp::Ads1x15::Ads1015Rate::SPS1600"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate7SPS2400E","espp::Ads1x15::Ads1015Rate::SPS2400"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate6SPS250E","espp::Ads1x15::Ads1015Rate::SPS250"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate7SPS3300E","espp::Ads1x15::Ads1015Rate::SPS3300"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate6SPS490E","espp::Ads1x15::Ads1015Rate::SPS490"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1015Rate6SPS920E","espp::Ads1x15::Ads1015Rate::SPS920"],[1,2,1,"_CPPv4N4espp7Ads1x1513Ads1115ConfigE","espp::Ads1x15::Ads1115Config"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1115Config14device_addressE","espp::Ads1x15::Ads1115Config::device_address"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1115Config4gainE","espp::Ads1x15::Ads1115Config::gain"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1115Config9log_levelE","espp::Ads1x15::Ads1115Config::log_level"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1115Config4readE","espp::Ads1x15::Ads1115Config::read"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1115Config11sample_rateE","espp::Ads1x15::Ads1115Config::sample_rate"],[1,1,1,"_CPPv4N4espp7Ads1x1513Ads1115Config5writeE","espp::Ads1x15::Ads1115Config::write"],[1,6,1,"_CPPv4N4espp7Ads1x1511Ads1115RateE","espp::Ads1x15::Ads1115Rate"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate6SPS128E","espp::Ads1x15::Ads1115Rate::SPS128"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate5SPS16E","espp::Ads1x15::Ads1115Rate::SPS16"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate6SPS250E","espp::Ads1x15::Ads1115Rate::SPS250"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate5SPS32E","espp::Ads1x15::Ads1115Rate::SPS32"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate6SPS475E","espp::Ads1x15::Ads1115Rate::SPS475"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate5SPS64E","espp::Ads1x15::Ads1115Rate::SPS64"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate4SPS8E","espp::Ads1x15::Ads1115Rate::SPS8"],[1,7,1,"_CPPv4N4espp7Ads1x1511Ads1115Rate6SPS860E","espp::Ads1x15::Ads1115Rate::SPS860"],[1,3,1,"_CPPv4N4espp7Ads1x157Ads1x15ERK13Ads1015Config","espp::Ads1x15::Ads1x15"],[1,3,1,"_CPPv4N4espp7Ads1x157Ads1x15ERK13Ads1115Config","espp::Ads1x15::Ads1x15"],[1,4,1,"_CPPv4N4espp7Ads1x157Ads1x15ERK13Ads1015Config","espp::Ads1x15::Ads1x15::config"],[1,4,1,"_CPPv4N4espp7Ads1x157Ads1x15ERK13Ads1115Config","espp::Ads1x15::Ads1x15::config"],[1,1,1,"_CPPv4N4espp7Ads1x1515DEFAULT_ADDRESSE","espp::Ads1x15::DEFAULT_ADDRESS"],[1,6,1,"_CPPv4N4espp7Ads1x154GainE","espp::Ads1x15::Gain"],[1,7,1,"_CPPv4N4espp7Ads1x154Gain5EIGHTE","espp::Ads1x15::Gain::EIGHT"],[1,7,1,"_CPPv4N4espp7Ads1x154Gain4FOURE","espp::Ads1x15::Gain::FOUR"],[1,7,1,"_CPPv4N4espp7Ads1x154Gain3ONEE","espp::Ads1x15::Gain::ONE"],[1,7,1,"_CPPv4N4espp7Ads1x154Gain7SIXTEENE","espp::Ads1x15::Gain::SIXTEEN"],[1,7,1,"_CPPv4N4espp7Ads1x154Gain3TWOE","espp::Ads1x15::Gain::TWO"],[1,7,1,"_CPPv4N4espp7Ads1x154Gain9TWOTHIRDSE","espp::Ads1x15::Gain::TWOTHIRDS"],[1,8,1,"_CPPv4N4espp7Ads1x157read_fnE","espp::Ads1x15::read_fn"],[1,3,1,"_CPPv4N4espp7Ads1x159sample_mvEi","espp::Ads1x15::sample_mv"],[1,4,1,"_CPPv4N4espp7Ads1x159sample_mvEi","espp::Ads1x15::sample_mv::channel"],[1,8,1,"_CPPv4N4espp7Ads1x158write_fnE","espp::Ads1x15::write_fn"],[2,2,1,"_CPPv4N4espp7Ads7138E","espp::Ads7138"],[2,3,1,"_CPPv4N4espp7Ads71387Ads7138ERK6Config","espp::Ads7138::Ads7138"],[2,4,1,"_CPPv4N4espp7Ads71387Ads7138ERK6Config","espp::Ads7138::Ads7138::config"],[2,6,1,"_CPPv4N4espp7Ads713810AlertLogicE","espp::Ads7138::AlertLogic"],[2,7,1,"_CPPv4N4espp7Ads713810AlertLogic11ACTIVE_HIGHE","espp::Ads7138::AlertLogic::ACTIVE_HIGH"],[2,7,1,"_CPPv4N4espp7Ads713810AlertLogic10ACTIVE_LOWE","espp::Ads7138::AlertLogic::ACTIVE_LOW"],[2,7,1,"_CPPv4N4espp7Ads713810AlertLogic11PULSED_HIGHE","espp::Ads7138::AlertLogic::PULSED_HIGH"],[2,7,1,"_CPPv4N4espp7Ads713810AlertLogic10PULSED_LOWE","espp::Ads7138::AlertLogic::PULSED_LOW"],[2,6,1,"_CPPv4N4espp7Ads713811AnalogEventE","espp::Ads7138::AnalogEvent"],[2,7,1,"_CPPv4N4espp7Ads713811AnalogEvent6INSIDEE","espp::Ads7138::AnalogEvent::INSIDE"],[2,7,1,"_CPPv4N4espp7Ads713811AnalogEvent7OUTSIDEE","espp::Ads7138::AnalogEvent::OUTSIDE"],[2,6,1,"_CPPv4N4espp7Ads71386AppendE","espp::Ads7138::Append"],[2,7,1,"_CPPv4N4espp7Ads71386Append10CHANNEL_IDE","espp::Ads7138::Append::CHANNEL_ID"],[2,7,1,"_CPPv4N4espp7Ads71386Append4NONEE","espp::Ads7138::Append::NONE"],[2,7,1,"_CPPv4N4espp7Ads71386Append6STATUSE","espp::Ads7138::Append::STATUS"],[2,6,1,"_CPPv4N4espp7Ads71387ChannelE","espp::Ads7138::Channel"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH0E","espp::Ads7138::Channel::CH0"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH1E","espp::Ads7138::Channel::CH1"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH2E","espp::Ads7138::Channel::CH2"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH3E","espp::Ads7138::Channel::CH3"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH4E","espp::Ads7138::Channel::CH4"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH5E","espp::Ads7138::Channel::CH5"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH6E","espp::Ads7138::Channel::CH6"],[2,7,1,"_CPPv4N4espp7Ads71387Channel3CH7E","espp::Ads7138::Channel::CH7"],[2,2,1,"_CPPv4N4espp7Ads71386ConfigE","espp::Ads7138::Config"],[2,1,1,"_CPPv4N4espp7Ads71386Config13analog_inputsE","espp::Ads7138::Config::analog_inputs"],[2,1,1,"_CPPv4N4espp7Ads71386Config10avdd_voltsE","espp::Ads7138::Config::avdd_volts"],[2,1,1,"_CPPv4N4espp7Ads71386Config14device_addressE","espp::Ads7138::Config::device_address"],[2,1,1,"_CPPv4N4espp7Ads71386Config14digital_inputsE","espp::Ads7138::Config::digital_inputs"],[2,1,1,"_CPPv4N4espp7Ads71386Config15digital_outputsE","espp::Ads7138::Config::digital_outputs"],[2,1,1,"_CPPv4N4espp7Ads71386Config9log_levelE","espp::Ads7138::Config::log_level"],[2,1,1,"_CPPv4N4espp7Ads71386Config4modeE","espp::Ads7138::Config::mode"],[2,1,1,"_CPPv4N4espp7Ads71386Config18oversampling_ratioE","espp::Ads7138::Config::oversampling_ratio"],[2,1,1,"_CPPv4N4espp7Ads71386Config4readE","espp::Ads7138::Config::read"],[2,1,1,"_CPPv4N4espp7Ads71386Config18statistics_enabledE","espp::Ads7138::Config::statistics_enabled"],[2,1,1,"_CPPv4N4espp7Ads71386Config5writeE","espp::Ads7138::Config::write"],[2,1,1,"_CPPv4N4espp7Ads713815DEFAULT_ADDRESSE","espp::Ads7138::DEFAULT_ADDRESS"],[2,6,1,"_CPPv4N4espp7Ads713810DataFormatE","espp::Ads7138::DataFormat"],[2,7,1,"_CPPv4N4espp7Ads713810DataFormat8AVERAGEDE","espp::Ads7138::DataFormat::AVERAGED"],[2,7,1,"_CPPv4N4espp7Ads713810DataFormat3RAWE","espp::Ads7138::DataFormat::RAW"],[2,6,1,"_CPPv4N4espp7Ads713812DigitalEventE","espp::Ads7138::DigitalEvent"],[2,7,1,"_CPPv4N4espp7Ads713812DigitalEvent4HIGHE","espp::Ads7138::DigitalEvent::HIGH"],[2,7,1,"_CPPv4N4espp7Ads713812DigitalEvent3LOWE","espp::Ads7138::DigitalEvent::LOW"],[2,6,1,"_CPPv4N4espp7Ads71384ModeE","espp::Ads7138::Mode"],[2,7,1,"_CPPv4N4espp7Ads71384Mode10AUTONOMOUSE","espp::Ads7138::Mode::AUTONOMOUS"],[2,7,1,"_CPPv4N4espp7Ads71384Mode8AUTO_SEQE","espp::Ads7138::Mode::AUTO_SEQ"],[2,7,1,"_CPPv4N4espp7Ads71384Mode6MANUALE","espp::Ads7138::Mode::MANUAL"],[2,6,1,"_CPPv4N4espp7Ads713810OutputModeE","espp::Ads7138::OutputMode"],[2,7,1,"_CPPv4N4espp7Ads713810OutputMode10OPEN_DRAINE","espp::Ads7138::OutputMode::OPEN_DRAIN"],[2,7,1,"_CPPv4N4espp7Ads713810OutputMode9PUSH_PULLE","espp::Ads7138::OutputMode::PUSH_PULL"],[2,6,1,"_CPPv4N4espp7Ads713817OversamplingRatioE","espp::Ads7138::OversamplingRatio"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio4NONEE","espp::Ads7138::OversamplingRatio::NONE"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio7OSR_128E","espp::Ads7138::OversamplingRatio::OSR_128"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio6OSR_16E","espp::Ads7138::OversamplingRatio::OSR_16"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio5OSR_2E","espp::Ads7138::OversamplingRatio::OSR_2"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio6OSR_32E","espp::Ads7138::OversamplingRatio::OSR_32"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio5OSR_4E","espp::Ads7138::OversamplingRatio::OSR_4"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio6OSR_64E","espp::Ads7138::OversamplingRatio::OSR_64"],[2,7,1,"_CPPv4N4espp7Ads713817OversamplingRatio5OSR_8E","espp::Ads7138::OversamplingRatio::OSR_8"],[2,3,1,"_CPPv4N4espp7Ads713821clear_event_high_flagE7uint8_t","espp::Ads7138::clear_event_high_flag"],[2,4,1,"_CPPv4N4espp7Ads713821clear_event_high_flagE7uint8_t","espp::Ads7138::clear_event_high_flag::flags"],[2,3,1,"_CPPv4N4espp7Ads713820clear_event_low_flagE7uint8_t","espp::Ads7138::clear_event_low_flag"],[2,4,1,"_CPPv4N4espp7Ads713820clear_event_low_flagE7uint8_t","espp::Ads7138::clear_event_low_flag::flags"],[2,3,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogic","espp::Ads7138::configure_alert"],[2,4,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogic","espp::Ads7138::configure_alert::alert_logic"],[2,4,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogic","espp::Ads7138::configure_alert::output_mode"],[2,3,1,"_CPPv4N4espp7Ads713810get_all_mvEv","espp::Ads7138::get_all_mv"],[2,3,1,"_CPPv4N4espp7Ads713823get_digital_input_valueE7Channel","espp::Ads7138::get_digital_input_value"],[2,4,1,"_CPPv4N4espp7Ads713823get_digital_input_valueE7Channel","espp::Ads7138::get_digital_input_value::channel"],[2,3,1,"_CPPv4N4espp7Ads713824get_digital_input_valuesEv","espp::Ads7138::get_digital_input_values"],[2,3,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_t","espp::Ads7138::get_event_data"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_t","espp::Ads7138::get_event_data::event_flags"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_t","espp::Ads7138::get_event_data::event_high_flags"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_t","espp::Ads7138::get_event_data::event_low_flags"],[2,3,1,"_CPPv4N4espp7Ads713815get_event_flagsEv","espp::Ads7138::get_event_flags"],[2,3,1,"_CPPv4N4espp7Ads713819get_event_high_flagEv","espp::Ads7138::get_event_high_flag"],[2,3,1,"_CPPv4N4espp7Ads713818get_event_low_flagEv","espp::Ads7138::get_event_low_flag"],[2,3,1,"_CPPv4N4espp7Ads71386get_mvE7Channel","espp::Ads7138::get_mv"],[2,4,1,"_CPPv4N4espp7Ads71386get_mvE7Channel","espp::Ads7138::get_mv::channel"],[2,8,1,"_CPPv4N4espp7Ads71387read_fnE","espp::Ads7138::read_fn"],[2,3,1,"_CPPv4N4espp7Ads71385resetEv","espp::Ads7138::reset"],[2,3,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventi","espp::Ads7138::set_analog_alert"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventi","espp::Ads7138::set_analog_alert::channel"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventi","espp::Ads7138::set_analog_alert::event"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventi","espp::Ads7138::set_analog_alert::event_count"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventi","espp::Ads7138::set_analog_alert::high_threshold_mv"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventi","espp::Ads7138::set_analog_alert::low_threshold_mv"],[2,3,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEvent","espp::Ads7138::set_digital_alert"],[2,4,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEvent","espp::Ads7138::set_digital_alert::channel"],[2,4,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEvent","espp::Ads7138::set_digital_alert::event"],[2,3,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputMode","espp::Ads7138::set_digital_output_mode"],[2,4,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputMode","espp::Ads7138::set_digital_output_mode::channel"],[2,4,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputMode","espp::Ads7138::set_digital_output_mode::output_mode"],[2,3,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7Channelb","espp::Ads7138::set_digital_output_value"],[2,4,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7Channelb","espp::Ads7138::set_digital_output_value::channel"],[2,4,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7Channelb","espp::Ads7138::set_digital_output_value::value"],[2,8,1,"_CPPv4N4espp7Ads71388write_fnE","espp::Ads7138::write_fn"],[18,2,1,"_CPPv4N4espp6As5600E","espp::As5600"],[18,3,1,"_CPPv4N4espp6As56006As5600ERK6Config","espp::As5600::As5600"],[18,4,1,"_CPPv4N4espp6As56006As5600ERK6Config","espp::As5600::As5600::config"],[18,1,1,"_CPPv4N4espp6As560021COUNTS_PER_REVOLUTIONE","espp::As5600::COUNTS_PER_REVOLUTION"],[18,1,1,"_CPPv4N4espp6As560023COUNTS_PER_REVOLUTION_FE","espp::As5600::COUNTS_PER_REVOLUTION_F"],[18,1,1,"_CPPv4N4espp6As560017COUNTS_TO_DEGREESE","espp::As5600::COUNTS_TO_DEGREES"],[18,1,1,"_CPPv4N4espp6As560017COUNTS_TO_RADIANSE","espp::As5600::COUNTS_TO_RADIANS"],[18,2,1,"_CPPv4N4espp6As56006ConfigE","espp::As5600::Config"],[18,1,1,"_CPPv4N4espp6As56006Config14device_addressE","espp::As5600::Config::device_address"],[18,1,1,"_CPPv4N4espp6As56006Config4readE","espp::As5600::Config::read"],[18,1,1,"_CPPv4N4espp6As56006Config13update_periodE","espp::As5600::Config::update_period"],[18,1,1,"_CPPv4N4espp6As56006Config15velocity_filterE","espp::As5600::Config::velocity_filter"],[18,1,1,"_CPPv4N4espp6As56006Config5writeE","espp::As5600::Config::write"],[18,1,1,"_CPPv4N4espp6As560015DEFAULT_ADDRESSE","espp::As5600::DEFAULT_ADDRESS"],[18,1,1,"_CPPv4N4espp6As560018SECONDS_PER_MINUTEE","espp::As5600::SECONDS_PER_MINUTE"],[18,3,1,"_CPPv4NK4espp6As560015get_accumulatorEv","espp::As5600::get_accumulator"],[18,3,1,"_CPPv4NK4espp6As56009get_countEv","espp::As5600::get_count"],[18,3,1,"_CPPv4NK4espp6As560011get_degreesEv","espp::As5600::get_degrees"],[18,3,1,"_CPPv4NK4espp6As560022get_mechanical_degreesEv","espp::As5600::get_mechanical_degrees"],[18,3,1,"_CPPv4NK4espp6As560022get_mechanical_radiansEv","espp::As5600::get_mechanical_radians"],[18,3,1,"_CPPv4NK4espp6As560011get_radiansEv","espp::As5600::get_radians"],[18,3,1,"_CPPv4NK4espp6As56007get_rpmEv","espp::As5600::get_rpm"],[18,3,1,"_CPPv4NK4espp6As560017needs_zero_searchEv","espp::As5600::needs_zero_search"],[18,8,1,"_CPPv4N4espp6As56007read_fnE","espp::As5600::read_fn"],[18,8,1,"_CPPv4N4espp6As560018velocity_filter_fnE","espp::As5600::velocity_filter_fn"],[18,8,1,"_CPPv4N4espp6As56008write_fnE","espp::As5600::write_fn"],[38,2,1,"_CPPv4N4espp6Aw9523E","espp::Aw9523"],[38,3,1,"_CPPv4N4espp6Aw95236Aw9523ERK6Config","espp::Aw9523::Aw9523"],[38,4,1,"_CPPv4N4espp6Aw95236Aw9523ERK6Config","espp::Aw9523::Aw9523::config"],[38,2,1,"_CPPv4N4espp6Aw95236ConfigE","espp::Aw9523::Config"],[38,1,1,"_CPPv4N4espp6Aw95236Config14device_addressE","espp::Aw9523::Config::device_address"],[38,1,1,"_CPPv4N4espp6Aw95236Config9log_levelE","espp::Aw9523::Config::log_level"],[38,1,1,"_CPPv4N4espp6Aw95236Config15max_led_currentE","espp::Aw9523::Config::max_led_current"],[38,1,1,"_CPPv4N4espp6Aw95236Config20output_drive_mode_p0E","espp::Aw9523::Config::output_drive_mode_p0"],[38,1,1,"_CPPv4N4espp6Aw95236Config21port_0_direction_maskE","espp::Aw9523::Config::port_0_direction_mask"],[38,1,1,"_CPPv4N4espp6Aw95236Config21port_0_interrupt_maskE","espp::Aw9523::Config::port_0_interrupt_mask"],[38,1,1,"_CPPv4N4espp6Aw95236Config21port_1_direction_maskE","espp::Aw9523::Config::port_1_direction_mask"],[38,1,1,"_CPPv4N4espp6Aw95236Config21port_1_interrupt_maskE","espp::Aw9523::Config::port_1_interrupt_mask"],[38,1,1,"_CPPv4N4espp6Aw95236Config4readE","espp::Aw9523::Config::read"],[38,1,1,"_CPPv4N4espp6Aw95236Config5writeE","espp::Aw9523::Config::write"],[38,1,1,"_CPPv4N4espp6Aw952315DEFAULT_ADDRESSE","espp::Aw9523::DEFAULT_ADDRESS"],[38,6,1,"_CPPv4N4espp6Aw952313MaxLedCurrentE","espp::Aw9523::MaxLedCurrent"],[38,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent4IMAXE","espp::Aw9523::MaxLedCurrent::IMAX"],[38,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent7IMAX_25E","espp::Aw9523::MaxLedCurrent::IMAX_25"],[38,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent7IMAX_50E","espp::Aw9523::MaxLedCurrent::IMAX_50"],[38,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent7IMAX_75E","espp::Aw9523::MaxLedCurrent::IMAX_75"],[38,6,1,"_CPPv4N4espp6Aw952317OutputDriveModeP0E","espp::Aw9523::OutputDriveModeP0"],[38,7,1,"_CPPv4N4espp6Aw952317OutputDriveModeP010OPEN_DRAINE","espp::Aw9523::OutputDriveModeP0::OPEN_DRAIN"],[38,7,1,"_CPPv4N4espp6Aw952317OutputDriveModeP09PUSH_PUSHE","espp::Aw9523::OutputDriveModeP0::PUSH_PUSH"],[38,6,1,"_CPPv4N4espp6Aw95234PortE","espp::Aw9523::Port"],[38,7,1,"_CPPv4N4espp6Aw95234Port5PORT0E","espp::Aw9523::Port::PORT0"],[38,7,1,"_CPPv4N4espp6Aw95234Port5PORT1E","espp::Aw9523::Port::PORT1"],[38,3,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrent","espp::Aw9523::configure_global_control"],[38,4,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrent","espp::Aw9523::configure_global_control::max_led_current"],[38,4,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrent","espp::Aw9523::configure_global_control::output_drive_mode_p0"],[38,3,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_t","espp::Aw9523::configure_led"],[38,3,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_t","espp::Aw9523::configure_led"],[38,3,1,"_CPPv4N4espp6Aw952313configure_ledE8uint16_t","espp::Aw9523::configure_led"],[38,4,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_t","espp::Aw9523::configure_led::mask"],[38,4,1,"_CPPv4N4espp6Aw952313configure_ledE8uint16_t","espp::Aw9523::configure_led::mask"],[38,4,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_t","espp::Aw9523::configure_led::p0"],[38,4,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_t","espp::Aw9523::configure_led::p1"],[38,4,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_t","espp::Aw9523::configure_led::port"],[38,3,1,"_CPPv4N4espp6Aw95238get_pinsE4Port","espp::Aw9523::get_pins"],[38,3,1,"_CPPv4N4espp6Aw95238get_pinsEv","espp::Aw9523::get_pins"],[38,4,1,"_CPPv4N4espp6Aw95238get_pinsE4Port","espp::Aw9523::get_pins::port"],[38,3,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_t","espp::Aw9523::led"],[38,4,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_t","espp::Aw9523::led::brightness"],[38,4,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_t","espp::Aw9523::led::pin"],[38,8,1,"_CPPv4N4espp6Aw95237read_fnE","espp::Aw9523::read_fn"],[38,3,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_t","espp::Aw9523::set_direction"],[38,3,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_t","espp::Aw9523::set_direction"],[38,4,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_t","espp::Aw9523::set_direction::mask"],[38,4,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_t","espp::Aw9523::set_direction::p0"],[38,4,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_t","espp::Aw9523::set_direction::p1"],[38,4,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_t","espp::Aw9523::set_direction::port"],[38,3,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_t","espp::Aw9523::set_interrupt"],[38,3,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_t","espp::Aw9523::set_interrupt"],[38,4,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_t","espp::Aw9523::set_interrupt::mask"],[38,4,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_t","espp::Aw9523::set_interrupt::p0"],[38,4,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_t","espp::Aw9523::set_interrupt::p1"],[38,4,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_t","espp::Aw9523::set_interrupt::port"],[38,3,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_t","espp::Aw9523::set_pins"],[38,3,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_t","espp::Aw9523::set_pins"],[38,4,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_t","espp::Aw9523::set_pins::output"],[38,4,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_t","espp::Aw9523::set_pins::p0"],[38,4,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_t","espp::Aw9523::set_pins::p1"],[38,4,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_t","espp::Aw9523::set_pins::port"],[38,8,1,"_CPPv4N4espp6Aw95238write_fnE","espp::Aw9523::write_fn"],[45,2,1,"_CPPv4I0EN4espp6BezierE","espp::Bezier"],[45,3,1,"_CPPv4N4espp6Bezier6BezierERK14WeightedConfig","espp::Bezier::Bezier"],[45,3,1,"_CPPv4N4espp6Bezier6BezierERK6Config","espp::Bezier::Bezier"],[45,4,1,"_CPPv4N4espp6Bezier6BezierERK14WeightedConfig","espp::Bezier::Bezier::config"],[45,4,1,"_CPPv4N4espp6Bezier6BezierERK6Config","espp::Bezier::Bezier::config"],[45,2,1,"_CPPv4N4espp6Bezier6ConfigE","espp::Bezier::Config"],[45,1,1,"_CPPv4N4espp6Bezier6Config14control_pointsE","espp::Bezier::Config::control_points"],[45,5,1,"_CPPv4I0EN4espp6BezierE","espp::Bezier::T"],[45,2,1,"_CPPv4N4espp6Bezier14WeightedConfigE","espp::Bezier::WeightedConfig"],[45,1,1,"_CPPv4N4espp6Bezier14WeightedConfig14control_pointsE","espp::Bezier::WeightedConfig::control_points"],[45,1,1,"_CPPv4N4espp6Bezier14WeightedConfig7weightsE","espp::Bezier::WeightedConfig::weights"],[45,3,1,"_CPPv4NK4espp6Bezier2atEf","espp::Bezier::at"],[45,4,1,"_CPPv4NK4espp6Bezier2atEf","espp::Bezier::at::t"],[45,3,1,"_CPPv4NK4espp6BezierclEf","espp::Bezier::operator()"],[45,4,1,"_CPPv4NK4espp6BezierclEf","espp::Bezier::operator()::t"],[24,2,1,"_CPPv4N4espp15BiquadFilterDf1E","espp::BiquadFilterDf1"],[24,3,1,"_CPPv4N4espp15BiquadFilterDf16updateEf","espp::BiquadFilterDf1::update"],[24,4,1,"_CPPv4N4espp15BiquadFilterDf16updateEf","espp::BiquadFilterDf1::update::input"],[24,2,1,"_CPPv4N4espp15BiquadFilterDf2E","espp::BiquadFilterDf2"],[24,3,1,"_CPPv4N4espp15BiquadFilterDf26updateEKf","espp::BiquadFilterDf2::update"],[24,3,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update"],[24,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEKf","espp::BiquadFilterDf2::update::input"],[24,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update::input"],[24,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update::length"],[24,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update::output"],[6,2,1,"_CPPv4N4espp10BldcDriverE","espp::BldcDriver"],[6,3,1,"_CPPv4N4espp10BldcDriver10BldcDriverERK6Config","espp::BldcDriver::BldcDriver"],[6,4,1,"_CPPv4N4espp10BldcDriver10BldcDriverERK6Config","espp::BldcDriver::BldcDriver::config"],[6,2,1,"_CPPv4N4espp10BldcDriver6ConfigE","espp::BldcDriver::Config"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config9dead_zoneE","espp::BldcDriver::Config::dead_zone"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_a_hE","espp::BldcDriver::Config::gpio_a_h"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_a_lE","espp::BldcDriver::Config::gpio_a_l"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_b_hE","espp::BldcDriver::Config::gpio_b_h"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_b_lE","espp::BldcDriver::Config::gpio_b_l"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_c_hE","espp::BldcDriver::Config::gpio_c_h"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_c_lE","espp::BldcDriver::Config::gpio_c_l"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config11gpio_enableE","espp::BldcDriver::Config::gpio_enable"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config10gpio_faultE","espp::BldcDriver::Config::gpio_fault"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config13limit_voltageE","espp::BldcDriver::Config::limit_voltage"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config9log_levelE","espp::BldcDriver::Config::log_level"],[6,1,1,"_CPPv4N4espp10BldcDriver6Config20power_supply_voltageE","espp::BldcDriver::Config::power_supply_voltage"],[6,3,1,"_CPPv4N4espp10BldcDriver15configure_powerEff","espp::BldcDriver::configure_power"],[6,4,1,"_CPPv4N4espp10BldcDriver15configure_powerEff","espp::BldcDriver::configure_power::power_supply_voltage"],[6,4,1,"_CPPv4N4espp10BldcDriver15configure_powerEff","espp::BldcDriver::configure_power::voltage_limit"],[6,3,1,"_CPPv4N4espp10BldcDriver7disableEv","espp::BldcDriver::disable"],[6,3,1,"_CPPv4N4espp10BldcDriver6enableEv","espp::BldcDriver::enable"],[6,3,1,"_CPPv4NK4espp10BldcDriver22get_power_supply_limitEv","espp::BldcDriver::get_power_supply_limit"],[6,3,1,"_CPPv4NK4espp10BldcDriver17get_voltage_limitEv","espp::BldcDriver::get_voltage_limit"],[6,3,1,"_CPPv4NK4espp10BldcDriver10is_enabledEv","espp::BldcDriver::is_enabled"],[6,3,1,"_CPPv4N4espp10BldcDriver10is_faultedEv","espp::BldcDriver::is_faulted"],[6,3,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state"],[6,4,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state::state_a"],[6,4,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state::state_b"],[6,4,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state::state_c"],[6,3,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm"],[6,4,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm::duty_a"],[6,4,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm::duty_b"],[6,4,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm::duty_c"],[6,3,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage"],[6,4,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage::ua"],[6,4,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage::ub"],[6,4,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage::uc"],[6,3,1,"_CPPv4N4espp10BldcDriverD0Ev","espp::BldcDriver::~BldcDriver"],[32,2,1,"_CPPv4I_12MotorConceptEN4espp11BldcHapticsE","espp::BldcHaptics"],[32,3,1,"_CPPv4N4espp11BldcHaptics11BldcHapticsERK6Config","espp::BldcHaptics::BldcHaptics"],[32,4,1,"_CPPv4N4espp11BldcHaptics11BldcHapticsERK6Config","espp::BldcHaptics::BldcHaptics::config"],[32,2,1,"_CPPv4N4espp11BldcHaptics6ConfigE","espp::BldcHaptics::Config"],[32,1,1,"_CPPv4N4espp11BldcHaptics6Config13kd_factor_maxE","espp::BldcHaptics::Config::kd_factor_max"],[32,1,1,"_CPPv4N4espp11BldcHaptics6Config13kd_factor_minE","espp::BldcHaptics::Config::kd_factor_min"],[32,1,1,"_CPPv4N4espp11BldcHaptics6Config9kp_factorE","espp::BldcHaptics::Config::kp_factor"],[32,1,1,"_CPPv4N4espp11BldcHaptics6Config9log_levelE","espp::BldcHaptics::Config::log_level"],[32,1,1,"_CPPv4N4espp11BldcHaptics6Config5motorE","espp::BldcHaptics::Config::motor"],[32,5,1,"_CPPv4I_12MotorConceptEN4espp11BldcHapticsE","espp::BldcHaptics::M"],[32,3,1,"_CPPv4NK4espp11BldcHaptics12get_positionEv","espp::BldcHaptics::get_position"],[32,3,1,"_CPPv4NK4espp11BldcHaptics10is_runningEv","espp::BldcHaptics::is_running"],[32,3,1,"_CPPv4N4espp11BldcHaptics11play_hapticERKN6detail12HapticConfigE","espp::BldcHaptics::play_haptic"],[32,4,1,"_CPPv4N4espp11BldcHaptics11play_hapticERKN6detail12HapticConfigE","espp::BldcHaptics::play_haptic::config"],[32,3,1,"_CPPv4N4espp11BldcHaptics5startEv","espp::BldcHaptics::start"],[32,3,1,"_CPPv4N4espp11BldcHaptics4stopEv","espp::BldcHaptics::stop"],[32,3,1,"_CPPv4N4espp11BldcHaptics20update_detent_configERKN6detail12DetentConfigE","espp::BldcHaptics::update_detent_config"],[32,4,1,"_CPPv4N4espp11BldcHaptics20update_detent_configERKN6detail12DetentConfigE","espp::BldcHaptics::update_detent_config::config"],[32,3,1,"_CPPv4N4espp11BldcHapticsD0Ev","espp::BldcHaptics::~BldcHaptics"],[7,2,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor"],[7,3,1,"_CPPv4N4espp9BldcMotor9BldcMotorERK6Config","espp::BldcMotor::BldcMotor"],[7,4,1,"_CPPv4N4espp9BldcMotor9BldcMotorERK6Config","espp::BldcMotor::BldcMotor::config"],[7,5,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor::CS"],[7,2,1,"_CPPv4N4espp9BldcMotor6ConfigE","espp::BldcMotor::Config"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config12angle_filterE","espp::BldcMotor::Config::angle_filter"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config13current_limitE","espp::BldcMotor::Config::current_limit"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config13current_senseE","espp::BldcMotor::Config::current_sense"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config16d_current_filterE","espp::BldcMotor::Config::d_current_filter"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config6driverE","espp::BldcMotor::Config::driver"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config8foc_typeE","espp::BldcMotor::Config::foc_type"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config9kv_ratingE","espp::BldcMotor::Config::kv_rating"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config9log_levelE","espp::BldcMotor::Config::log_level"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config14num_pole_pairsE","espp::BldcMotor::Config::num_pole_pairs"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config16phase_inductanceE","espp::BldcMotor::Config::phase_inductance"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config16phase_resistanceE","espp::BldcMotor::Config::phase_resistance"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config16q_current_filterE","espp::BldcMotor::Config::q_current_filter"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config6sensorE","espp::BldcMotor::Config::sensor"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config17torque_controllerE","espp::BldcMotor::Config::torque_controller"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config15velocity_filterE","espp::BldcMotor::Config::velocity_filter"],[7,1,1,"_CPPv4N4espp9BldcMotor6Config14velocity_limitE","espp::BldcMotor::Config::velocity_limit"],[7,5,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor::D"],[7,5,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor::S"],[7,3,1,"_CPPv4N4espp9BldcMotor7disableEv","espp::BldcMotor::disable"],[7,3,1,"_CPPv4N4espp9BldcMotor6enableEv","espp::BldcMotor::enable"],[7,8,1,"_CPPv4N4espp9BldcMotor9filter_fnE","espp::BldcMotor::filter_fn"],[7,3,1,"_CPPv4N4espp9BldcMotor20get_electrical_angleEv","espp::BldcMotor::get_electrical_angle"],[7,3,1,"_CPPv4N4espp9BldcMotor15get_shaft_angleEv","espp::BldcMotor::get_shaft_angle"],[7,3,1,"_CPPv4N4espp9BldcMotor18get_shaft_velocityEv","espp::BldcMotor::get_shaft_velocity"],[7,3,1,"_CPPv4NK4espp9BldcMotor10is_enabledEv","espp::BldcMotor::is_enabled"],[7,3,1,"_CPPv4N4espp9BldcMotor8loop_focEv","espp::BldcMotor::loop_foc"],[7,3,1,"_CPPv4N4espp9BldcMotor4moveEf","espp::BldcMotor::move"],[7,4,1,"_CPPv4N4espp9BldcMotor4moveEf","espp::BldcMotor::move::new_target"],[7,3,1,"_CPPv4N4espp9BldcMotor23set_motion_control_typeEN6detail17MotionControlTypeE","espp::BldcMotor::set_motion_control_type"],[7,4,1,"_CPPv4N4espp9BldcMotor23set_motion_control_typeEN6detail17MotionControlTypeE","espp::BldcMotor::set_motion_control_type::motion_control_type"],[7,3,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage"],[7,4,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage::el_angle"],[7,4,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage::ud"],[7,4,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage::uq"],[7,3,1,"_CPPv4N4espp9BldcMotorD0Ev","espp::BldcMotor::~BldcMotor"],[25,2,1,"_CPPv4I_6size_t0EN4espp17ButterworthFilterE","espp::ButterworthFilter"],[25,3,1,"_CPPv4N4espp17ButterworthFilter17ButterworthFilterERK6Config","espp::ButterworthFilter::ButterworthFilter"],[25,4,1,"_CPPv4N4espp17ButterworthFilter17ButterworthFilterERK6Config","espp::ButterworthFilter::ButterworthFilter::config"],[25,2,1,"_CPPv4N4espp17ButterworthFilter6ConfigE","espp::ButterworthFilter::Config"],[25,1,1,"_CPPv4N4espp17ButterworthFilter6Config27normalized_cutoff_frequencyE","espp::ButterworthFilter::Config::normalized_cutoff_frequency"],[25,5,1,"_CPPv4I_6size_t0EN4espp17ButterworthFilterE","espp::ButterworthFilter::Impl"],[25,5,1,"_CPPv4I_6size_t0EN4espp17ButterworthFilterE","espp::ButterworthFilter::ORDER"],[25,3,1,"_CPPv4N4espp17ButterworthFilterclEf","espp::ButterworthFilter::operator()"],[25,4,1,"_CPPv4N4espp17ButterworthFilterclEf","espp::ButterworthFilter::operator()::input"],[25,3,1,"_CPPv4N4espp17ButterworthFilter6updateEf","espp::ButterworthFilter::update"],[25,4,1,"_CPPv4N4espp17ButterworthFilter6updateEf","espp::ButterworthFilter::update::input"],[9,2,1,"_CPPv4N4espp6ButtonE","espp::Button"],[9,6,1,"_CPPv4N4espp6Button11ActiveLevelE","espp::Button::ActiveLevel"],[9,7,1,"_CPPv4N4espp6Button11ActiveLevel4HIGHE","espp::Button::ActiveLevel::HIGH"],[9,7,1,"_CPPv4N4espp6Button11ActiveLevel3LOWE","espp::Button::ActiveLevel::LOW"],[9,3,1,"_CPPv4N4espp6Button6ButtonERK6Config","espp::Button::Button"],[9,4,1,"_CPPv4N4espp6Button6ButtonERK6Config","espp::Button::Button::config"],[9,2,1,"_CPPv4N4espp6Button6ConfigE","espp::Button::Config"],[9,1,1,"_CPPv4N4espp6Button6Config12active_levelE","espp::Button::Config::active_level"],[9,1,1,"_CPPv4N4espp6Button6Config8callbackE","espp::Button::Config::callback"],[9,1,1,"_CPPv4N4espp6Button6Config8gpio_numE","espp::Button::Config::gpio_num"],[9,1,1,"_CPPv4N4espp6Button6Config14interrupt_typeE","espp::Button::Config::interrupt_type"],[9,1,1,"_CPPv4N4espp6Button6Config9log_levelE","espp::Button::Config::log_level"],[9,1,1,"_CPPv4N4espp6Button6Config16pulldown_enabledE","espp::Button::Config::pulldown_enabled"],[9,1,1,"_CPPv4N4espp6Button6Config14pullup_enabledE","espp::Button::Config::pullup_enabled"],[9,1,1,"_CPPv4N4espp6Button6Config21task_stack_size_bytesE","espp::Button::Config::task_stack_size_bytes"],[9,2,1,"_CPPv4N4espp6Button5EventE","espp::Button::Event"],[9,1,1,"_CPPv4N4espp6Button5Event8gpio_numE","espp::Button::Event::gpio_num"],[9,1,1,"_CPPv4N4espp6Button5Event7pressedE","espp::Button::Event::pressed"],[9,6,1,"_CPPv4N4espp6Button13InterruptTypeE","espp::Button::InterruptType"],[9,7,1,"_CPPv4N4espp6Button13InterruptType8ANY_EDGEE","espp::Button::InterruptType::ANY_EDGE"],[9,7,1,"_CPPv4N4espp6Button13InterruptType12FALLING_EDGEE","espp::Button::InterruptType::FALLING_EDGE"],[9,7,1,"_CPPv4N4espp6Button13InterruptType10HIGH_LEVELE","espp::Button::InterruptType::HIGH_LEVEL"],[9,7,1,"_CPPv4N4espp6Button13InterruptType9LOW_LEVELE","espp::Button::InterruptType::LOW_LEVEL"],[9,7,1,"_CPPv4N4espp6Button13InterruptType11RISING_EDGEE","espp::Button::InterruptType::RISING_EDGE"],[9,8,1,"_CPPv4N4espp6Button17event_callback_fnE","espp::Button::event_callback_fn"],[9,3,1,"_CPPv4NK4espp6Button10is_pressedEv","espp::Button::is_pressed"],[9,3,1,"_CPPv4N4espp6ButtonD0Ev","espp::Button::~Button"],[10,2,1,"_CPPv4N4espp3CliE","espp::Cli"],[10,3,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli"],[10,4,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli::_cli"],[10,4,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli::_in"],[10,4,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli::_out"],[10,3,1,"_CPPv4NK4espp3Cli15GetInputHistoryEv","espp::Cli::GetInputHistory"],[10,3,1,"_CPPv4N4espp3Cli15SetInputHistoryERKN9LineInput7HistoryE","espp::Cli::SetInputHistory"],[10,4,1,"_CPPv4N4espp3Cli15SetInputHistoryERKN9LineInput7HistoryE","espp::Cli::SetInputHistory::history"],[10,3,1,"_CPPv4N4espp3Cli19SetInputHistorySizeE6size_t","espp::Cli::SetInputHistorySize"],[10,4,1,"_CPPv4N4espp3Cli19SetInputHistorySizeE6size_t","espp::Cli::SetInputHistorySize::history_size"],[10,3,1,"_CPPv4N4espp3Cli5StartEv","espp::Cli::Start"],[10,3,1,"_CPPv4N4espp3Cli22configure_stdin_stdoutEv","espp::Cli::configure_stdin_stdout"],[3,2,1,"_CPPv4N4espp13ContinuousAdcE","espp::ContinuousAdc"],[3,2,1,"_CPPv4N4espp13ContinuousAdc6ConfigE","espp::ContinuousAdc::Config"],[3,1,1,"_CPPv4N4espp13ContinuousAdc6Config8channelsE","espp::ContinuousAdc::Config::channels"],[3,1,1,"_CPPv4N4espp13ContinuousAdc6Config12convert_modeE","espp::ContinuousAdc::Config::convert_mode"],[3,1,1,"_CPPv4N4espp13ContinuousAdc6Config9log_levelE","espp::ContinuousAdc::Config::log_level"],[3,1,1,"_CPPv4N4espp13ContinuousAdc6Config14sample_rate_hzE","espp::ContinuousAdc::Config::sample_rate_hz"],[3,1,1,"_CPPv4N4espp13ContinuousAdc6Config13task_priorityE","espp::ContinuousAdc::Config::task_priority"],[3,1,1,"_CPPv4N4espp13ContinuousAdc6Config17window_size_bytesE","espp::ContinuousAdc::Config::window_size_bytes"],[3,3,1,"_CPPv4N4espp13ContinuousAdc13ContinuousAdcERK6Config","espp::ContinuousAdc::ContinuousAdc"],[3,4,1,"_CPPv4N4espp13ContinuousAdc13ContinuousAdcERK6Config","espp::ContinuousAdc::ContinuousAdc::config"],[3,3,1,"_CPPv4N4espp13ContinuousAdc6get_mvERK9AdcConfig","espp::ContinuousAdc::get_mv"],[3,4,1,"_CPPv4N4espp13ContinuousAdc6get_mvERK9AdcConfig","espp::ContinuousAdc::get_mv::config"],[3,3,1,"_CPPv4N4espp13ContinuousAdc8get_rateERK9AdcConfig","espp::ContinuousAdc::get_rate"],[3,4,1,"_CPPv4N4espp13ContinuousAdc8get_rateERK9AdcConfig","espp::ContinuousAdc::get_rate::config"],[3,3,1,"_CPPv4N4espp13ContinuousAdc5startEv","espp::ContinuousAdc::start"],[3,3,1,"_CPPv4N4espp13ContinuousAdc4stopEv","espp::ContinuousAdc::stop"],[3,3,1,"_CPPv4N4espp13ContinuousAdcD0Ev","espp::ContinuousAdc::~ContinuousAdc"],[12,2,1,"_CPPv4N4espp10ControllerE","espp::Controller"],[12,2,1,"_CPPv4N4espp10Controller20AnalogJoystickConfigE","espp::Controller::AnalogJoystickConfig"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig10active_lowE","espp::Controller::AnalogJoystickConfig::active_low"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_aE","espp::Controller::AnalogJoystickConfig::gpio_a"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_bE","espp::Controller::AnalogJoystickConfig::gpio_b"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig20gpio_joystick_selectE","espp::Controller::AnalogJoystickConfig::gpio_joystick_select"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig11gpio_selectE","espp::Controller::AnalogJoystickConfig::gpio_select"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig10gpio_startE","espp::Controller::AnalogJoystickConfig::gpio_start"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_xE","espp::Controller::AnalogJoystickConfig::gpio_x"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_yE","espp::Controller::AnalogJoystickConfig::gpio_y"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig15joystick_configE","espp::Controller::AnalogJoystickConfig::joystick_config"],[12,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig9log_levelE","espp::Controller::AnalogJoystickConfig::log_level"],[12,6,1,"_CPPv4N4espp10Controller6ButtonE","espp::Controller::Button"],[12,7,1,"_CPPv4N4espp10Controller6Button1AE","espp::Controller::Button::A"],[12,7,1,"_CPPv4N4espp10Controller6Button1BE","espp::Controller::Button::B"],[12,7,1,"_CPPv4N4espp10Controller6Button4DOWNE","espp::Controller::Button::DOWN"],[12,7,1,"_CPPv4N4espp10Controller6Button15JOYSTICK_SELECTE","espp::Controller::Button::JOYSTICK_SELECT"],[12,7,1,"_CPPv4N4espp10Controller6Button11LAST_UNUSEDE","espp::Controller::Button::LAST_UNUSED"],[12,7,1,"_CPPv4N4espp10Controller6Button4LEFTE","espp::Controller::Button::LEFT"],[12,7,1,"_CPPv4N4espp10Controller6Button5RIGHTE","espp::Controller::Button::RIGHT"],[12,7,1,"_CPPv4N4espp10Controller6Button6SELECTE","espp::Controller::Button::SELECT"],[12,7,1,"_CPPv4N4espp10Controller6Button5STARTE","espp::Controller::Button::START"],[12,7,1,"_CPPv4N4espp10Controller6Button2UPE","espp::Controller::Button::UP"],[12,7,1,"_CPPv4N4espp10Controller6Button1XE","espp::Controller::Button::X"],[12,7,1,"_CPPv4N4espp10Controller6Button1YE","espp::Controller::Button::Y"],[12,3,1,"_CPPv4N4espp10Controller10ControllerERK10DualConfig","espp::Controller::Controller"],[12,3,1,"_CPPv4N4espp10Controller10ControllerERK13DigitalConfig","espp::Controller::Controller"],[12,3,1,"_CPPv4N4espp10Controller10ControllerERK20AnalogJoystickConfig","espp::Controller::Controller"],[12,4,1,"_CPPv4N4espp10Controller10ControllerERK10DualConfig","espp::Controller::Controller::config"],[12,4,1,"_CPPv4N4espp10Controller10ControllerERK13DigitalConfig","espp::Controller::Controller::config"],[12,4,1,"_CPPv4N4espp10Controller10ControllerERK20AnalogJoystickConfig","espp::Controller::Controller::config"],[12,2,1,"_CPPv4N4espp10Controller13DigitalConfigE","espp::Controller::DigitalConfig"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig10active_lowE","espp::Controller::DigitalConfig::active_low"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_aE","espp::Controller::DigitalConfig::gpio_a"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_bE","espp::Controller::DigitalConfig::gpio_b"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig9gpio_downE","espp::Controller::DigitalConfig::gpio_down"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig9gpio_leftE","espp::Controller::DigitalConfig::gpio_left"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig10gpio_rightE","espp::Controller::DigitalConfig::gpio_right"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig11gpio_selectE","espp::Controller::DigitalConfig::gpio_select"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig10gpio_startE","espp::Controller::DigitalConfig::gpio_start"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig7gpio_upE","espp::Controller::DigitalConfig::gpio_up"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_xE","espp::Controller::DigitalConfig::gpio_x"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_yE","espp::Controller::DigitalConfig::gpio_y"],[12,1,1,"_CPPv4N4espp10Controller13DigitalConfig9log_levelE","espp::Controller::DigitalConfig::log_level"],[12,2,1,"_CPPv4N4espp10Controller10DualConfigE","espp::Controller::DualConfig"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig10active_lowE","espp::Controller::DualConfig::active_low"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_aE","espp::Controller::DualConfig::gpio_a"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_bE","espp::Controller::DualConfig::gpio_b"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig9gpio_downE","espp::Controller::DualConfig::gpio_down"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig20gpio_joystick_selectE","espp::Controller::DualConfig::gpio_joystick_select"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig9gpio_leftE","espp::Controller::DualConfig::gpio_left"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig10gpio_rightE","espp::Controller::DualConfig::gpio_right"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig11gpio_selectE","espp::Controller::DualConfig::gpio_select"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig10gpio_startE","espp::Controller::DualConfig::gpio_start"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig7gpio_upE","espp::Controller::DualConfig::gpio_up"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_xE","espp::Controller::DualConfig::gpio_x"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_yE","espp::Controller::DualConfig::gpio_y"],[12,1,1,"_CPPv4N4espp10Controller10DualConfig9log_levelE","espp::Controller::DualConfig::log_level"],[12,2,1,"_CPPv4N4espp10Controller5StateE","espp::Controller::State"],[12,1,1,"_CPPv4N4espp10Controller5State1aE","espp::Controller::State::a"],[12,1,1,"_CPPv4N4espp10Controller5State1bE","espp::Controller::State::b"],[12,1,1,"_CPPv4N4espp10Controller5State4downE","espp::Controller::State::down"],[12,1,1,"_CPPv4N4espp10Controller5State15joystick_selectE","espp::Controller::State::joystick_select"],[12,1,1,"_CPPv4N4espp10Controller5State4leftE","espp::Controller::State::left"],[12,1,1,"_CPPv4N4espp10Controller5State5rightE","espp::Controller::State::right"],[12,1,1,"_CPPv4N4espp10Controller5State6selectE","espp::Controller::State::select"],[12,1,1,"_CPPv4N4espp10Controller5State5startE","espp::Controller::State::start"],[12,1,1,"_CPPv4N4espp10Controller5State2upE","espp::Controller::State::up"],[12,1,1,"_CPPv4N4espp10Controller5State1xE","espp::Controller::State::x"],[12,1,1,"_CPPv4N4espp10Controller5State1yE","espp::Controller::State::y"],[12,3,1,"_CPPv4N4espp10Controller9get_stateEv","espp::Controller::get_state"],[12,3,1,"_CPPv4N4espp10Controller10is_pressedEK6Button","espp::Controller::is_pressed"],[12,4,1,"_CPPv4N4espp10Controller10is_pressedEK6Button","espp::Controller::is_pressed::input"],[12,3,1,"_CPPv4N4espp10Controller6updateEv","espp::Controller::update"],[12,3,1,"_CPPv4N4espp10ControllerD0Ev","espp::Controller::~Controller"],[14,2,1,"_CPPv4N4espp7DisplayE","espp::Display"],[14,2,1,"_CPPv4N4espp7Display16AllocatingConfigE","espp::Display::AllocatingConfig"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig16allocation_flagsE","espp::Display::AllocatingConfig::allocation_flags"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig15double_bufferedE","espp::Display::AllocatingConfig::double_buffered"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig14flush_callbackE","espp::Display::AllocatingConfig::flush_callback"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig6heightE","espp::Display::AllocatingConfig::height"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig9log_levelE","espp::Display::AllocatingConfig::log_level"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig17pixel_buffer_sizeE","espp::Display::AllocatingConfig::pixel_buffer_size"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig8rotationE","espp::Display::AllocatingConfig::rotation"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig25software_rotation_enabledE","espp::Display::AllocatingConfig::software_rotation_enabled"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig13update_periodE","espp::Display::AllocatingConfig::update_period"],[14,1,1,"_CPPv4N4espp7Display16AllocatingConfig5widthE","espp::Display::AllocatingConfig::width"],[14,3,1,"_CPPv4N4espp7Display7DisplayERK16AllocatingConfig","espp::Display::Display"],[14,3,1,"_CPPv4N4espp7Display7DisplayERK19NonAllocatingConfig","espp::Display::Display"],[14,4,1,"_CPPv4N4espp7Display7DisplayERK16AllocatingConfig","espp::Display::Display::config"],[14,4,1,"_CPPv4N4espp7Display7DisplayERK19NonAllocatingConfig","espp::Display::Display::config"],[14,2,1,"_CPPv4N4espp7Display19NonAllocatingConfigE","espp::Display::NonAllocatingConfig"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig14flush_callbackE","espp::Display::NonAllocatingConfig::flush_callback"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig6heightE","espp::Display::NonAllocatingConfig::height"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig9log_levelE","espp::Display::NonAllocatingConfig::log_level"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig17pixel_buffer_sizeE","espp::Display::NonAllocatingConfig::pixel_buffer_size"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig8rotationE","espp::Display::NonAllocatingConfig::rotation"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig25software_rotation_enabledE","espp::Display::NonAllocatingConfig::software_rotation_enabled"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig13update_periodE","espp::Display::NonAllocatingConfig::update_period"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig5vram0E","espp::Display::NonAllocatingConfig::vram0"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig5vram1E","espp::Display::NonAllocatingConfig::vram1"],[14,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig5widthE","espp::Display::NonAllocatingConfig::width"],[14,6,1,"_CPPv4N4espp7Display8RotationE","espp::Display::Rotation"],[14,7,1,"_CPPv4N4espp7Display8Rotation9LANDSCAPEE","espp::Display::Rotation::LANDSCAPE"],[14,7,1,"_CPPv4N4espp7Display8Rotation18LANDSCAPE_INVERTEDE","espp::Display::Rotation::LANDSCAPE_INVERTED"],[14,7,1,"_CPPv4N4espp7Display8Rotation8PORTRAITE","espp::Display::Rotation::PORTRAIT"],[14,7,1,"_CPPv4N4espp7Display8Rotation17PORTRAIT_INVERTEDE","espp::Display::Rotation::PORTRAIT_INVERTED"],[14,6,1,"_CPPv4N4espp7Display6SignalE","espp::Display::Signal"],[14,7,1,"_CPPv4N4espp7Display6Signal5FLUSHE","espp::Display::Signal::FLUSH"],[14,7,1,"_CPPv4N4espp7Display6Signal4NONEE","espp::Display::Signal::NONE"],[14,8,1,"_CPPv4N4espp7Display8flush_fnE","espp::Display::flush_fn"],[14,3,1,"_CPPv4N4espp7Display13force_refreshEv","espp::Display::force_refresh"],[14,3,1,"_CPPv4NK4espp7Display6heightEv","espp::Display::height"],[14,3,1,"_CPPv4N4espp7Display5pauseEv","espp::Display::pause"],[14,3,1,"_CPPv4N4espp7Display6resumeEv","espp::Display::resume"],[14,3,1,"_CPPv4N4espp7Display5vram0Ev","espp::Display::vram0"],[14,3,1,"_CPPv4N4espp7Display5vram1Ev","espp::Display::vram1"],[14,3,1,"_CPPv4N4espp7Display15vram_size_bytesEv","espp::Display::vram_size_bytes"],[14,3,1,"_CPPv4N4espp7Display12vram_size_pxEv","espp::Display::vram_size_px"],[14,3,1,"_CPPv4NK4espp7Display5widthEv","espp::Display::width"],[14,3,1,"_CPPv4N4espp7DisplayD0Ev","espp::Display::~Display"],[33,2,1,"_CPPv4N4espp7Drv2605E","espp::Drv2605"],[33,2,1,"_CPPv4N4espp7Drv26056ConfigE","espp::Drv2605::Config"],[33,1,1,"_CPPv4N4espp7Drv26056Config14device_addressE","espp::Drv2605::Config::device_address"],[33,1,1,"_CPPv4N4espp7Drv26056Config9log_levelE","espp::Drv2605::Config::log_level"],[33,1,1,"_CPPv4N4espp7Drv26056Config10motor_typeE","espp::Drv2605::Config::motor_type"],[33,1,1,"_CPPv4N4espp7Drv26056Config4readE","espp::Drv2605::Config::read"],[33,1,1,"_CPPv4N4espp7Drv26056Config5writeE","espp::Drv2605::Config::write"],[33,3,1,"_CPPv4N4espp7Drv26057Drv2605ERK6Config","espp::Drv2605::Drv2605"],[33,4,1,"_CPPv4N4espp7Drv26057Drv2605ERK6Config","espp::Drv2605::Drv2605::config"],[33,6,1,"_CPPv4N4espp7Drv26054ModeE","espp::Drv2605::Mode"],[33,7,1,"_CPPv4N4espp7Drv26054Mode9AUDIOVIBEE","espp::Drv2605::Mode::AUDIOVIBE"],[33,7,1,"_CPPv4N4espp7Drv26054Mode7AUTOCALE","espp::Drv2605::Mode::AUTOCAL"],[33,7,1,"_CPPv4N4espp7Drv26054Mode7DIAGNOSE","espp::Drv2605::Mode::DIAGNOS"],[33,7,1,"_CPPv4N4espp7Drv26054Mode11EXTTRIGEDGEE","espp::Drv2605::Mode::EXTTRIGEDGE"],[33,7,1,"_CPPv4N4espp7Drv26054Mode10EXTTRIGLVLE","espp::Drv2605::Mode::EXTTRIGLVL"],[33,7,1,"_CPPv4N4espp7Drv26054Mode7INTTRIGE","espp::Drv2605::Mode::INTTRIG"],[33,7,1,"_CPPv4N4espp7Drv26054Mode9PWMANALOGE","espp::Drv2605::Mode::PWMANALOG"],[33,7,1,"_CPPv4N4espp7Drv26054Mode8REALTIMEE","espp::Drv2605::Mode::REALTIME"],[33,6,1,"_CPPv4N4espp7Drv26059MotorTypeE","espp::Drv2605::MotorType"],[33,7,1,"_CPPv4N4espp7Drv26059MotorType3ERME","espp::Drv2605::MotorType::ERM"],[33,7,1,"_CPPv4N4espp7Drv26059MotorType3LRAE","espp::Drv2605::MotorType::LRA"],[33,6,1,"_CPPv4N4espp7Drv26058WaveformE","espp::Drv2605::Waveform"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform12ALERT_1000MSE","espp::Drv2605::Waveform::ALERT_1000MS"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform11ALERT_750MSE","espp::Drv2605::Waveform::ALERT_750MS"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ1E","espp::Drv2605::Waveform::BUZZ1"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ2E","espp::Drv2605::Waveform::BUZZ2"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ3E","espp::Drv2605::Waveform::BUZZ3"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ4E","espp::Drv2605::Waveform::BUZZ4"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ5E","espp::Drv2605::Waveform::BUZZ5"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform12DOUBLE_CLICKE","espp::Drv2605::Waveform::DOUBLE_CLICK"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform3ENDE","espp::Drv2605::Waveform::END"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform3MAXE","espp::Drv2605::Waveform::MAX"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform16PULSING_STRONG_1E","espp::Drv2605::Waveform::PULSING_STRONG_1"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform16PULSING_STRONG_2E","espp::Drv2605::Waveform::PULSING_STRONG_2"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform11SHARP_CLICKE","espp::Drv2605::Waveform::SHARP_CLICK"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform9SOFT_BUMPE","espp::Drv2605::Waveform::SOFT_BUMP"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform9SOFT_FUZZE","espp::Drv2605::Waveform::SOFT_FUZZ"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform11STRONG_BUZZE","espp::Drv2605::Waveform::STRONG_BUZZ"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform12STRONG_CLICKE","espp::Drv2605::Waveform::STRONG_CLICK"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform18TRANSITION_CLICK_1E","espp::Drv2605::Waveform::TRANSITION_CLICK_1"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform16TRANSITION_HUM_1E","espp::Drv2605::Waveform::TRANSITION_HUM_1"],[33,7,1,"_CPPv4N4espp7Drv26058Waveform12TRIPLE_CLICKE","espp::Drv2605::Waveform::TRIPLE_CLICK"],[33,8,1,"_CPPv4N4espp7Drv26057read_fnE","espp::Drv2605::read_fn"],[33,3,1,"_CPPv4N4espp7Drv260514select_libraryE7uint8_t","espp::Drv2605::select_library"],[33,4,1,"_CPPv4N4espp7Drv260514select_libraryE7uint8_t","espp::Drv2605::select_library::lib"],[33,3,1,"_CPPv4N4espp7Drv26058set_modeE4Mode","espp::Drv2605::set_mode"],[33,4,1,"_CPPv4N4espp7Drv26058set_modeE4Mode","espp::Drv2605::set_mode::mode"],[33,3,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8Waveform","espp::Drv2605::set_waveform"],[33,4,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8Waveform","espp::Drv2605::set_waveform::slot"],[33,4,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8Waveform","espp::Drv2605::set_waveform::w"],[33,3,1,"_CPPv4N4espp7Drv26055startEv","espp::Drv2605::start"],[33,3,1,"_CPPv4N4espp7Drv26054stopEv","espp::Drv2605::stop"],[33,8,1,"_CPPv4N4espp7Drv26058write_fnE","espp::Drv2605::write_fn"],[22,2,1,"_CPPv4N4espp12EventManagerE","espp::EventManager"],[22,3,1,"_CPPv4N4espp12EventManager13add_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::add_publisher"],[22,4,1,"_CPPv4N4espp12EventManager13add_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::add_publisher::component"],[22,4,1,"_CPPv4N4espp12EventManager13add_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::add_publisher::topic"],[22,3,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fn","espp::EventManager::add_subscriber"],[22,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fn","espp::EventManager::add_subscriber::callback"],[22,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fn","espp::EventManager::add_subscriber::component"],[22,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fn","espp::EventManager::add_subscriber::topic"],[22,8,1,"_CPPv4N4espp12EventManager17event_callback_fnE","espp::EventManager::event_callback_fn"],[22,3,1,"_CPPv4N4espp12EventManager3getEv","espp::EventManager::get"],[22,3,1,"_CPPv4N4espp12EventManager7publishERKNSt6stringERKNSt6vectorI7uint8_tEE","espp::EventManager::publish"],[22,4,1,"_CPPv4N4espp12EventManager7publishERKNSt6stringERKNSt6vectorI7uint8_tEE","espp::EventManager::publish::data"],[22,4,1,"_CPPv4N4espp12EventManager7publishERKNSt6stringERKNSt6vectorI7uint8_tEE","espp::EventManager::publish::topic"],[22,3,1,"_CPPv4N4espp12EventManager16remove_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::remove_publisher"],[22,4,1,"_CPPv4N4espp12EventManager16remove_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::remove_publisher::component"],[22,4,1,"_CPPv4N4espp12EventManager16remove_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::remove_publisher::topic"],[22,3,1,"_CPPv4N4espp12EventManager17remove_subscriberERKNSt6stringERKNSt6stringE","espp::EventManager::remove_subscriber"],[22,4,1,"_CPPv4N4espp12EventManager17remove_subscriberERKNSt6stringERKNSt6stringE","espp::EventManager::remove_subscriber::component"],[22,4,1,"_CPPv4N4espp12EventManager17remove_subscriberERKNSt6stringERKNSt6stringE","espp::EventManager::remove_subscriber::topic"],[22,3,1,"_CPPv4N4espp12EventManager13set_log_levelEN6Logger9VerbosityE","espp::EventManager::set_log_level"],[22,4,1,"_CPPv4N4espp12EventManager13set_log_levelEN6Logger9VerbosityE","espp::EventManager::set_log_level::level"],[23,2,1,"_CPPv4N4espp10FileSystemE","espp::FileSystem"],[23,2,1,"_CPPv4N4espp10FileSystem10ListConfigE","espp::FileSystem::ListConfig"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig9date_timeE","espp::FileSystem::ListConfig::date_time"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig5groupE","espp::FileSystem::ListConfig::group"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig15number_of_linksE","espp::FileSystem::ListConfig::number_of_links"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig5ownerE","espp::FileSystem::ListConfig::owner"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig11permissionsE","espp::FileSystem::ListConfig::permissions"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig9recursiveE","espp::FileSystem::ListConfig::recursive"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig4sizeE","espp::FileSystem::ListConfig::size"],[23,1,1,"_CPPv4N4espp10FileSystem10ListConfig4typeE","espp::FileSystem::ListConfig::type"],[23,3,1,"_CPPv4N4espp10FileSystem3getEv","espp::FileSystem::get"],[23,3,1,"_CPPv4N4espp10FileSystem14get_free_spaceEv","espp::FileSystem::get_free_space"],[23,3,1,"_CPPv4N4espp10FileSystem15get_mount_pointEv","espp::FileSystem::get_mount_point"],[23,3,1,"_CPPv4N4espp10FileSystem19get_partition_labelEv","espp::FileSystem::get_partition_label"],[23,3,1,"_CPPv4N4espp10FileSystem13get_root_pathEv","espp::FileSystem::get_root_path"],[23,3,1,"_CPPv4N4espp10FileSystem15get_total_spaceEv","espp::FileSystem::get_total_space"],[23,3,1,"_CPPv4N4espp10FileSystem14get_used_spaceEv","espp::FileSystem::get_used_space"],[23,3,1,"_CPPv4N4espp10FileSystem14human_readableE6size_t","espp::FileSystem::human_readable"],[23,4,1,"_CPPv4N4espp10FileSystem14human_readableE6size_t","espp::FileSystem::human_readable::bytes"],[23,3,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory"],[23,3,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory"],[23,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::config"],[23,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::config"],[23,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::path"],[23,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::path"],[23,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::prefix"],[23,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::prefix"],[23,3,1,"_CPPv4I0EN4espp10FileSystem9to_time_tENSt6time_tE2TP","espp::FileSystem::to_time_t"],[23,5,1,"_CPPv4I0EN4espp10FileSystem9to_time_tENSt6time_tE2TP","espp::FileSystem::to_time_t::TP"],[23,4,1,"_CPPv4I0EN4espp10FileSystem9to_time_tENSt6time_tE2TP","espp::FileSystem::to_time_t::tp"],[30,2,1,"_CPPv4N4espp16FtpClientSessionE","espp::FtpClientSession"],[30,3,1,"_CPPv4NK4espp16FtpClientSession17current_directoryEv","espp::FtpClientSession::current_directory"],[30,3,1,"_CPPv4NK4espp16FtpClientSession2idEv","espp::FtpClientSession::id"],[30,3,1,"_CPPv4NK4espp16FtpClientSession8is_aliveEv","espp::FtpClientSession::is_alive"],[30,3,1,"_CPPv4NK4espp16FtpClientSession12is_connectedEv","espp::FtpClientSession::is_connected"],[30,3,1,"_CPPv4NK4espp16FtpClientSession26is_passive_data_connectionEv","espp::FtpClientSession::is_passive_data_connection"],[30,2,1,"_CPPv4N4espp9FtpServerE","espp::FtpServer"],[30,3,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer"],[30,4,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer::ip_address"],[30,4,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer::port"],[30,4,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer::root"],[30,3,1,"_CPPv4N4espp9FtpServer5startEv","espp::FtpServer::start"],[30,3,1,"_CPPv4N4espp9FtpServer4stopEv","espp::FtpServer::stop"],[30,3,1,"_CPPv4N4espp9FtpServerD0Ev","espp::FtpServer::~FtpServer"],[47,2,1,"_CPPv4N4espp8GaussianE","espp::Gaussian"],[47,2,1,"_CPPv4N4espp8Gaussian6ConfigE","espp::Gaussian::Config"],[47,1,1,"_CPPv4N4espp8Gaussian6Config5alphaE","espp::Gaussian::Config::alpha"],[47,1,1,"_CPPv4N4espp8Gaussian6Config4betaE","espp::Gaussian::Config::beta"],[47,1,1,"_CPPv4N4espp8Gaussian6Config5gammaE","espp::Gaussian::Config::gamma"],[47,3,1,"_CPPv4N4espp8Gaussian8GaussianERK6Config","espp::Gaussian::Gaussian"],[47,4,1,"_CPPv4N4espp8Gaussian8GaussianERK6Config","espp::Gaussian::Gaussian::config"],[47,3,1,"_CPPv4N4espp8Gaussian5alphaEf","espp::Gaussian::alpha"],[47,3,1,"_CPPv4NK4espp8Gaussian5alphaEv","espp::Gaussian::alpha"],[47,4,1,"_CPPv4N4espp8Gaussian5alphaEf","espp::Gaussian::alpha::a"],[47,3,1,"_CPPv4NK4espp8Gaussian2atEf","espp::Gaussian::at"],[47,4,1,"_CPPv4NK4espp8Gaussian2atEf","espp::Gaussian::at::t"],[47,3,1,"_CPPv4N4espp8Gaussian4betaEf","espp::Gaussian::beta"],[47,3,1,"_CPPv4NK4espp8Gaussian4betaEv","espp::Gaussian::beta"],[47,4,1,"_CPPv4N4espp8Gaussian4betaEf","espp::Gaussian::beta::b"],[47,3,1,"_CPPv4N4espp8Gaussian5gammaEf","espp::Gaussian::gamma"],[47,3,1,"_CPPv4NK4espp8Gaussian5gammaEv","espp::Gaussian::gamma"],[47,4,1,"_CPPv4N4espp8Gaussian5gammaEf","espp::Gaussian::gamma::g"],[47,3,1,"_CPPv4NK4espp8GaussianclEf","espp::Gaussian::operator()"],[47,4,1,"_CPPv4NK4espp8GaussianclEf","espp::Gaussian::operator()::t"],[11,2,1,"_CPPv4N4espp3HsvE","espp::Hsv"],[11,3,1,"_CPPv4N4espp3Hsv3HsvERK3Hsv","espp::Hsv::Hsv"],[11,3,1,"_CPPv4N4espp3Hsv3HsvERK3Rgb","espp::Hsv::Hsv"],[11,3,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv"],[11,4,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv::h"],[11,4,1,"_CPPv4N4espp3Hsv3HsvERK3Hsv","espp::Hsv::Hsv::hsv"],[11,4,1,"_CPPv4N4espp3Hsv3HsvERK3Rgb","espp::Hsv::Hsv::rgb"],[11,4,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv::s"],[11,4,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv::v"],[11,1,1,"_CPPv4N4espp3Hsv1hE","espp::Hsv::h"],[11,3,1,"_CPPv4NK4espp3Hsv3rgbEv","espp::Hsv::rgb"],[11,1,1,"_CPPv4N4espp3Hsv1sE","espp::Hsv::s"],[11,1,1,"_CPPv4N4espp3Hsv1vE","espp::Hsv::v"],[15,2,1,"_CPPv4N4espp7Ili9341E","espp::Ili9341"],[15,3,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear"],[15,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::color"],[15,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::height"],[15,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::width"],[15,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::x"],[15,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::y"],[15,3,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill"],[15,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::area"],[15,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::color_map"],[15,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::drv"],[15,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::flags"],[15,3,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush"],[15,4,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush::area"],[15,4,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush::color_map"],[15,4,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush::drv"],[15,3,1,"_CPPv4N4espp7Ili934110get_offsetERiRi","espp::Ili9341::get_offset"],[15,4,1,"_CPPv4N4espp7Ili934110get_offsetERiRi","espp::Ili9341::get_offset::x"],[15,4,1,"_CPPv4N4espp7Ili934110get_offsetERiRi","espp::Ili9341::get_offset::y"],[15,3,1,"_CPPv4N4espp7Ili934110initializeERKN15display_drivers6ConfigE","espp::Ili9341::initialize"],[15,4,1,"_CPPv4N4espp7Ili934110initializeERKN15display_drivers6ConfigE","espp::Ili9341::initialize::config"],[15,3,1,"_CPPv4N4espp7Ili934112send_commandE7uint8_t","espp::Ili9341::send_command"],[15,4,1,"_CPPv4N4espp7Ili934112send_commandE7uint8_t","espp::Ili9341::send_command::command"],[15,3,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data"],[15,4,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data::data"],[15,4,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data::flags"],[15,4,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data::length"],[15,3,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area"],[15,3,1,"_CPPv4N4espp7Ili934116set_drawing_areaEPK9lv_area_t","espp::Ili9341::set_drawing_area"],[15,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaEPK9lv_area_t","espp::Ili9341::set_drawing_area::area"],[15,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::xe"],[15,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::xs"],[15,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::ye"],[15,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::ys"],[15,3,1,"_CPPv4N4espp7Ili934110set_offsetEii","espp::Ili9341::set_offset"],[15,4,1,"_CPPv4N4espp7Ili934110set_offsetEii","espp::Ili9341::set_offset::x"],[15,4,1,"_CPPv4N4espp7Ili934110set_offsetEii","espp::Ili9341::set_offset::y"],[41,2,1,"_CPPv4N4espp8JoystickE","espp::Joystick"],[41,2,1,"_CPPv4N4espp8Joystick6ConfigE","espp::Joystick::Config"],[41,1,1,"_CPPv4N4espp8Joystick6Config8deadzoneE","espp::Joystick::Config::deadzone"],[41,1,1,"_CPPv4N4espp8Joystick6Config15deadzone_radiusE","espp::Joystick::Config::deadzone_radius"],[41,1,1,"_CPPv4N4espp8Joystick6Config10get_valuesE","espp::Joystick::Config::get_values"],[41,1,1,"_CPPv4N4espp8Joystick6Config9log_levelE","espp::Joystick::Config::log_level"],[41,1,1,"_CPPv4N4espp8Joystick6Config13x_calibrationE","espp::Joystick::Config::x_calibration"],[41,1,1,"_CPPv4N4espp8Joystick6Config13y_calibrationE","espp::Joystick::Config::y_calibration"],[41,6,1,"_CPPv4N4espp8Joystick8DeadzoneE","espp::Joystick::Deadzone"],[41,7,1,"_CPPv4N4espp8Joystick8Deadzone8CIRCULARE","espp::Joystick::Deadzone::CIRCULAR"],[41,7,1,"_CPPv4N4espp8Joystick8Deadzone11RECTANGULARE","espp::Joystick::Deadzone::RECTANGULAR"],[41,3,1,"_CPPv4N4espp8Joystick8JoystickERK6Config","espp::Joystick::Joystick"],[41,4,1,"_CPPv4N4espp8Joystick8JoystickERK6Config","espp::Joystick::Joystick::config"],[41,8,1,"_CPPv4N4espp8Joystick13get_values_fnE","espp::Joystick::get_values_fn"],[41,3,1,"_CPPv4NK4espp8Joystick8positionEv","espp::Joystick::position"],[41,3,1,"_CPPv4NK4espp8Joystick3rawEv","espp::Joystick::raw"],[41,3,1,"_CPPv4N4espp8Joystick15set_calibrationERKN16FloatRangeMapper6ConfigERKN16FloatRangeMapper6ConfigE","espp::Joystick::set_calibration"],[41,4,1,"_CPPv4N4espp8Joystick15set_calibrationERKN16FloatRangeMapper6ConfigERKN16FloatRangeMapper6ConfigE","espp::Joystick::set_calibration::x_calibration"],[41,4,1,"_CPPv4N4espp8Joystick15set_calibrationERKN16FloatRangeMapper6ConfigERKN16FloatRangeMapper6ConfigE","espp::Joystick::set_calibration::y_calibration"],[41,3,1,"_CPPv4N4espp8Joystick12set_deadzoneE8Deadzonef","espp::Joystick::set_deadzone"],[41,4,1,"_CPPv4N4espp8Joystick12set_deadzoneE8Deadzonef","espp::Joystick::set_deadzone::deadzone"],[41,4,1,"_CPPv4N4espp8Joystick12set_deadzoneE8Deadzonef","espp::Joystick::set_deadzone::radius"],[41,3,1,"_CPPv4N4espp8Joystick6updateEv","espp::Joystick::update"],[41,3,1,"_CPPv4NK4espp8Joystick1xEv","espp::Joystick::x"],[41,3,1,"_CPPv4NK4espp8Joystick1yEv","espp::Joystick::y"],[61,2,1,"_CPPv4N4espp9JpegFrameE","espp::JpegFrame"],[61,3,1,"_CPPv4N4espp9JpegFrame9JpegFrameEPKc6size_t","espp::JpegFrame::JpegFrame"],[61,3,1,"_CPPv4N4espp9JpegFrame9JpegFrameERK13RtpJpegPacket","espp::JpegFrame::JpegFrame"],[61,4,1,"_CPPv4N4espp9JpegFrame9JpegFrameEPKc6size_t","espp::JpegFrame::JpegFrame::data"],[61,4,1,"_CPPv4N4espp9JpegFrame9JpegFrameERK13RtpJpegPacket","espp::JpegFrame::JpegFrame::packet"],[61,4,1,"_CPPv4N4espp9JpegFrame9JpegFrameEPKc6size_t","espp::JpegFrame::JpegFrame::size"],[61,3,1,"_CPPv4N4espp9JpegFrame8add_scanERK13RtpJpegPacket","espp::JpegFrame::add_scan"],[61,4,1,"_CPPv4N4espp9JpegFrame8add_scanERK13RtpJpegPacket","espp::JpegFrame::add_scan::packet"],[61,3,1,"_CPPv4N4espp9JpegFrame6appendERK13RtpJpegPacket","espp::JpegFrame::append"],[61,4,1,"_CPPv4N4espp9JpegFrame6appendERK13RtpJpegPacket","espp::JpegFrame::append::packet"],[61,3,1,"_CPPv4NK4espp9JpegFrame8get_dataEv","espp::JpegFrame::get_data"],[61,3,1,"_CPPv4NK4espp9JpegFrame10get_headerEv","espp::JpegFrame::get_header"],[61,3,1,"_CPPv4NK4espp9JpegFrame10get_heightEv","espp::JpegFrame::get_height"],[61,3,1,"_CPPv4NK4espp9JpegFrame13get_scan_dataEv","espp::JpegFrame::get_scan_data"],[61,3,1,"_CPPv4NK4espp9JpegFrame9get_widthEv","espp::JpegFrame::get_width"],[61,3,1,"_CPPv4NK4espp9JpegFrame11is_completeEv","espp::JpegFrame::is_complete"],[61,2,1,"_CPPv4N4espp10JpegHeaderE","espp::JpegHeader"],[61,3,1,"_CPPv4N4espp10JpegHeader10JpegHeaderENSt11string_viewE","espp::JpegHeader::JpegHeader"],[61,3,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader"],[61,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderENSt11string_viewE","espp::JpegHeader::JpegHeader::data"],[61,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::height"],[61,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::q0_table"],[61,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::q1_table"],[61,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::width"],[61,3,1,"_CPPv4NK4espp10JpegHeader8get_dataEv","espp::JpegHeader::get_data"],[61,3,1,"_CPPv4NK4espp10JpegHeader10get_heightEv","espp::JpegHeader::get_height"],[61,3,1,"_CPPv4NK4espp10JpegHeader22get_quantization_tableEi","espp::JpegHeader::get_quantization_table"],[61,4,1,"_CPPv4NK4espp10JpegHeader22get_quantization_tableEi","espp::JpegHeader::get_quantization_table::index"],[61,3,1,"_CPPv4NK4espp10JpegHeader9get_widthEv","espp::JpegHeader::get_width"],[42,2,1,"_CPPv4N4espp3LedE","espp::Led"],[42,2,1,"_CPPv4N4espp3Led13ChannelConfigE","espp::Led::ChannelConfig"],[42,1,1,"_CPPv4N4espp3Led13ChannelConfig7channelE","espp::Led::ChannelConfig::channel"],[42,1,1,"_CPPv4N4espp3Led13ChannelConfig4dutyE","espp::Led::ChannelConfig::duty"],[42,1,1,"_CPPv4N4espp3Led13ChannelConfig4gpioE","espp::Led::ChannelConfig::gpio"],[42,1,1,"_CPPv4N4espp3Led13ChannelConfig13output_invertE","espp::Led::ChannelConfig::output_invert"],[42,1,1,"_CPPv4N4espp3Led13ChannelConfig10speed_modeE","espp::Led::ChannelConfig::speed_mode"],[42,1,1,"_CPPv4N4espp3Led13ChannelConfig5timerE","espp::Led::ChannelConfig::timer"],[42,2,1,"_CPPv4N4espp3Led6ConfigE","espp::Led::Config"],[42,1,1,"_CPPv4N4espp3Led6Config8channelsE","espp::Led::Config::channels"],[42,1,1,"_CPPv4N4espp3Led6Config15duty_resolutionE","espp::Led::Config::duty_resolution"],[42,1,1,"_CPPv4N4espp3Led6Config12frequency_hzE","espp::Led::Config::frequency_hz"],[42,1,1,"_CPPv4N4espp3Led6Config9log_levelE","espp::Led::Config::log_level"],[42,1,1,"_CPPv4N4espp3Led6Config10speed_modeE","espp::Led::Config::speed_mode"],[42,1,1,"_CPPv4N4espp3Led6Config5timerE","espp::Led::Config::timer"],[42,3,1,"_CPPv4N4espp3Led3LedERK6Config","espp::Led::Led"],[42,4,1,"_CPPv4N4espp3Led3LedERK6Config","espp::Led::Led::config"],[42,3,1,"_CPPv4N4espp3Led10can_changeE14ledc_channel_t","espp::Led::can_change"],[42,4,1,"_CPPv4N4espp3Led10can_changeE14ledc_channel_t","espp::Led::can_change::channel"],[42,3,1,"_CPPv4N4espp3Led8get_dutyE14ledc_channel_t","espp::Led::get_duty"],[42,4,1,"_CPPv4N4espp3Led8get_dutyE14ledc_channel_t","espp::Led::get_duty::channel"],[42,3,1,"_CPPv4N4espp3Led8set_dutyE14ledc_channel_tf","espp::Led::set_duty"],[42,4,1,"_CPPv4N4espp3Led8set_dutyE14ledc_channel_tf","espp::Led::set_duty::channel"],[42,4,1,"_CPPv4N4espp3Led8set_dutyE14ledc_channel_tf","espp::Led::set_duty::duty_percent"],[42,3,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time"],[42,4,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time::channel"],[42,4,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time::duty_percent"],[42,4,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time::fade_time_ms"],[42,3,1,"_CPPv4N4espp3LedD0Ev","espp::Led::~Led"],[43,2,1,"_CPPv4N4espp8LedStripE","espp::LedStrip"],[43,1,1,"_CPPv4N4espp8LedStrip18APA102_START_FRAMEE","espp::LedStrip::APA102_START_FRAME"],[43,6,1,"_CPPv4N4espp8LedStrip9ByteOrderE","espp::LedStrip::ByteOrder"],[43,7,1,"_CPPv4N4espp8LedStrip9ByteOrder3BGRE","espp::LedStrip::ByteOrder::BGR"],[43,7,1,"_CPPv4N4espp8LedStrip9ByteOrder3GRBE","espp::LedStrip::ByteOrder::GRB"],[43,7,1,"_CPPv4N4espp8LedStrip9ByteOrder3RGBE","espp::LedStrip::ByteOrder::RGB"],[43,2,1,"_CPPv4N4espp8LedStrip6ConfigE","espp::LedStrip::Config"],[43,1,1,"_CPPv4N4espp8LedStrip6Config10byte_orderE","espp::LedStrip::Config::byte_order"],[43,1,1,"_CPPv4N4espp8LedStrip6Config9end_frameE","espp::LedStrip::Config::end_frame"],[43,1,1,"_CPPv4N4espp8LedStrip6Config9log_levelE","espp::LedStrip::Config::log_level"],[43,1,1,"_CPPv4N4espp8LedStrip6Config8num_ledsE","espp::LedStrip::Config::num_leds"],[43,1,1,"_CPPv4N4espp8LedStrip6Config15send_brightnessE","espp::LedStrip::Config::send_brightness"],[43,1,1,"_CPPv4N4espp8LedStrip6Config11start_frameE","espp::LedStrip::Config::start_frame"],[43,1,1,"_CPPv4N4espp8LedStrip6Config5writeE","espp::LedStrip::Config::write"],[43,3,1,"_CPPv4N4espp8LedStrip8LedStripERK6Config","espp::LedStrip::LedStrip"],[43,4,1,"_CPPv4N4espp8LedStrip8LedStripERK6Config","espp::LedStrip::LedStrip::config"],[43,3,1,"_CPPv4NK4espp8LedStrip10byte_orderEv","espp::LedStrip::byte_order"],[43,3,1,"_CPPv4NK4espp8LedStrip8num_ledsEv","espp::LedStrip::num_leds"],[43,3,1,"_CPPv4N4espp8LedStrip7set_allE3Hsvf","espp::LedStrip::set_all"],[43,3,1,"_CPPv4N4espp8LedStrip7set_allE3Rgbf","espp::LedStrip::set_all"],[43,3,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::b"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE3Hsvf","espp::LedStrip::set_all::brightness"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE3Rgbf","espp::LedStrip::set_all::brightness"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::brightness"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::g"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE3Hsvf","espp::LedStrip::set_all::hsv"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::r"],[43,4,1,"_CPPv4N4espp8LedStrip7set_allE3Rgbf","espp::LedStrip::set_all::rgb"],[43,3,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel"],[43,3,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel"],[43,3,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::b"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel::brightness"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel::brightness"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::brightness"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::g"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel::hsv"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel::index"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel::index"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::index"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::r"],[43,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel::rgb"],[43,3,1,"_CPPv4N4espp8LedStrip10shift_leftEi","espp::LedStrip::shift_left"],[43,4,1,"_CPPv4N4espp8LedStrip10shift_leftEi","espp::LedStrip::shift_left::shift_by"],[43,3,1,"_CPPv4N4espp8LedStrip11shift_rightEi","espp::LedStrip::shift_right"],[43,4,1,"_CPPv4N4espp8LedStrip11shift_rightEi","espp::LedStrip::shift_right::shift_by"],[43,3,1,"_CPPv4N4espp8LedStrip4showEv","espp::LedStrip::show"],[43,8,1,"_CPPv4N4espp8LedStrip8write_fnE","espp::LedStrip::write_fn"],[10,2,1,"_CPPv4N4espp9LineInputE","espp::LineInput"],[10,8,1,"_CPPv4N4espp9LineInput7HistoryE","espp::LineInput::History"],[10,3,1,"_CPPv4N4espp9LineInput9LineInputEv","espp::LineInput::LineInput"],[10,3,1,"_CPPv4NK4espp9LineInput11get_historyEv","espp::LineInput::get_history"],[10,3,1,"_CPPv4N4espp9LineInput14get_user_inputERNSt7istreamE9prompt_fn","espp::LineInput::get_user_input"],[10,4,1,"_CPPv4N4espp9LineInput14get_user_inputERNSt7istreamE9prompt_fn","espp::LineInput::get_user_input::is"],[10,4,1,"_CPPv4N4espp9LineInput14get_user_inputERNSt7istreamE9prompt_fn","espp::LineInput::get_user_input::prompt"],[10,8,1,"_CPPv4N4espp9LineInput9prompt_fnE","espp::LineInput::prompt_fn"],[10,3,1,"_CPPv4N4espp9LineInput11set_historyERK7History","espp::LineInput::set_history"],[10,4,1,"_CPPv4N4espp9LineInput11set_historyERK7History","espp::LineInput::set_history::history"],[10,3,1,"_CPPv4N4espp9LineInput16set_history_sizeE6size_t","espp::LineInput::set_history_size"],[10,4,1,"_CPPv4N4espp9LineInput16set_history_sizeE6size_t","espp::LineInput::set_history_size::new_size"],[10,3,1,"_CPPv4N4espp9LineInputD0Ev","espp::LineInput::~LineInput"],[44,2,1,"_CPPv4N4espp6LoggerE","espp::Logger"],[44,2,1,"_CPPv4N4espp6Logger6ConfigE","espp::Logger::Config"],[44,1,1,"_CPPv4N4espp6Logger6Config5levelE","espp::Logger::Config::level"],[44,1,1,"_CPPv4N4espp6Logger6Config10rate_limitE","espp::Logger::Config::rate_limit"],[44,1,1,"_CPPv4N4espp6Logger6Config3tagE","espp::Logger::Config::tag"],[44,3,1,"_CPPv4N4espp6Logger6LoggerERK6Config","espp::Logger::Logger"],[44,4,1,"_CPPv4N4espp6Logger6LoggerERK6Config","espp::Logger::Logger::config"],[44,6,1,"_CPPv4N4espp6Logger9VerbosityE","espp::Logger::Verbosity"],[44,7,1,"_CPPv4N4espp6Logger9Verbosity5DEBUGE","espp::Logger::Verbosity::DEBUG"],[44,7,1,"_CPPv4N4espp6Logger9Verbosity5ERRORE","espp::Logger::Verbosity::ERROR"],[44,7,1,"_CPPv4N4espp6Logger9Verbosity4INFOE","espp::Logger::Verbosity::INFO"],[44,7,1,"_CPPv4N4espp6Logger9Verbosity4NONEE","espp::Logger::Verbosity::NONE"],[44,7,1,"_CPPv4N4espp6Logger9Verbosity4WARNE","espp::Logger::Verbosity::WARN"],[44,3,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug"],[44,5,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited"],[44,5,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error"],[44,5,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited"],[44,5,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format"],[44,5,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info"],[44,5,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited"],[44,5,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited::rt_fmt_str"],[44,3,1,"_CPPv4N4espp6Logger13set_verbosityEK9Verbosity","espp::Logger::set_verbosity"],[44,4,1,"_CPPv4N4espp6Logger13set_verbosityEK9Verbosity","espp::Logger::set_verbosity::level"],[44,3,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn"],[44,5,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn::rt_fmt_str"],[44,3,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited"],[44,5,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited::Args"],[44,4,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited::args"],[44,4,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited::rt_fmt_str"],[27,2,1,"_CPPv4N4espp13LowpassFilterE","espp::LowpassFilter"],[27,2,1,"_CPPv4N4espp13LowpassFilter6ConfigE","espp::LowpassFilter::Config"],[27,1,1,"_CPPv4N4espp13LowpassFilter6Config27normalized_cutoff_frequencyE","espp::LowpassFilter::Config::normalized_cutoff_frequency"],[27,1,1,"_CPPv4N4espp13LowpassFilter6Config8q_factorE","espp::LowpassFilter::Config::q_factor"],[27,3,1,"_CPPv4N4espp13LowpassFilter13LowpassFilterERK6Config","espp::LowpassFilter::LowpassFilter"],[27,4,1,"_CPPv4N4espp13LowpassFilter13LowpassFilterERK6Config","espp::LowpassFilter::LowpassFilter::config"],[27,3,1,"_CPPv4N4espp13LowpassFilterclEf","espp::LowpassFilter::operator()"],[27,4,1,"_CPPv4N4espp13LowpassFilterclEf","espp::LowpassFilter::operator()::input"],[27,3,1,"_CPPv4N4espp13LowpassFilter6updateEKf","espp::LowpassFilter::update"],[27,3,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update"],[27,4,1,"_CPPv4N4espp13LowpassFilter6updateEKf","espp::LowpassFilter::update::input"],[27,4,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update::input"],[27,4,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update::length"],[27,4,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update::output"],[40,2,1,"_CPPv4N4espp8Mcp23x17E","espp::Mcp23x17"],[40,2,1,"_CPPv4N4espp8Mcp23x176ConfigE","espp::Mcp23x17::Config"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config14device_addressE","espp::Mcp23x17::Config::device_address"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config9log_levelE","espp::Mcp23x17::Config::log_level"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config21port_a_direction_maskE","espp::Mcp23x17::Config::port_a_direction_mask"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config21port_a_interrupt_maskE","espp::Mcp23x17::Config::port_a_interrupt_mask"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config21port_b_direction_maskE","espp::Mcp23x17::Config::port_b_direction_mask"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config21port_b_interrupt_maskE","espp::Mcp23x17::Config::port_b_interrupt_mask"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config4readE","espp::Mcp23x17::Config::read"],[40,1,1,"_CPPv4N4espp8Mcp23x176Config5writeE","espp::Mcp23x17::Config::write"],[40,1,1,"_CPPv4N4espp8Mcp23x1715DEFAULT_ADDRESSE","espp::Mcp23x17::DEFAULT_ADDRESS"],[40,3,1,"_CPPv4N4espp8Mcp23x178Mcp23x17ERK6Config","espp::Mcp23x17::Mcp23x17"],[40,4,1,"_CPPv4N4espp8Mcp23x178Mcp23x17ERK6Config","espp::Mcp23x17::Mcp23x17::config"],[40,6,1,"_CPPv4N4espp8Mcp23x174PortE","espp::Mcp23x17::Port"],[40,7,1,"_CPPv4N4espp8Mcp23x174Port1AE","espp::Mcp23x17::Port::A"],[40,7,1,"_CPPv4N4espp8Mcp23x174Port1BE","espp::Mcp23x17::Port::B"],[40,3,1,"_CPPv4N4espp8Mcp23x1721get_interrupt_captureE4Port","espp::Mcp23x17::get_interrupt_capture"],[40,4,1,"_CPPv4N4espp8Mcp23x1721get_interrupt_captureE4Port","espp::Mcp23x17::get_interrupt_capture::port"],[40,3,1,"_CPPv4N4espp8Mcp23x178get_pinsE4Port","espp::Mcp23x17::get_pins"],[40,4,1,"_CPPv4N4espp8Mcp23x178get_pinsE4Port","espp::Mcp23x17::get_pins::port"],[40,8,1,"_CPPv4N4espp8Mcp23x177read_fnE","espp::Mcp23x17::read_fn"],[40,3,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_t","espp::Mcp23x17::set_direction"],[40,4,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_t","espp::Mcp23x17::set_direction::mask"],[40,4,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_t","espp::Mcp23x17::set_direction::port"],[40,3,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_t","espp::Mcp23x17::set_input_polarity"],[40,4,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_t","espp::Mcp23x17::set_input_polarity::mask"],[40,4,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_t","espp::Mcp23x17::set_input_polarity::port"],[40,3,1,"_CPPv4N4espp8Mcp23x1720set_interrupt_mirrorEb","espp::Mcp23x17::set_interrupt_mirror"],[40,4,1,"_CPPv4N4espp8Mcp23x1720set_interrupt_mirrorEb","espp::Mcp23x17::set_interrupt_mirror::mirror"],[40,3,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_t","espp::Mcp23x17::set_interrupt_on_change"],[40,4,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_t","espp::Mcp23x17::set_interrupt_on_change::mask"],[40,4,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_t","espp::Mcp23x17::set_interrupt_on_change::port"],[40,3,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_t","espp::Mcp23x17::set_interrupt_on_value"],[40,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_t","espp::Mcp23x17::set_interrupt_on_value::pin_mask"],[40,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_t","espp::Mcp23x17::set_interrupt_on_value::port"],[40,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_t","espp::Mcp23x17::set_interrupt_on_value::val_mask"],[40,3,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_polarityEb","espp::Mcp23x17::set_interrupt_polarity"],[40,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_polarityEb","espp::Mcp23x17::set_interrupt_polarity::active_high"],[40,3,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_t","espp::Mcp23x17::set_pins"],[40,4,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_t","espp::Mcp23x17::set_pins::output"],[40,4,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_t","espp::Mcp23x17::set_pins::port"],[40,3,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_t","espp::Mcp23x17::set_pull_up"],[40,4,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_t","espp::Mcp23x17::set_pull_up::mask"],[40,4,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_t","espp::Mcp23x17::set_pull_up::port"],[40,8,1,"_CPPv4N4espp8Mcp23x178write_fnE","espp::Mcp23x17::write_fn"],[21,2,1,"_CPPv4N4espp6Mt6701E","espp::Mt6701"],[21,1,1,"_CPPv4N4espp6Mt670121COUNTS_PER_REVOLUTIONE","espp::Mt6701::COUNTS_PER_REVOLUTION"],[21,1,1,"_CPPv4N4espp6Mt670123COUNTS_PER_REVOLUTION_FE","espp::Mt6701::COUNTS_PER_REVOLUTION_F"],[21,1,1,"_CPPv4N4espp6Mt670117COUNTS_TO_DEGREESE","espp::Mt6701::COUNTS_TO_DEGREES"],[21,1,1,"_CPPv4N4espp6Mt670117COUNTS_TO_RADIANSE","espp::Mt6701::COUNTS_TO_RADIANS"],[21,2,1,"_CPPv4N4espp6Mt67016ConfigE","espp::Mt6701::Config"],[21,1,1,"_CPPv4N4espp6Mt67016Config14device_addressE","espp::Mt6701::Config::device_address"],[21,1,1,"_CPPv4N4espp6Mt67016Config4readE","espp::Mt6701::Config::read"],[21,1,1,"_CPPv4N4espp6Mt67016Config13update_periodE","espp::Mt6701::Config::update_period"],[21,1,1,"_CPPv4N4espp6Mt67016Config15velocity_filterE","espp::Mt6701::Config::velocity_filter"],[21,1,1,"_CPPv4N4espp6Mt67016Config5writeE","espp::Mt6701::Config::write"],[21,1,1,"_CPPv4N4espp6Mt670115DEFAULT_ADDRESSE","espp::Mt6701::DEFAULT_ADDRESS"],[21,3,1,"_CPPv4N4espp6Mt67016Mt6701ERK6Config","espp::Mt6701::Mt6701"],[21,4,1,"_CPPv4N4espp6Mt67016Mt6701ERK6Config","espp::Mt6701::Mt6701::config"],[21,1,1,"_CPPv4N4espp6Mt670118SECONDS_PER_MINUTEE","espp::Mt6701::SECONDS_PER_MINUTE"],[21,3,1,"_CPPv4NK4espp6Mt670115get_accumulatorEv","espp::Mt6701::get_accumulator"],[21,3,1,"_CPPv4NK4espp6Mt67019get_countEv","espp::Mt6701::get_count"],[21,3,1,"_CPPv4NK4espp6Mt670111get_degreesEv","espp::Mt6701::get_degrees"],[21,3,1,"_CPPv4NK4espp6Mt670122get_mechanical_degreesEv","espp::Mt6701::get_mechanical_degrees"],[21,3,1,"_CPPv4NK4espp6Mt670122get_mechanical_radiansEv","espp::Mt6701::get_mechanical_radians"],[21,3,1,"_CPPv4NK4espp6Mt670111get_radiansEv","espp::Mt6701::get_radians"],[21,3,1,"_CPPv4NK4espp6Mt67017get_rpmEv","espp::Mt6701::get_rpm"],[21,3,1,"_CPPv4NK4espp6Mt670117needs_zero_searchEv","espp::Mt6701::needs_zero_search"],[21,8,1,"_CPPv4N4espp6Mt67017read_fnE","espp::Mt6701::read_fn"],[21,8,1,"_CPPv4N4espp6Mt670118velocity_filter_fnE","espp::Mt6701::velocity_filter_fn"],[21,8,1,"_CPPv4N4espp6Mt67018write_fnE","espp::Mt6701::write_fn"],[57,2,1,"_CPPv4N4espp4NdefE","espp::Ndef"],[57,6,1,"_CPPv4N4espp4Ndef7BleRoleE","espp::Ndef::BleRole"],[57,7,1,"_CPPv4N4espp4Ndef7BleRole12CENTRAL_ONLYE","espp::Ndef::BleRole::CENTRAL_ONLY"],[57,7,1,"_CPPv4N4espp4Ndef7BleRole18CENTRAL_PERIPHERALE","espp::Ndef::BleRole::CENTRAL_PERIPHERAL"],[57,7,1,"_CPPv4N4espp4Ndef7BleRole18PERIPHERAL_CENTRALE","espp::Ndef::BleRole::PERIPHERAL_CENTRAL"],[57,7,1,"_CPPv4N4espp4Ndef7BleRole15PERIPHERAL_ONLYE","espp::Ndef::BleRole::PERIPHERAL_ONLY"],[57,6,1,"_CPPv4N4espp4Ndef12BtAppearanceE","espp::Ndef::BtAppearance"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance5CLOCKE","espp::Ndef::BtAppearance::CLOCK"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance8COMPUTERE","espp::Ndef::BtAppearance::COMPUTER"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance7DISPLAYE","espp::Ndef::BtAppearance::DISPLAY"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance7GAMEPADE","espp::Ndef::BtAppearance::GAMEPAD"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance6GAMINGE","espp::Ndef::BtAppearance::GAMING"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance11GENERIC_HIDE","espp::Ndef::BtAppearance::GENERIC_HID"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance8JOYSTICKE","espp::Ndef::BtAppearance::JOYSTICK"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance8KEYBOARDE","espp::Ndef::BtAppearance::KEYBOARD"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance5MOUSEE","espp::Ndef::BtAppearance::MOUSE"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance5PHONEE","espp::Ndef::BtAppearance::PHONE"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance14REMOTE_CONTROLE","espp::Ndef::BtAppearance::REMOTE_CONTROL"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance8TOUCHPADE","espp::Ndef::BtAppearance::TOUCHPAD"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance7UNKNOWNE","espp::Ndef::BtAppearance::UNKNOWN"],[57,7,1,"_CPPv4N4espp4Ndef12BtAppearance5WATCHE","espp::Ndef::BtAppearance::WATCH"],[57,6,1,"_CPPv4N4espp4Ndef5BtEirE","espp::Ndef::BtEir"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir10APPEARANCEE","espp::Ndef::BtEir::APPEARANCE"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir15CLASS_OF_DEVICEE","espp::Ndef::BtEir::CLASS_OF_DEVICE"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir5FLAGSE","espp::Ndef::BtEir::FLAGS"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir7LE_ROLEE","espp::Ndef::BtEir::LE_ROLE"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir18LE_SC_CONFIRMATIONE","espp::Ndef::BtEir::LE_SC_CONFIRMATION"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir12LE_SC_RANDOME","espp::Ndef::BtEir::LE_SC_RANDOM"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir15LONG_LOCAL_NAMEE","espp::Ndef::BtEir::LONG_LOCAL_NAME"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir3MACE","espp::Ndef::BtEir::MAC"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir22SECURITY_MANAGER_FLAGSE","espp::Ndef::BtEir::SECURITY_MANAGER_FLAGS"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir19SECURITY_MANAGER_TKE","espp::Ndef::BtEir::SECURITY_MANAGER_TK"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir16SHORT_LOCAL_NAMEE","espp::Ndef::BtEir::SHORT_LOCAL_NAME"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir12SP_HASH_C192E","espp::Ndef::BtEir::SP_HASH_C192"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir12SP_HASH_C256E","espp::Ndef::BtEir::SP_HASH_C256"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir12SP_HASH_R256E","espp::Ndef::BtEir::SP_HASH_R256"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir14SP_RANDOM_R192E","espp::Ndef::BtEir::SP_RANDOM_R192"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir14TX_POWER_LEVELE","espp::Ndef::BtEir::TX_POWER_LEVEL"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir22UUIDS_128_BIT_COMPLETEE","espp::Ndef::BtEir::UUIDS_128_BIT_COMPLETE"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir21UUIDS_128_BIT_PARTIALE","espp::Ndef::BtEir::UUIDS_128_BIT_PARTIAL"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir21UUIDS_16_BIT_COMPLETEE","espp::Ndef::BtEir::UUIDS_16_BIT_COMPLETE"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir20UUIDS_16_BIT_PARTIALE","espp::Ndef::BtEir::UUIDS_16_BIT_PARTIAL"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir21UUIDS_32_BIT_COMPLETEE","espp::Ndef::BtEir::UUIDS_32_BIT_COMPLETE"],[57,7,1,"_CPPv4N4espp4Ndef5BtEir20UUIDS_32_BIT_PARTIALE","espp::Ndef::BtEir::UUIDS_32_BIT_PARTIAL"],[57,6,1,"_CPPv4N4espp4Ndef6BtTypeE","espp::Ndef::BtType"],[57,7,1,"_CPPv4N4espp4Ndef6BtType3BLEE","espp::Ndef::BtType::BLE"],[57,7,1,"_CPPv4N4espp4Ndef6BtType5BREDRE","espp::Ndef::BtType::BREDR"],[57,3,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef"],[57,4,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef::payload"],[57,4,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef::tnf"],[57,4,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef::type"],[57,6,1,"_CPPv4N4espp4Ndef3TNFE","espp::Ndef::TNF"],[57,7,1,"_CPPv4N4espp4Ndef3TNF12ABSOLUTE_URIE","espp::Ndef::TNF::ABSOLUTE_URI"],[57,7,1,"_CPPv4N4espp4Ndef3TNF5EMPTYE","espp::Ndef::TNF::EMPTY"],[57,7,1,"_CPPv4N4espp4Ndef3TNF13EXTERNAL_TYPEE","espp::Ndef::TNF::EXTERNAL_TYPE"],[57,7,1,"_CPPv4N4espp4Ndef3TNF10MIME_MEDIAE","espp::Ndef::TNF::MIME_MEDIA"],[57,7,1,"_CPPv4N4espp4Ndef3TNF8RESERVEDE","espp::Ndef::TNF::RESERVED"],[57,7,1,"_CPPv4N4espp4Ndef3TNF9UNCHANGEDE","espp::Ndef::TNF::UNCHANGED"],[57,7,1,"_CPPv4N4espp4Ndef3TNF7UNKNOWNE","espp::Ndef::TNF::UNKNOWN"],[57,7,1,"_CPPv4N4espp4Ndef3TNF10WELL_KNOWNE","espp::Ndef::TNF::WELL_KNOWN"],[57,6,1,"_CPPv4N4espp4Ndef3UicE","espp::Ndef::Uic"],[57,7,1,"_CPPv4N4espp4Ndef3Uic6BTGOEPE","espp::Ndef::Uic::BTGOEP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic7BTL2CAPE","espp::Ndef::Uic::BTL2CAP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic5BTSPPE","espp::Ndef::Uic::BTSPP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3DAVE","espp::Ndef::Uic::DAV"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4FILEE","espp::Ndef::Uic::FILE"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3FTPE","espp::Ndef::Uic::FTP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4FTPSE","espp::Ndef::Uic::FTPS"],[57,7,1,"_CPPv4N4espp4Ndef3Uic8FTP_ANONE","espp::Ndef::Uic::FTP_ANON"],[57,7,1,"_CPPv4N4espp4Ndef3Uic7FTP_FTPE","espp::Ndef::Uic::FTP_FTP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4HTTPE","espp::Ndef::Uic::HTTP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic5HTTPSE","espp::Ndef::Uic::HTTPS"],[57,7,1,"_CPPv4N4espp4Ndef3Uic9HTTPS_WWWE","espp::Ndef::Uic::HTTPS_WWW"],[57,7,1,"_CPPv4N4espp4Ndef3Uic8HTTP_WWWE","espp::Ndef::Uic::HTTP_WWW"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4IMAPE","espp::Ndef::Uic::IMAP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic8IRDAOBEXE","espp::Ndef::Uic::IRDAOBEX"],[57,7,1,"_CPPv4N4espp4Ndef3Uic6MAILTOE","espp::Ndef::Uic::MAILTO"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4NEWSE","espp::Ndef::Uic::NEWS"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3NFSE","espp::Ndef::Uic::NFS"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4NONEE","espp::Ndef::Uic::NONE"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3POPE","espp::Ndef::Uic::POP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4RSTPE","espp::Ndef::Uic::RSTP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4SFTPE","espp::Ndef::Uic::SFTP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3SIPE","espp::Ndef::Uic::SIP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4SIPSE","espp::Ndef::Uic::SIPS"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3SMBE","espp::Ndef::Uic::SMB"],[57,7,1,"_CPPv4N4espp4Ndef3Uic7TCPOBEXE","espp::Ndef::Uic::TCPOBEX"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3TELE","espp::Ndef::Uic::TEL"],[57,7,1,"_CPPv4N4espp4Ndef3Uic6TELNETE","espp::Ndef::Uic::TELNET"],[57,7,1,"_CPPv4N4espp4Ndef3Uic4TFTPE","espp::Ndef::Uic::TFTP"],[57,7,1,"_CPPv4N4espp4Ndef3Uic3URNE","espp::Ndef::Uic::URN"],[57,7,1,"_CPPv4N4espp4Ndef3Uic7URN_EPCE","espp::Ndef::Uic::URN_EPC"],[57,7,1,"_CPPv4N4espp4Ndef3Uic10URN_EPC_IDE","espp::Ndef::Uic::URN_EPC_ID"],[57,7,1,"_CPPv4N4espp4Ndef3Uic11URN_EPC_PATE","espp::Ndef::Uic::URN_EPC_PAT"],[57,7,1,"_CPPv4N4espp4Ndef3Uic11URN_EPC_RAWE","espp::Ndef::Uic::URN_EPC_RAW"],[57,7,1,"_CPPv4N4espp4Ndef3Uic11URN_EPC_TAGE","espp::Ndef::Uic::URN_EPC_TAG"],[57,7,1,"_CPPv4N4espp4Ndef3Uic7URN_NFCE","espp::Ndef::Uic::URN_NFC"],[57,6,1,"_CPPv4N4espp4Ndef22WifiAuthenticationTypeE","espp::Ndef::WifiAuthenticationType"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType4OPENE","espp::Ndef::WifiAuthenticationType::OPEN"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType6SHAREDE","espp::Ndef::WifiAuthenticationType::SHARED"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType15WPA2_ENTERPRISEE","espp::Ndef::WifiAuthenticationType::WPA2_ENTERPRISE"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType13WPA2_PERSONALE","espp::Ndef::WifiAuthenticationType::WPA2_PERSONAL"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType14WPA_ENTERPRISEE","espp::Ndef::WifiAuthenticationType::WPA_ENTERPRISE"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType12WPA_PERSONALE","espp::Ndef::WifiAuthenticationType::WPA_PERSONAL"],[57,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType17WPA_WPA2_PERSONALE","espp::Ndef::WifiAuthenticationType::WPA_WPA2_PERSONAL"],[57,2,1,"_CPPv4N4espp4Ndef10WifiConfigE","espp::Ndef::WifiConfig"],[57,1,1,"_CPPv4N4espp4Ndef10WifiConfig14authenticationE","espp::Ndef::WifiConfig::authentication"],[57,1,1,"_CPPv4N4espp4Ndef10WifiConfig10encryptionE","espp::Ndef::WifiConfig::encryption"],[57,1,1,"_CPPv4N4espp4Ndef10WifiConfig3keyE","espp::Ndef::WifiConfig::key"],[57,1,1,"_CPPv4N4espp4Ndef10WifiConfig11mac_addressE","espp::Ndef::WifiConfig::mac_address"],[57,1,1,"_CPPv4N4espp4Ndef10WifiConfig4ssidE","espp::Ndef::WifiConfig::ssid"],[57,6,1,"_CPPv4N4espp4Ndef18WifiEncryptionTypeE","espp::Ndef::WifiEncryptionType"],[57,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType3AESE","espp::Ndef::WifiEncryptionType::AES"],[57,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType4NONEE","espp::Ndef::WifiEncryptionType::NONE"],[57,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType4TKIPE","espp::Ndef::WifiEncryptionType::TKIP"],[57,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType3WEPE","espp::Ndef::WifiEncryptionType::WEP"],[57,3,1,"_CPPv4NK4espp4Ndef8get_sizeEv","espp::Ndef::get_size"],[57,3,1,"_CPPv4N4espp4Ndef21make_android_launcherENSt11string_viewE","espp::Ndef::make_android_launcher"],[57,4,1,"_CPPv4N4espp4Ndef21make_android_launcherENSt11string_viewE","espp::Ndef::make_android_launcher::uri"],[57,3,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearance","espp::Ndef::make_le_oob_pairing"],[57,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearance","espp::Ndef::make_le_oob_pairing::appearance"],[57,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearance","espp::Ndef::make_le_oob_pairing::mac_addr"],[57,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearance","espp::Ndef::make_le_oob_pairing::name"],[57,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearance","espp::Ndef::make_le_oob_pairing::role"],[57,3,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewE","espp::Ndef::make_oob_pairing"],[57,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewE","espp::Ndef::make_oob_pairing::device_class"],[57,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewE","espp::Ndef::make_oob_pairing::mac_addr"],[57,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewE","espp::Ndef::make_oob_pairing::name"],[57,3,1,"_CPPv4N4espp4Ndef9make_textENSt11string_viewE","espp::Ndef::make_text"],[57,4,1,"_CPPv4N4espp4Ndef9make_textENSt11string_viewE","espp::Ndef::make_text::text"],[57,3,1,"_CPPv4N4espp4Ndef8make_uriENSt11string_viewE3Uic","espp::Ndef::make_uri"],[57,4,1,"_CPPv4N4espp4Ndef8make_uriENSt11string_viewE3Uic","espp::Ndef::make_uri::uic"],[57,4,1,"_CPPv4N4espp4Ndef8make_uriENSt11string_viewE3Uic","espp::Ndef::make_uri::uri"],[57,3,1,"_CPPv4N4espp4Ndef16make_wifi_configERK10WifiConfig","espp::Ndef::make_wifi_config"],[57,4,1,"_CPPv4N4espp4Ndef16make_wifi_configERK10WifiConfig","espp::Ndef::make_wifi_config::config"],[57,3,1,"_CPPv4N4espp4Ndef7payloadEv","espp::Ndef::payload"],[57,3,1,"_CPPv4N4espp4Ndef9serializeEv","espp::Ndef::serialize"],[5,2,1,"_CPPv4N4espp10OneshotAdcE","espp::OneshotAdc"],[5,2,1,"_CPPv4N4espp10OneshotAdc6ConfigE","espp::OneshotAdc::Config"],[5,1,1,"_CPPv4N4espp10OneshotAdc6Config8channelsE","espp::OneshotAdc::Config::channels"],[5,1,1,"_CPPv4N4espp10OneshotAdc6Config9log_levelE","espp::OneshotAdc::Config::log_level"],[5,1,1,"_CPPv4N4espp10OneshotAdc6Config4unitE","espp::OneshotAdc::Config::unit"],[5,3,1,"_CPPv4N4espp10OneshotAdc10OneshotAdcERK6Config","espp::OneshotAdc::OneshotAdc"],[5,4,1,"_CPPv4N4espp10OneshotAdc10OneshotAdcERK6Config","espp::OneshotAdc::OneshotAdc::config"],[5,3,1,"_CPPv4N4espp10OneshotAdc7read_mvERK9AdcConfig","espp::OneshotAdc::read_mv"],[5,4,1,"_CPPv4N4espp10OneshotAdc7read_mvERK9AdcConfig","espp::OneshotAdc::read_mv::config"],[5,3,1,"_CPPv4N4espp10OneshotAdc8read_rawERK9AdcConfig","espp::OneshotAdc::read_raw"],[5,4,1,"_CPPv4N4espp10OneshotAdc8read_rawERK9AdcConfig","espp::OneshotAdc::read_raw::config"],[5,3,1,"_CPPv4N4espp10OneshotAdcD0Ev","espp::OneshotAdc::~OneshotAdc"],[59,2,1,"_CPPv4N4espp3PidE","espp::Pid"],[59,2,1,"_CPPv4N4espp3Pid6ConfigE","espp::Pid::Config"],[59,1,1,"_CPPv4N4espp3Pid6Config14integrator_maxE","espp::Pid::Config::integrator_max"],[59,1,1,"_CPPv4N4espp3Pid6Config14integrator_minE","espp::Pid::Config::integrator_min"],[59,1,1,"_CPPv4N4espp3Pid6Config2kdE","espp::Pid::Config::kd"],[59,1,1,"_CPPv4N4espp3Pid6Config2kiE","espp::Pid::Config::ki"],[59,1,1,"_CPPv4N4espp3Pid6Config2kpE","espp::Pid::Config::kp"],[59,1,1,"_CPPv4N4espp3Pid6Config9log_levelE","espp::Pid::Config::log_level"],[59,1,1,"_CPPv4N4espp3Pid6Config10output_maxE","espp::Pid::Config::output_max"],[59,1,1,"_CPPv4N4espp3Pid6Config10output_minE","espp::Pid::Config::output_min"],[59,3,1,"_CPPv4N4espp3Pid3PidERK6Config","espp::Pid::Pid"],[59,4,1,"_CPPv4N4espp3Pid3PidERK6Config","espp::Pid::Pid::config"],[59,3,1,"_CPPv4N4espp3Pid12change_gainsERK6Configb","espp::Pid::change_gains"],[59,4,1,"_CPPv4N4espp3Pid12change_gainsERK6Configb","espp::Pid::change_gains::config"],[59,4,1,"_CPPv4N4espp3Pid12change_gainsERK6Configb","espp::Pid::change_gains::reset_state"],[59,3,1,"_CPPv4N4espp3Pid5clearEv","espp::Pid::clear"],[59,3,1,"_CPPv4NK4espp3Pid10get_configEv","espp::Pid::get_config"],[59,3,1,"_CPPv4NK4espp3Pid9get_errorEv","espp::Pid::get_error"],[59,3,1,"_CPPv4NK4espp3Pid14get_integratorEv","espp::Pid::get_integrator"],[59,3,1,"_CPPv4N4espp3PidclEf","espp::Pid::operator()"],[59,4,1,"_CPPv4N4espp3PidclEf","espp::Pid::operator()::error"],[59,3,1,"_CPPv4N4espp3Pid10set_configERK6Configb","espp::Pid::set_config"],[59,4,1,"_CPPv4N4espp3Pid10set_configERK6Configb","espp::Pid::set_config::config"],[59,4,1,"_CPPv4N4espp3Pid10set_configERK6Configb","espp::Pid::set_config::reset_state"],[59,3,1,"_CPPv4N4espp3Pid6updateEf","espp::Pid::update"],[59,4,1,"_CPPv4N4espp3Pid6updateEf","espp::Pid::update::error"],[49,2,1,"_CPPv4I0EN4espp11RangeMapperE","espp::RangeMapper"],[49,2,1,"_CPPv4N4espp11RangeMapper6ConfigE","espp::RangeMapper::Config"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config6centerE","espp::RangeMapper::Config::center"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config8deadbandE","espp::RangeMapper::Config::deadband"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config12invert_inputE","espp::RangeMapper::Config::invert_input"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config13invert_outputE","espp::RangeMapper::Config::invert_output"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config7maximumE","espp::RangeMapper::Config::maximum"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config7minimumE","espp::RangeMapper::Config::minimum"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config13output_centerE","espp::RangeMapper::Config::output_center"],[49,1,1,"_CPPv4N4espp11RangeMapper6Config12output_rangeE","espp::RangeMapper::Config::output_range"],[49,3,1,"_CPPv4N4espp11RangeMapper11RangeMapperERK6Config","espp::RangeMapper::RangeMapper"],[49,4,1,"_CPPv4N4espp11RangeMapper11RangeMapperERK6Config","espp::RangeMapper::RangeMapper::config"],[49,5,1,"_CPPv4I0EN4espp11RangeMapperE","espp::RangeMapper::T"],[49,3,1,"_CPPv4N4espp11RangeMapper9configureERK6Config","espp::RangeMapper::configure"],[49,4,1,"_CPPv4N4espp11RangeMapper9configureERK6Config","espp::RangeMapper::configure::config"],[49,3,1,"_CPPv4NK4espp11RangeMapper17get_output_centerEv","espp::RangeMapper::get_output_center"],[49,3,1,"_CPPv4NK4espp11RangeMapper14get_output_maxEv","espp::RangeMapper::get_output_max"],[49,3,1,"_CPPv4NK4espp11RangeMapper14get_output_minEv","espp::RangeMapper::get_output_min"],[49,3,1,"_CPPv4NK4espp11RangeMapper16get_output_rangeEv","espp::RangeMapper::get_output_range"],[49,3,1,"_CPPv4N4espp11RangeMapper3mapERK1T","espp::RangeMapper::map"],[49,4,1,"_CPPv4N4espp11RangeMapper3mapERK1T","espp::RangeMapper::map::v"],[11,2,1,"_CPPv4N4espp3RgbE","espp::Rgb"],[11,3,1,"_CPPv4N4espp3Rgb3RgbERK3Hsv","espp::Rgb::Rgb"],[11,3,1,"_CPPv4N4espp3Rgb3RgbERK3Rgb","espp::Rgb::Rgb"],[11,3,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb"],[11,4,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb::b"],[11,4,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb::g"],[11,4,1,"_CPPv4N4espp3Rgb3RgbERK3Hsv","espp::Rgb::Rgb::hsv"],[11,4,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb::r"],[11,4,1,"_CPPv4N4espp3Rgb3RgbERK3Rgb","espp::Rgb::Rgb::rgb"],[11,1,1,"_CPPv4N4espp3Rgb1bE","espp::Rgb::b"],[11,1,1,"_CPPv4N4espp3Rgb1gE","espp::Rgb::g"],[11,3,1,"_CPPv4NK4espp3Rgb3hsvEv","espp::Rgb::hsv"],[11,3,1,"_CPPv4NK4espp3RgbplERK3Rgb","espp::Rgb::operator+"],[11,4,1,"_CPPv4NK4espp3RgbplERK3Rgb","espp::Rgb::operator+::rhs"],[11,3,1,"_CPPv4N4espp3RgbpLERK3Rgb","espp::Rgb::operator+="],[11,4,1,"_CPPv4N4espp3RgbpLERK3Rgb","espp::Rgb::operator+=::rhs"],[11,1,1,"_CPPv4N4espp3Rgb1rE","espp::Rgb::r"],[60,2,1,"_CPPv4N4espp3RmtE","espp::Rmt"],[60,2,1,"_CPPv4N4espp3Rmt6ConfigE","espp::Rmt::Config"],[60,1,1,"_CPPv4N4espp3Rmt6Config10block_sizeE","espp::Rmt::Config::block_size"],[60,1,1,"_CPPv4N4espp3Rmt6Config9clock_srcE","espp::Rmt::Config::clock_src"],[60,1,1,"_CPPv4N4espp3Rmt6Config11dma_enabledE","espp::Rmt::Config::dma_enabled"],[60,1,1,"_CPPv4N4espp3Rmt6Config8gpio_numE","espp::Rmt::Config::gpio_num"],[60,1,1,"_CPPv4N4espp3Rmt6Config9log_levelE","espp::Rmt::Config::log_level"],[60,1,1,"_CPPv4N4espp3Rmt6Config13resolution_hzE","espp::Rmt::Config::resolution_hz"],[60,1,1,"_CPPv4N4espp3Rmt6Config23transaction_queue_depthE","espp::Rmt::Config::transaction_queue_depth"],[60,3,1,"_CPPv4N4espp3Rmt3RmtERK6Config","espp::Rmt::Rmt"],[60,4,1,"_CPPv4N4espp3Rmt3RmtERK6Config","espp::Rmt::Rmt::config"],[60,3,1,"_CPPv4N4espp3Rmt8transmitEPK7uint8_t6size_t","espp::Rmt::transmit"],[60,4,1,"_CPPv4N4espp3Rmt8transmitEPK7uint8_t6size_t","espp::Rmt::transmit::data"],[60,4,1,"_CPPv4N4espp3Rmt8transmitEPK7uint8_t6size_t","espp::Rmt::transmit::length"],[60,3,1,"_CPPv4N4espp3RmtD0Ev","espp::Rmt::~Rmt"],[60,2,1,"_CPPv4N4espp10RmtEncoderE","espp::RmtEncoder"],[60,2,1,"_CPPv4N4espp10RmtEncoder6ConfigE","espp::RmtEncoder::Config"],[60,1,1,"_CPPv4N4espp10RmtEncoder6Config20bytes_encoder_configE","espp::RmtEncoder::Config::bytes_encoder_config"],[60,1,1,"_CPPv4N4espp10RmtEncoder6Config3delE","espp::RmtEncoder::Config::del"],[60,1,1,"_CPPv4N4espp10RmtEncoder6Config6encodeE","espp::RmtEncoder::Config::encode"],[60,1,1,"_CPPv4N4espp10RmtEncoder6Config5resetE","espp::RmtEncoder::Config::reset"],[60,3,1,"_CPPv4N4espp10RmtEncoder10RmtEncoderERK6Config","espp::RmtEncoder::RmtEncoder"],[60,4,1,"_CPPv4N4espp10RmtEncoder10RmtEncoderERK6Config","espp::RmtEncoder::RmtEncoder::config"],[60,8,1,"_CPPv4N4espp10RmtEncoder9delete_fnE","espp::RmtEncoder::delete_fn"],[60,8,1,"_CPPv4N4espp10RmtEncoder9encode_fnE","espp::RmtEncoder::encode_fn"],[60,3,1,"_CPPv4NK4espp10RmtEncoder6handleEv","espp::RmtEncoder::handle"],[60,8,1,"_CPPv4N4espp10RmtEncoder8reset_fnE","espp::RmtEncoder::reset_fn"],[60,3,1,"_CPPv4N4espp10RmtEncoderD0Ev","espp::RmtEncoder::~RmtEncoder"],[61,2,1,"_CPPv4N4espp10RtcpPacketE","espp::RtcpPacket"],[61,2,1,"_CPPv4N4espp13RtpJpegPacketE","espp::RtpJpegPacket"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::data"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::frag_type"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::frag_type"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::height"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::height"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::offset"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q0"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q1"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::scan_data"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::scan_data"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::type_specific"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::type_specific"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::width"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::width"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket8get_dataEv","espp::RtpJpegPacket::get_data"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket10get_heightEv","espp::RtpJpegPacket::get_height"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket13get_jpeg_dataEv","espp::RtpJpegPacket::get_jpeg_data"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket16get_mjpeg_headerEv","espp::RtpJpegPacket::get_mjpeg_header"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket16get_num_q_tablesEv","espp::RtpJpegPacket::get_num_q_tables"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket10get_offsetEv","espp::RtpJpegPacket::get_offset"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket10get_packetEv","espp::RtpJpegPacket::get_packet"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket11get_payloadEv","espp::RtpJpegPacket::get_payload"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket5get_qEv","espp::RtpJpegPacket::get_q"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket11get_q_tableEi","espp::RtpJpegPacket::get_q_table"],[61,4,1,"_CPPv4NK4espp13RtpJpegPacket11get_q_tableEi","espp::RtpJpegPacket::get_q_table::index"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket14get_rpt_headerEv","espp::RtpJpegPacket::get_rpt_header"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket19get_rtp_header_sizeEv","espp::RtpJpegPacket::get_rtp_header_size"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket17get_type_specificEv","espp::RtpJpegPacket::get_type_specific"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket11get_versionEv","espp::RtpJpegPacket::get_version"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket9get_widthEv","espp::RtpJpegPacket::get_width"],[61,3,1,"_CPPv4NK4espp13RtpJpegPacket12has_q_tablesEv","espp::RtpJpegPacket::has_q_tables"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket9serializeEv","espp::RtpJpegPacket::serialize"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket11set_payloadENSt11string_viewE","espp::RtpJpegPacket::set_payload"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket11set_payloadENSt11string_viewE","espp::RtpJpegPacket::set_payload::payload"],[61,3,1,"_CPPv4N4espp13RtpJpegPacket11set_versionEi","espp::RtpJpegPacket::set_version"],[61,4,1,"_CPPv4N4espp13RtpJpegPacket11set_versionEi","espp::RtpJpegPacket::set_version::version"],[61,2,1,"_CPPv4N4espp9RtpPacketE","espp::RtpPacket"],[61,3,1,"_CPPv4N4espp9RtpPacket9RtpPacketE6size_t","espp::RtpPacket::RtpPacket"],[61,3,1,"_CPPv4N4espp9RtpPacket9RtpPacketENSt11string_viewE","espp::RtpPacket::RtpPacket"],[61,3,1,"_CPPv4N4espp9RtpPacket9RtpPacketEv","espp::RtpPacket::RtpPacket"],[61,4,1,"_CPPv4N4espp9RtpPacket9RtpPacketENSt11string_viewE","espp::RtpPacket::RtpPacket::data"],[61,4,1,"_CPPv4N4espp9RtpPacket9RtpPacketE6size_t","espp::RtpPacket::RtpPacket::payload_size"],[61,3,1,"_CPPv4NK4espp9RtpPacket8get_dataEv","espp::RtpPacket::get_data"],[61,3,1,"_CPPv4N4espp9RtpPacket10get_packetEv","espp::RtpPacket::get_packet"],[61,3,1,"_CPPv4NK4espp9RtpPacket11get_payloadEv","espp::RtpPacket::get_payload"],[61,3,1,"_CPPv4NK4espp9RtpPacket14get_rpt_headerEv","espp::RtpPacket::get_rpt_header"],[61,3,1,"_CPPv4NK4espp9RtpPacket19get_rtp_header_sizeEv","espp::RtpPacket::get_rtp_header_size"],[61,3,1,"_CPPv4NK4espp9RtpPacket11get_versionEv","espp::RtpPacket::get_version"],[61,3,1,"_CPPv4N4espp9RtpPacket9serializeEv","espp::RtpPacket::serialize"],[61,3,1,"_CPPv4N4espp9RtpPacket11set_payloadENSt11string_viewE","espp::RtpPacket::set_payload"],[61,4,1,"_CPPv4N4espp9RtpPacket11set_payloadENSt11string_viewE","espp::RtpPacket::set_payload::payload"],[61,3,1,"_CPPv4N4espp9RtpPacket11set_versionEi","espp::RtpPacket::set_version"],[61,4,1,"_CPPv4N4espp9RtpPacket11set_versionEi","espp::RtpPacket::set_version::version"],[61,2,1,"_CPPv4N4espp10RtspClientE","espp::RtspClient"],[61,2,1,"_CPPv4N4espp10RtspClient6ConfigE","espp::RtspClient::Config"],[61,1,1,"_CPPv4N4espp10RtspClient6Config9log_levelE","espp::RtspClient::Config::log_level"],[61,1,1,"_CPPv4N4espp10RtspClient6Config13on_jpeg_frameE","espp::RtspClient::Config::on_jpeg_frame"],[61,1,1,"_CPPv4N4espp10RtspClient6Config4pathE","espp::RtspClient::Config::path"],[61,1,1,"_CPPv4N4espp10RtspClient6Config9rtsp_portE","espp::RtspClient::Config::rtsp_port"],[61,1,1,"_CPPv4N4espp10RtspClient6Config14server_addressE","espp::RtspClient::Config::server_address"],[61,3,1,"_CPPv4N4espp10RtspClient10RtspClientERK6Config","espp::RtspClient::RtspClient"],[61,4,1,"_CPPv4N4espp10RtspClient10RtspClientERK6Config","espp::RtspClient::RtspClient::config"],[61,3,1,"_CPPv4N4espp10RtspClient7connectERNSt10error_codeE","espp::RtspClient::connect"],[61,4,1,"_CPPv4N4espp10RtspClient7connectERNSt10error_codeE","espp::RtspClient::connect::ec"],[61,3,1,"_CPPv4N4espp10RtspClient8describeERNSt10error_codeE","espp::RtspClient::describe"],[61,4,1,"_CPPv4N4espp10RtspClient8describeERNSt10error_codeE","espp::RtspClient::describe::ec"],[61,3,1,"_CPPv4N4espp10RtspClient10disconnectERNSt10error_codeE","espp::RtspClient::disconnect"],[61,4,1,"_CPPv4N4espp10RtspClient10disconnectERNSt10error_codeE","espp::RtspClient::disconnect::ec"],[61,8,1,"_CPPv4N4espp10RtspClient21jpeg_frame_callback_tE","espp::RtspClient::jpeg_frame_callback_t"],[61,3,1,"_CPPv4N4espp10RtspClient5pauseERNSt10error_codeE","espp::RtspClient::pause"],[61,4,1,"_CPPv4N4espp10RtspClient5pauseERNSt10error_codeE","espp::RtspClient::pause::ec"],[61,3,1,"_CPPv4N4espp10RtspClient4playERNSt10error_codeE","espp::RtspClient::play"],[61,4,1,"_CPPv4N4espp10RtspClient4playERNSt10error_codeE","espp::RtspClient::play::ec"],[61,3,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request"],[61,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::ec"],[61,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::extra_headers"],[61,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::method"],[61,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::path"],[61,3,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup"],[61,3,1,"_CPPv4N4espp10RtspClient5setupERNSt10error_codeE","espp::RtspClient::setup"],[61,4,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup::ec"],[61,4,1,"_CPPv4N4espp10RtspClient5setupERNSt10error_codeE","espp::RtspClient::setup::ec"],[61,4,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup::rtcp_port"],[61,4,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup::rtp_port"],[61,3,1,"_CPPv4N4espp10RtspClient8teardownERNSt10error_codeE","espp::RtspClient::teardown"],[61,4,1,"_CPPv4N4espp10RtspClient8teardownERNSt10error_codeE","espp::RtspClient::teardown::ec"],[61,3,1,"_CPPv4N4espp10RtspClientD0Ev","espp::RtspClient::~RtspClient"],[61,2,1,"_CPPv4N4espp10RtspServerE","espp::RtspServer"],[61,2,1,"_CPPv4N4espp10RtspServer6ConfigE","espp::RtspServer::Config"],[61,1,1,"_CPPv4N4espp10RtspServer6Config9log_levelE","espp::RtspServer::Config::log_level"],[61,1,1,"_CPPv4N4espp10RtspServer6Config13max_data_sizeE","espp::RtspServer::Config::max_data_size"],[61,1,1,"_CPPv4N4espp10RtspServer6Config4pathE","espp::RtspServer::Config::path"],[61,1,1,"_CPPv4N4espp10RtspServer6Config4portE","espp::RtspServer::Config::port"],[61,1,1,"_CPPv4N4espp10RtspServer6Config14server_addressE","espp::RtspServer::Config::server_address"],[61,3,1,"_CPPv4N4espp10RtspServer10RtspServerERK6Config","espp::RtspServer::RtspServer"],[61,4,1,"_CPPv4N4espp10RtspServer10RtspServerERK6Config","espp::RtspServer::RtspServer::config"],[61,3,1,"_CPPv4N4espp10RtspServer10send_frameERK9JpegFrame","espp::RtspServer::send_frame"],[61,4,1,"_CPPv4N4espp10RtspServer10send_frameERK9JpegFrame","espp::RtspServer::send_frame::frame"],[61,3,1,"_CPPv4N4espp10RtspServer21set_session_log_levelEN6Logger9VerbosityE","espp::RtspServer::set_session_log_level"],[61,4,1,"_CPPv4N4espp10RtspServer21set_session_log_levelEN6Logger9VerbosityE","espp::RtspServer::set_session_log_level::log_level"],[61,3,1,"_CPPv4N4espp10RtspServer5startEv","espp::RtspServer::start"],[61,3,1,"_CPPv4N4espp10RtspServer4stopEv","espp::RtspServer::stop"],[61,3,1,"_CPPv4N4espp10RtspServerD0Ev","espp::RtspServer::~RtspServer"],[61,2,1,"_CPPv4N4espp11RtspSessionE","espp::RtspSession"],[61,2,1,"_CPPv4N4espp11RtspSession6ConfigE","espp::RtspSession::Config"],[61,1,1,"_CPPv4N4espp11RtspSession6Config9log_levelE","espp::RtspSession::Config::log_level"],[61,1,1,"_CPPv4N4espp11RtspSession6Config9rtsp_pathE","espp::RtspSession::Config::rtsp_path"],[61,1,1,"_CPPv4N4espp11RtspSession6Config14server_addressE","espp::RtspSession::Config::server_address"],[61,3,1,"_CPPv4N4espp11RtspSession11RtspSessionENSt10unique_ptrI9TcpSocketEERK6Config","espp::RtspSession::RtspSession"],[61,4,1,"_CPPv4N4espp11RtspSession11RtspSessionENSt10unique_ptrI9TcpSocketEERK6Config","espp::RtspSession::RtspSession::config"],[61,4,1,"_CPPv4N4espp11RtspSession11RtspSessionENSt10unique_ptrI9TcpSocketEERK6Config","espp::RtspSession::RtspSession::control_socket"],[61,3,1,"_CPPv4NK4espp11RtspSession14get_session_idEv","espp::RtspSession::get_session_id"],[61,3,1,"_CPPv4NK4espp11RtspSession9is_activeEv","espp::RtspSession::is_active"],[61,3,1,"_CPPv4NK4espp11RtspSession9is_closedEv","espp::RtspSession::is_closed"],[61,3,1,"_CPPv4NK4espp11RtspSession12is_connectedEv","espp::RtspSession::is_connected"],[61,3,1,"_CPPv4N4espp11RtspSession5pauseEv","espp::RtspSession::pause"],[61,3,1,"_CPPv4N4espp11RtspSession4playEv","espp::RtspSession::play"],[61,3,1,"_CPPv4N4espp11RtspSession16send_rtcp_packetERK10RtcpPacket","espp::RtspSession::send_rtcp_packet"],[61,4,1,"_CPPv4N4espp11RtspSession16send_rtcp_packetERK10RtcpPacket","espp::RtspSession::send_rtcp_packet::packet"],[61,3,1,"_CPPv4N4espp11RtspSession15send_rtp_packetERK9RtpPacket","espp::RtspSession::send_rtp_packet"],[61,4,1,"_CPPv4N4espp11RtspSession15send_rtp_packetERK9RtpPacket","espp::RtspSession::send_rtp_packet::packet"],[61,3,1,"_CPPv4N4espp11RtspSession8teardownEv","espp::RtspSession::teardown"],[53,2,1,"_CPPv4N4espp6SocketE","espp::Socket"],[53,2,1,"_CPPv4N4espp6Socket4InfoE","espp::Socket::Info"],[53,1,1,"_CPPv4N4espp6Socket4Info7addressE","espp::Socket::Info::address"],[53,3,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK11sockaddr_in","espp::Socket::Info::from_sockaddr"],[53,3,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK12sockaddr_in6","espp::Socket::Info::from_sockaddr"],[53,3,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK16sockaddr_storage","espp::Socket::Info::from_sockaddr"],[53,4,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK11sockaddr_in","espp::Socket::Info::from_sockaddr::source_address"],[53,4,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK12sockaddr_in6","espp::Socket::Info::from_sockaddr::source_address"],[53,4,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK16sockaddr_storage","espp::Socket::Info::from_sockaddr::source_address"],[53,3,1,"_CPPv4N4espp6Socket4Info9init_ipv4ERKNSt6stringE6size_t","espp::Socket::Info::init_ipv4"],[53,4,1,"_CPPv4N4espp6Socket4Info9init_ipv4ERKNSt6stringE6size_t","espp::Socket::Info::init_ipv4::addr"],[53,4,1,"_CPPv4N4espp6Socket4Info9init_ipv4ERKNSt6stringE6size_t","espp::Socket::Info::init_ipv4::prt"],[53,3,1,"_CPPv4N4espp6Socket4Info8ipv4_ptrEv","espp::Socket::Info::ipv4_ptr"],[53,3,1,"_CPPv4N4espp6Socket4Info8ipv6_ptrEv","espp::Socket::Info::ipv6_ptr"],[53,1,1,"_CPPv4N4espp6Socket4Info4portE","espp::Socket::Info::port"],[53,3,1,"_CPPv4N4espp6Socket4Info6updateEv","espp::Socket::Info::update"],[53,3,1,"_CPPv4N4espp6Socket6SocketE4TypeRKN6Logger6ConfigE","espp::Socket::Socket"],[53,3,1,"_CPPv4N4espp6Socket6SocketEiRKN6Logger6ConfigE","espp::Socket::Socket"],[53,4,1,"_CPPv4N4espp6Socket6SocketE4TypeRKN6Logger6ConfigE","espp::Socket::Socket::logger_config"],[53,4,1,"_CPPv4N4espp6Socket6SocketEiRKN6Logger6ConfigE","espp::Socket::Socket::logger_config"],[53,4,1,"_CPPv4N4espp6Socket6SocketEiRKN6Logger6ConfigE","espp::Socket::Socket::socket_fd"],[53,4,1,"_CPPv4N4espp6Socket6SocketE4TypeRKN6Logger6ConfigE","espp::Socket::Socket::type"],[53,3,1,"_CPPv4N4espp6Socket19add_multicast_groupERKNSt6stringE","espp::Socket::add_multicast_group"],[53,4,1,"_CPPv4N4espp6Socket19add_multicast_groupERKNSt6stringE","espp::Socket::add_multicast_group::multicast_group"],[53,3,1,"_CPPv4N4espp6Socket12enable_reuseEv","espp::Socket::enable_reuse"],[53,3,1,"_CPPv4N4espp6Socket13get_ipv4_infoEv","espp::Socket::get_ipv4_info"],[53,3,1,"_CPPv4N4espp6Socket8is_validEi","espp::Socket::is_valid"],[53,3,1,"_CPPv4NK4espp6Socket8is_validEv","espp::Socket::is_valid"],[53,4,1,"_CPPv4N4espp6Socket8is_validEi","espp::Socket::is_valid::socket_fd"],[53,3,1,"_CPPv4N4espp6Socket14make_multicastE7uint8_t7uint8_t","espp::Socket::make_multicast"],[53,4,1,"_CPPv4N4espp6Socket14make_multicastE7uint8_t7uint8_t","espp::Socket::make_multicast::loopback_enabled"],[53,4,1,"_CPPv4N4espp6Socket14make_multicastE7uint8_t7uint8_t","espp::Socket::make_multicast::time_to_live"],[53,8,1,"_CPPv4N4espp6Socket19receive_callback_fnE","espp::Socket::receive_callback_fn"],[53,8,1,"_CPPv4N4espp6Socket20response_callback_fnE","espp::Socket::response_callback_fn"],[53,3,1,"_CPPv4N4espp6Socket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::Socket::set_receive_timeout"],[53,4,1,"_CPPv4N4espp6Socket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::Socket::set_receive_timeout::timeout"],[53,3,1,"_CPPv4N4espp6SocketD0Ev","espp::Socket::~Socket"],[28,2,1,"_CPPv4I_6size_t0EN4espp9SosFilterE","espp::SosFilter"],[28,5,1,"_CPPv4I_6size_t0EN4espp9SosFilterE","espp::SosFilter::N"],[28,5,1,"_CPPv4I_6size_t0EN4espp9SosFilterE","espp::SosFilter::SectionImpl"],[28,3,1,"_CPPv4N4espp9SosFilter9SosFilterERKNSt5arrayI16TransferFunctionIXL3EEE1NEE","espp::SosFilter::SosFilter"],[28,4,1,"_CPPv4N4espp9SosFilter9SosFilterERKNSt5arrayI16TransferFunctionIXL3EEE1NEE","espp::SosFilter::SosFilter::config"],[28,3,1,"_CPPv4N4espp9SosFilterclEf","espp::SosFilter::operator()"],[28,4,1,"_CPPv4N4espp9SosFilterclEf","espp::SosFilter::operator()::input"],[28,3,1,"_CPPv4N4espp9SosFilter6updateEf","espp::SosFilter::update"],[28,4,1,"_CPPv4N4espp9SosFilter6updateEf","espp::SosFilter::update::input"],[58,2,1,"_CPPv4N4espp6St25dvE","espp::St25dv"],[58,2,1,"_CPPv4N4espp6St25dv6ConfigE","espp::St25dv::Config"],[58,1,1,"_CPPv4N4espp6St25dv6Config9log_levelE","espp::St25dv::Config::log_level"],[58,1,1,"_CPPv4N4espp6St25dv6Config4readE","espp::St25dv::Config::read"],[58,1,1,"_CPPv4N4espp6St25dv6Config5writeE","espp::St25dv::Config::write"],[58,1,1,"_CPPv4N4espp6St25dv12DATA_ADDRESSE","espp::St25dv::DATA_ADDRESS"],[58,2,1,"_CPPv4N4espp6St25dv7EH_CTRLE","espp::St25dv::EH_CTRL"],[58,2,1,"_CPPv4N4espp6St25dv3GPOE","espp::St25dv::GPO"],[58,2,1,"_CPPv4N4espp6St25dv6IT_STSE","espp::St25dv::IT_STS"],[58,2,1,"_CPPv4N4espp6St25dv6IT_STSE","espp::St25dv::IT_STS"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS13FIELD_FALLINGE","espp::St25dv::IT_STS::FIELD_FALLING"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS13FIELD_FALLINGE","espp::St25dv::IT_STS::FIELD_FALLING"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS12FIELD_RISINGE","espp::St25dv::IT_STS::FIELD_RISING"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS12FIELD_RISINGE","espp::St25dv::IT_STS::FIELD_RISING"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS11RF_ACTIVITYE","espp::St25dv::IT_STS::RF_ACTIVITY"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS11RF_ACTIVITYE","espp::St25dv::IT_STS::RF_ACTIVITY"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_GET_MSGE","espp::St25dv::IT_STS::RF_GET_MSG"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_GET_MSGE","espp::St25dv::IT_STS::RF_GET_MSG"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS12RF_INTTERUPTE","espp::St25dv::IT_STS::RF_INTTERUPT"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS12RF_INTTERUPTE","espp::St25dv::IT_STS::RF_INTTERUPT"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_PUT_MSGE","espp::St25dv::IT_STS::RF_PUT_MSG"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_PUT_MSGE","espp::St25dv::IT_STS::RF_PUT_MSG"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS7RF_USERE","espp::St25dv::IT_STS::RF_USER"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS7RF_USERE","espp::St25dv::IT_STS::RF_USER"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS8RF_WRITEE","espp::St25dv::IT_STS::RF_WRITE"],[58,1,1,"_CPPv4N4espp6St25dv6IT_STS8RF_WRITEE","espp::St25dv::IT_STS::RF_WRITE"],[58,2,1,"_CPPv4N4espp6St25dv7MB_CTRLE","espp::St25dv::MB_CTRL"],[58,1,1,"_CPPv4N4espp6St25dv19PhonyNameDueToError6lengthE","espp::St25dv::PhonyNameDueToError::length"],[58,1,1,"_CPPv4N4espp6St25dv19PhonyNameDueToError8length16E","espp::St25dv::PhonyNameDueToError::length16"],[58,1,1,"_CPPv4N4espp6St25dv19PhonyNameDueToError4typeE","espp::St25dv::PhonyNameDueToError::type"],[58,1,1,"_CPPv4N4espp6St25dv12SYST_ADDRESSE","espp::St25dv::SYST_ADDRESS"],[58,3,1,"_CPPv4N4espp6St25dv6St25dvERK6Config","espp::St25dv::St25dv"],[58,4,1,"_CPPv4N4espp6St25dv6St25dvERK6Config","espp::St25dv::St25dv::config"],[58,3,1,"_CPPv4N4espp6St25dv14get_ftm_lengthEv","espp::St25dv::get_ftm_length"],[58,3,1,"_CPPv4N4espp6St25dv20get_interrupt_statusEv","espp::St25dv::get_interrupt_status"],[58,3,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_t","espp::St25dv::read"],[58,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_t","espp::St25dv::read::data"],[58,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_t","espp::St25dv::read::length"],[58,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_t","espp::St25dv::read::offset"],[58,8,1,"_CPPv4N4espp6St25dv7read_fnE","espp::St25dv::read_fn"],[58,3,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_t","espp::St25dv::receive"],[58,4,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_t","espp::St25dv::receive::data"],[58,4,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_t","espp::St25dv::receive::length"],[58,3,1,"_CPPv4N4espp6St25dv10set_recordER4Ndef","espp::St25dv::set_record"],[58,4,1,"_CPPv4N4espp6St25dv10set_recordER4Ndef","espp::St25dv::set_record::record"],[58,3,1,"_CPPv4N4espp6St25dv24start_fast_transfer_modeEv","espp::St25dv::start_fast_transfer_mode"],[58,3,1,"_CPPv4N4espp6St25dv23stop_fast_transfer_modeEv","espp::St25dv::stop_fast_transfer_mode"],[58,3,1,"_CPPv4N4espp6St25dv8transferEP7uint8_t7uint8_t","espp::St25dv::transfer"],[58,4,1,"_CPPv4N4espp6St25dv8transferEP7uint8_t7uint8_t","espp::St25dv::transfer::data"],[58,4,1,"_CPPv4N4espp6St25dv8transferEP7uint8_t7uint8_t","espp::St25dv::transfer::length"],[58,3,1,"_CPPv4N4espp6St25dv5writeENSt11string_viewE","espp::St25dv::write"],[58,4,1,"_CPPv4N4espp6St25dv5writeENSt11string_viewE","espp::St25dv::write::payload"],[58,8,1,"_CPPv4N4espp6St25dv8write_fnE","espp::St25dv::write_fn"],[15,2,1,"_CPPv4N4espp6St7789E","espp::St7789"],[15,3,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear"],[15,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::color"],[15,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::height"],[15,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::width"],[15,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::x"],[15,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::y"],[15,3,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill"],[15,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::area"],[15,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::color_map"],[15,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::drv"],[15,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::flags"],[15,3,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush"],[15,4,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush::area"],[15,4,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush::color_map"],[15,4,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush::drv"],[15,3,1,"_CPPv4N4espp6St778910get_offsetERiRi","espp::St7789::get_offset"],[15,4,1,"_CPPv4N4espp6St778910get_offsetERiRi","espp::St7789::get_offset::x"],[15,4,1,"_CPPv4N4espp6St778910get_offsetERiRi","espp::St7789::get_offset::y"],[15,3,1,"_CPPv4N4espp6St778910initializeERKN15display_drivers6ConfigE","espp::St7789::initialize"],[15,4,1,"_CPPv4N4espp6St778910initializeERKN15display_drivers6ConfigE","espp::St7789::initialize::config"],[15,3,1,"_CPPv4N4espp6St778912send_commandE7uint8_t","espp::St7789::send_command"],[15,4,1,"_CPPv4N4espp6St778912send_commandE7uint8_t","espp::St7789::send_command::command"],[15,3,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data"],[15,4,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data::data"],[15,4,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data::flags"],[15,4,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data::length"],[15,3,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area"],[15,3,1,"_CPPv4N4espp6St778916set_drawing_areaEPK9lv_area_t","espp::St7789::set_drawing_area"],[15,4,1,"_CPPv4N4espp6St778916set_drawing_areaEPK9lv_area_t","espp::St7789::set_drawing_area::area"],[15,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::xe"],[15,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::xs"],[15,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::ye"],[15,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::ys"],[15,3,1,"_CPPv4N4espp6St778910set_offsetEii","espp::St7789::set_offset"],[15,4,1,"_CPPv4N4espp6St778910set_offsetEii","espp::St7789::set_offset::x"],[15,4,1,"_CPPv4N4espp6St778910set_offsetEii","espp::St7789::set_offset::y"],[64,2,1,"_CPPv4N4espp4TaskE","espp::Task"],[64,2,1,"_CPPv4N4espp4Task6ConfigE","espp::Task::Config"],[64,1,1,"_CPPv4N4espp4Task6Config8callbackE","espp::Task::Config::callback"],[64,1,1,"_CPPv4N4espp4Task6Config7core_idE","espp::Task::Config::core_id"],[64,1,1,"_CPPv4N4espp4Task6Config9log_levelE","espp::Task::Config::log_level"],[64,1,1,"_CPPv4N4espp4Task6Config4nameE","espp::Task::Config::name"],[64,1,1,"_CPPv4N4espp4Task6Config8priorityE","espp::Task::Config::priority"],[64,1,1,"_CPPv4N4espp4Task6Config16stack_size_bytesE","espp::Task::Config::stack_size_bytes"],[64,8,1,"_CPPv4N4espp4Task11callback_fnE","espp::Task::callback_fn"],[64,3,1,"_CPPv4N4espp4Task10is_runningEv","espp::Task::is_running"],[64,3,1,"_CPPv4N4espp4Task10is_startedEv","espp::Task::is_started"],[64,3,1,"_CPPv4N4espp4Task11make_uniqueERK6Config","espp::Task::make_unique"],[64,4,1,"_CPPv4N4espp4Task11make_uniqueERK6Config","espp::Task::make_unique::config"],[64,3,1,"_CPPv4N4espp4Task5startEv","espp::Task::start"],[64,3,1,"_CPPv4N4espp4Task4stopEv","espp::Task::stop"],[64,3,1,"_CPPv4N4espp4TaskD0Ev","espp::Task::~Task"],[51,2,1,"_CPPv4N4espp11TaskMonitorE","espp::TaskMonitor"],[51,2,1,"_CPPv4N4espp11TaskMonitor6ConfigE","espp::TaskMonitor::Config"],[51,1,1,"_CPPv4N4espp11TaskMonitor6Config6periodE","espp::TaskMonitor::Config::period"],[51,1,1,"_CPPv4N4espp11TaskMonitor6Config21task_stack_size_bytesE","espp::TaskMonitor::Config::task_stack_size_bytes"],[51,3,1,"_CPPv4N4espp11TaskMonitor15get_latest_infoEv","espp::TaskMonitor::get_latest_info"],[54,2,1,"_CPPv4N4espp9TcpSocketE","espp::TcpSocket"],[54,2,1,"_CPPv4N4espp9TcpSocket6ConfigE","espp::TcpSocket::Config"],[54,1,1,"_CPPv4N4espp9TcpSocket6Config9log_levelE","espp::TcpSocket::Config::log_level"],[54,2,1,"_CPPv4N4espp9TcpSocket13ConnectConfigE","espp::TcpSocket::ConnectConfig"],[54,1,1,"_CPPv4N4espp9TcpSocket13ConnectConfig10ip_addressE","espp::TcpSocket::ConnectConfig::ip_address"],[54,1,1,"_CPPv4N4espp9TcpSocket13ConnectConfig4portE","espp::TcpSocket::ConnectConfig::port"],[54,3,1,"_CPPv4N4espp9TcpSocket9TcpSocketERK6Config","espp::TcpSocket::TcpSocket"],[54,4,1,"_CPPv4N4espp9TcpSocket9TcpSocketERK6Config","espp::TcpSocket::TcpSocket::config"],[54,3,1,"_CPPv4N4espp9TcpSocket6acceptEv","espp::TcpSocket::accept"],[54,3,1,"_CPPv4N4espp9TcpSocket19add_multicast_groupERKNSt6stringE","espp::TcpSocket::add_multicast_group"],[54,4,1,"_CPPv4N4espp9TcpSocket19add_multicast_groupERKNSt6stringE","espp::TcpSocket::add_multicast_group::multicast_group"],[54,3,1,"_CPPv4N4espp9TcpSocket4bindEi","espp::TcpSocket::bind"],[54,4,1,"_CPPv4N4espp9TcpSocket4bindEi","espp::TcpSocket::bind::port"],[54,3,1,"_CPPv4N4espp9TcpSocket5closeEv","espp::TcpSocket::close"],[54,3,1,"_CPPv4N4espp9TcpSocket7connectERK13ConnectConfig","espp::TcpSocket::connect"],[54,4,1,"_CPPv4N4espp9TcpSocket7connectERK13ConnectConfig","espp::TcpSocket::connect::connect_config"],[54,3,1,"_CPPv4N4espp9TcpSocket12enable_reuseEv","espp::TcpSocket::enable_reuse"],[54,3,1,"_CPPv4N4espp9TcpSocket13get_ipv4_infoEv","espp::TcpSocket::get_ipv4_info"],[54,3,1,"_CPPv4NK4espp9TcpSocket15get_remote_infoEv","espp::TcpSocket::get_remote_info"],[54,3,1,"_CPPv4NK4espp9TcpSocket12is_connectedEv","espp::TcpSocket::is_connected"],[54,3,1,"_CPPv4N4espp9TcpSocket8is_validEi","espp::TcpSocket::is_valid"],[54,3,1,"_CPPv4NK4espp9TcpSocket8is_validEv","espp::TcpSocket::is_valid"],[54,4,1,"_CPPv4N4espp9TcpSocket8is_validEi","espp::TcpSocket::is_valid::socket_fd"],[54,3,1,"_CPPv4N4espp9TcpSocket6listenEi","espp::TcpSocket::listen"],[54,4,1,"_CPPv4N4espp9TcpSocket6listenEi","espp::TcpSocket::listen::max_pending_connections"],[54,3,1,"_CPPv4N4espp9TcpSocket14make_multicastE7uint8_t7uint8_t","espp::TcpSocket::make_multicast"],[54,4,1,"_CPPv4N4espp9TcpSocket14make_multicastE7uint8_t7uint8_t","espp::TcpSocket::make_multicast::loopback_enabled"],[54,4,1,"_CPPv4N4espp9TcpSocket14make_multicastE7uint8_t7uint8_t","espp::TcpSocket::make_multicast::time_to_live"],[54,3,1,"_CPPv4N4espp9TcpSocket7receiveEP7uint8_t6size_t","espp::TcpSocket::receive"],[54,3,1,"_CPPv4N4espp9TcpSocket7receiveERNSt6vectorI7uint8_tEE6size_t","espp::TcpSocket::receive"],[54,4,1,"_CPPv4N4espp9TcpSocket7receiveEP7uint8_t6size_t","espp::TcpSocket::receive::data"],[54,4,1,"_CPPv4N4espp9TcpSocket7receiveERNSt6vectorI7uint8_tEE6size_t","espp::TcpSocket::receive::data"],[54,4,1,"_CPPv4N4espp9TcpSocket7receiveEP7uint8_t6size_t","espp::TcpSocket::receive::max_num_bytes"],[54,4,1,"_CPPv4N4espp9TcpSocket7receiveERNSt6vectorI7uint8_tEE6size_t","espp::TcpSocket::receive::max_num_bytes"],[54,8,1,"_CPPv4N4espp9TcpSocket19receive_callback_fnE","espp::TcpSocket::receive_callback_fn"],[54,3,1,"_CPPv4N4espp9TcpSocket6reinitEv","espp::TcpSocket::reinit"],[54,8,1,"_CPPv4N4espp9TcpSocket20response_callback_fnE","espp::TcpSocket::response_callback_fn"],[54,3,1,"_CPPv4N4espp9TcpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::TcpSocket::set_receive_timeout"],[54,4,1,"_CPPv4N4espp9TcpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::TcpSocket::set_receive_timeout::timeout"],[54,3,1,"_CPPv4N4espp9TcpSocket8transmitENSt11string_viewERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit"],[54,3,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorI7uint8_tEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit"],[54,3,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorIcEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit"],[54,4,1,"_CPPv4N4espp9TcpSocket8transmitENSt11string_viewERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::data"],[54,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorI7uint8_tEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::data"],[54,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorIcEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::data"],[54,4,1,"_CPPv4N4espp9TcpSocket8transmitENSt11string_viewERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::transmit_config"],[54,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorI7uint8_tEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::transmit_config"],[54,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorIcEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::transmit_config"],[54,3,1,"_CPPv4N4espp9TcpSocketD0Ev","espp::TcpSocket::~TcpSocket"],[65,2,1,"_CPPv4N4espp10ThermistorE","espp::Thermistor"],[65,2,1,"_CPPv4N4espp10Thermistor6ConfigE","espp::Thermistor::Config"],[65,1,1,"_CPPv4N4espp10Thermistor6Config4betaE","espp::Thermistor::Config::beta"],[65,1,1,"_CPPv4N4espp10Thermistor6Config14divider_configE","espp::Thermistor::Config::divider_config"],[65,1,1,"_CPPv4N4espp10Thermistor6Config21fixed_resistance_ohmsE","espp::Thermistor::Config::fixed_resistance_ohms"],[65,1,1,"_CPPv4N4espp10Thermistor6Config9log_levelE","espp::Thermistor::Config::log_level"],[65,1,1,"_CPPv4N4espp10Thermistor6Config23nominal_resistance_ohmsE","espp::Thermistor::Config::nominal_resistance_ohms"],[65,1,1,"_CPPv4N4espp10Thermistor6Config7read_mvE","espp::Thermistor::Config::read_mv"],[65,1,1,"_CPPv4N4espp10Thermistor6Config9supply_mvE","espp::Thermistor::Config::supply_mv"],[65,6,1,"_CPPv4N4espp10Thermistor21ResistorDividerConfigE","espp::Thermistor::ResistorDividerConfig"],[65,7,1,"_CPPv4N4espp10Thermistor21ResistorDividerConfig5LOWERE","espp::Thermistor::ResistorDividerConfig::LOWER"],[65,7,1,"_CPPv4N4espp10Thermistor21ResistorDividerConfig5UPPERE","espp::Thermistor::ResistorDividerConfig::UPPER"],[65,3,1,"_CPPv4N4espp10Thermistor10ThermistorERK6Config","espp::Thermistor::Thermistor"],[65,4,1,"_CPPv4N4espp10Thermistor10ThermistorERK6Config","espp::Thermistor::Thermistor::config"],[65,3,1,"_CPPv4N4espp10Thermistor11get_celsiusEv","espp::Thermistor::get_celsius"],[65,3,1,"_CPPv4N4espp10Thermistor14get_fahrenheitEv","espp::Thermistor::get_fahrenheit"],[65,3,1,"_CPPv4N4espp10Thermistor10get_kelvinEv","espp::Thermistor::get_kelvin"],[65,3,1,"_CPPv4N4espp10Thermistor14get_resistanceEv","espp::Thermistor::get_resistance"],[65,8,1,"_CPPv4N4espp10Thermistor10read_mv_fnE","espp::Thermistor::read_mv_fn"],[37,2,1,"_CPPv4N4espp13TouchpadInputE","espp::TouchpadInput"],[37,2,1,"_CPPv4N4espp13TouchpadInput6ConfigE","espp::TouchpadInput::Config"],[37,1,1,"_CPPv4N4espp13TouchpadInput6Config8invert_xE","espp::TouchpadInput::Config::invert_x"],[37,1,1,"_CPPv4N4espp13TouchpadInput6Config8invert_yE","espp::TouchpadInput::Config::invert_y"],[37,1,1,"_CPPv4N4espp13TouchpadInput6Config9log_levelE","espp::TouchpadInput::Config::log_level"],[37,1,1,"_CPPv4N4espp13TouchpadInput6Config7swap_xyE","espp::TouchpadInput::Config::swap_xy"],[37,1,1,"_CPPv4N4espp13TouchpadInput6Config13touchpad_readE","espp::TouchpadInput::Config::touchpad_read"],[37,3,1,"_CPPv4N4espp13TouchpadInput13TouchpadInputERK6Config","espp::TouchpadInput::TouchpadInput"],[37,4,1,"_CPPv4N4espp13TouchpadInput13TouchpadInputERK6Config","espp::TouchpadInput::TouchpadInput::config"],[37,8,1,"_CPPv4N4espp13TouchpadInput16touchpad_read_fnE","espp::TouchpadInput::touchpad_read_fn"],[37,3,1,"_CPPv4N4espp13TouchpadInputD0Ev","espp::TouchpadInput::~TouchpadInput"],[55,2,1,"_CPPv4N4espp9UdpSocketE","espp::UdpSocket"],[55,2,1,"_CPPv4N4espp9UdpSocket6ConfigE","espp::UdpSocket::Config"],[55,1,1,"_CPPv4N4espp9UdpSocket6Config9log_levelE","espp::UdpSocket::Config::log_level"],[55,2,1,"_CPPv4N4espp9UdpSocket13ReceiveConfigE","espp::UdpSocket::ReceiveConfig"],[55,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig11buffer_sizeE","espp::UdpSocket::ReceiveConfig::buffer_size"],[55,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig21is_multicast_endpointE","espp::UdpSocket::ReceiveConfig::is_multicast_endpoint"],[55,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig15multicast_groupE","espp::UdpSocket::ReceiveConfig::multicast_group"],[55,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig19on_receive_callbackE","espp::UdpSocket::ReceiveConfig::on_receive_callback"],[55,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig4portE","espp::UdpSocket::ReceiveConfig::port"],[55,2,1,"_CPPv4N4espp9UdpSocket10SendConfigE","espp::UdpSocket::SendConfig"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig10ip_addressE","espp::UdpSocket::SendConfig::ip_address"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig21is_multicast_endpointE","espp::UdpSocket::SendConfig::is_multicast_endpoint"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig20on_response_callbackE","espp::UdpSocket::SendConfig::on_response_callback"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig4portE","espp::UdpSocket::SendConfig::port"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig13response_sizeE","espp::UdpSocket::SendConfig::response_size"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig16response_timeoutE","espp::UdpSocket::SendConfig::response_timeout"],[55,1,1,"_CPPv4N4espp9UdpSocket10SendConfig17wait_for_responseE","espp::UdpSocket::SendConfig::wait_for_response"],[55,3,1,"_CPPv4N4espp9UdpSocket9UdpSocketERK6Config","espp::UdpSocket::UdpSocket"],[55,4,1,"_CPPv4N4espp9UdpSocket9UdpSocketERK6Config","espp::UdpSocket::UdpSocket::config"],[55,3,1,"_CPPv4N4espp9UdpSocket19add_multicast_groupERKNSt6stringE","espp::UdpSocket::add_multicast_group"],[55,4,1,"_CPPv4N4espp9UdpSocket19add_multicast_groupERKNSt6stringE","espp::UdpSocket::add_multicast_group::multicast_group"],[55,3,1,"_CPPv4N4espp9UdpSocket12enable_reuseEv","espp::UdpSocket::enable_reuse"],[55,3,1,"_CPPv4N4espp9UdpSocket13get_ipv4_infoEv","espp::UdpSocket::get_ipv4_info"],[55,3,1,"_CPPv4N4espp9UdpSocket8is_validEi","espp::UdpSocket::is_valid"],[55,3,1,"_CPPv4NK4espp9UdpSocket8is_validEv","espp::UdpSocket::is_valid"],[55,4,1,"_CPPv4N4espp9UdpSocket8is_validEi","espp::UdpSocket::is_valid::socket_fd"],[55,3,1,"_CPPv4N4espp9UdpSocket14make_multicastE7uint8_t7uint8_t","espp::UdpSocket::make_multicast"],[55,4,1,"_CPPv4N4espp9UdpSocket14make_multicastE7uint8_t7uint8_t","espp::UdpSocket::make_multicast::loopback_enabled"],[55,4,1,"_CPPv4N4espp9UdpSocket14make_multicastE7uint8_t7uint8_t","espp::UdpSocket::make_multicast::time_to_live"],[55,3,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive"],[55,4,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive::data"],[55,4,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive::max_num_bytes"],[55,4,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive::remote_info"],[55,8,1,"_CPPv4N4espp9UdpSocket19receive_callback_fnE","espp::UdpSocket::receive_callback_fn"],[55,8,1,"_CPPv4N4espp9UdpSocket20response_callback_fnE","espp::UdpSocket::response_callback_fn"],[55,3,1,"_CPPv4N4espp9UdpSocket4sendENSt11string_viewERK10SendConfig","espp::UdpSocket::send"],[55,3,1,"_CPPv4N4espp9UdpSocket4sendERKNSt6vectorI7uint8_tEERK10SendConfig","espp::UdpSocket::send"],[55,4,1,"_CPPv4N4espp9UdpSocket4sendENSt11string_viewERK10SendConfig","espp::UdpSocket::send::data"],[55,4,1,"_CPPv4N4espp9UdpSocket4sendERKNSt6vectorI7uint8_tEERK10SendConfig","espp::UdpSocket::send::data"],[55,4,1,"_CPPv4N4espp9UdpSocket4sendENSt11string_viewERK10SendConfig","espp::UdpSocket::send::send_config"],[55,4,1,"_CPPv4N4espp9UdpSocket4sendERKNSt6vectorI7uint8_tEERK10SendConfig","espp::UdpSocket::send::send_config"],[55,3,1,"_CPPv4N4espp9UdpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::UdpSocket::set_receive_timeout"],[55,4,1,"_CPPv4N4espp9UdpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::UdpSocket::set_receive_timeout::timeout"],[55,3,1,"_CPPv4N4espp9UdpSocket15start_receivingERN4Task6ConfigERK13ReceiveConfig","espp::UdpSocket::start_receiving"],[55,4,1,"_CPPv4N4espp9UdpSocket15start_receivingERN4Task6ConfigERK13ReceiveConfig","espp::UdpSocket::start_receiving::receive_config"],[55,4,1,"_CPPv4N4espp9UdpSocket15start_receivingERN4Task6ConfigERK13ReceiveConfig","espp::UdpSocket::start_receiving::task_config"],[55,3,1,"_CPPv4N4espp9UdpSocketD0Ev","espp::UdpSocket::~UdpSocket"],[50,2,1,"_CPPv4I0EN4espp8Vector2dE","espp::Vector2d"],[50,5,1,"_CPPv4I0EN4espp8Vector2dE","espp::Vector2d::T"],[50,3,1,"_CPPv4N4espp8Vector2d8Vector2dE1T1T","espp::Vector2d::Vector2d"],[50,3,1,"_CPPv4N4espp8Vector2d8Vector2dERK8Vector2d","espp::Vector2d::Vector2d"],[50,4,1,"_CPPv4N4espp8Vector2d8Vector2dERK8Vector2d","espp::Vector2d::Vector2d::other"],[50,4,1,"_CPPv4N4espp8Vector2d8Vector2dE1T1T","espp::Vector2d::Vector2d::x"],[50,4,1,"_CPPv4N4espp8Vector2d8Vector2dE1T1T","espp::Vector2d::Vector2d::y"],[50,3,1,"_CPPv4NK4espp8Vector2d3dotERK8Vector2d","espp::Vector2d::dot"],[50,4,1,"_CPPv4NK4espp8Vector2d3dotERK8Vector2d","espp::Vector2d::dot::other"],[50,3,1,"_CPPv4NK4espp8Vector2d9magnitudeEv","espp::Vector2d::magnitude"],[50,3,1,"_CPPv4NK4espp8Vector2d17magnitude_squaredEv","espp::Vector2d::magnitude_squared"],[50,3,1,"_CPPv4NK4espp8Vector2d10normalizedEv","espp::Vector2d::normalized"],[50,3,1,"_CPPv4NK4espp8Vector2dmlERK1T","espp::Vector2d::operator*"],[50,4,1,"_CPPv4NK4espp8Vector2dmlERK1T","espp::Vector2d::operator*::v"],[50,3,1,"_CPPv4N4espp8Vector2dmLERK1T","espp::Vector2d::operator*="],[50,4,1,"_CPPv4N4espp8Vector2dmLERK1T","espp::Vector2d::operator*=::v"],[50,3,1,"_CPPv4NK4espp8Vector2dplERK8Vector2d","espp::Vector2d::operator+"],[50,4,1,"_CPPv4NK4espp8Vector2dplERK8Vector2d","espp::Vector2d::operator+::rhs"],[50,3,1,"_CPPv4N4espp8Vector2dpLERK8Vector2d","espp::Vector2d::operator+="],[50,4,1,"_CPPv4N4espp8Vector2dpLERK8Vector2d","espp::Vector2d::operator+=::rhs"],[50,3,1,"_CPPv4NK4espp8Vector2dmiERK8Vector2d","espp::Vector2d::operator-"],[50,3,1,"_CPPv4NK4espp8Vector2dmiEv","espp::Vector2d::operator-"],[50,4,1,"_CPPv4NK4espp8Vector2dmiERK8Vector2d","espp::Vector2d::operator-::rhs"],[50,3,1,"_CPPv4N4espp8Vector2dmIERK8Vector2d","espp::Vector2d::operator-="],[50,4,1,"_CPPv4N4espp8Vector2dmIERK8Vector2d","espp::Vector2d::operator-=::rhs"],[50,3,1,"_CPPv4NK4espp8Vector2ddvERK1T","espp::Vector2d::operator/"],[50,3,1,"_CPPv4NK4espp8Vector2ddvERK8Vector2d","espp::Vector2d::operator/"],[50,4,1,"_CPPv4NK4espp8Vector2ddvERK1T","espp::Vector2d::operator/::v"],[50,4,1,"_CPPv4NK4espp8Vector2ddvERK8Vector2d","espp::Vector2d::operator/::v"],[50,3,1,"_CPPv4N4espp8Vector2ddVERK1T","espp::Vector2d::operator/="],[50,3,1,"_CPPv4N4espp8Vector2ddVERK8Vector2d","espp::Vector2d::operator/="],[50,4,1,"_CPPv4N4espp8Vector2ddVERK1T","espp::Vector2d::operator/=::v"],[50,4,1,"_CPPv4N4espp8Vector2ddVERK8Vector2d","espp::Vector2d::operator/=::v"],[50,3,1,"_CPPv4N4espp8Vector2daSERK8Vector2d","espp::Vector2d::operator="],[50,4,1,"_CPPv4N4espp8Vector2daSERK8Vector2d","espp::Vector2d::operator=::other"],[50,3,1,"_CPPv4N4espp8Vector2dixEi","espp::Vector2d::operator[]"],[50,4,1,"_CPPv4N4espp8Vector2dixEi","espp::Vector2d::operator[]::index"],[50,3,1,"_CPPv4I0_PNSt9enable_ifINSt17is_floating_pointI1UE5valueEE4typeEENK4espp8Vector2d7rotatedE8Vector2d1T","espp::Vector2d::rotated"],[50,5,1,"_CPPv4I0_PNSt9enable_ifINSt17is_floating_pointI1UE5valueEE4typeEENK4espp8Vector2d7rotatedE8Vector2d1T","espp::Vector2d::rotated::U"],[50,4,1,"_CPPv4I0_PNSt9enable_ifINSt17is_floating_pointI1UE5valueEE4typeEENK4espp8Vector2d7rotatedE8Vector2d1T","espp::Vector2d::rotated::radians"],[50,3,1,"_CPPv4N4espp8Vector2d1xE1T","espp::Vector2d::x"],[50,3,1,"_CPPv4NK4espp8Vector2d1xEv","espp::Vector2d::x"],[50,4,1,"_CPPv4N4espp8Vector2d1xE1T","espp::Vector2d::x::v"],[50,3,1,"_CPPv4N4espp8Vector2d1yE1T","espp::Vector2d::y"],[50,3,1,"_CPPv4NK4espp8Vector2d1yEv","espp::Vector2d::y"],[50,4,1,"_CPPv4N4espp8Vector2d1yE1T","espp::Vector2d::y::v"],[67,2,1,"_CPPv4N4espp6WifiApE","espp::WifiAp"],[67,2,1,"_CPPv4N4espp6WifiAp6ConfigE","espp::WifiAp::Config"],[67,1,1,"_CPPv4N4espp6WifiAp6Config7channelE","espp::WifiAp::Config::channel"],[67,1,1,"_CPPv4N4espp6WifiAp6Config9log_levelE","espp::WifiAp::Config::log_level"],[67,1,1,"_CPPv4N4espp6WifiAp6Config22max_number_of_stationsE","espp::WifiAp::Config::max_number_of_stations"],[67,1,1,"_CPPv4N4espp6WifiAp6Config8passwordE","espp::WifiAp::Config::password"],[67,1,1,"_CPPv4N4espp6WifiAp6Config4ssidE","espp::WifiAp::Config::ssid"],[67,3,1,"_CPPv4N4espp6WifiAp6WifiApERK6Config","espp::WifiAp::WifiAp"],[67,4,1,"_CPPv4N4espp6WifiAp6WifiApERK6Config","espp::WifiAp::WifiAp::config"],[68,2,1,"_CPPv4N4espp7WifiStaE","espp::WifiSta"],[68,2,1,"_CPPv4N4espp7WifiSta6ConfigE","espp::WifiSta::Config"],[68,1,1,"_CPPv4N4espp7WifiSta6Config6ap_macE","espp::WifiSta::Config::ap_mac"],[68,1,1,"_CPPv4N4espp7WifiSta6Config7channelE","espp::WifiSta::Config::channel"],[68,1,1,"_CPPv4N4espp7WifiSta6Config9log_levelE","espp::WifiSta::Config::log_level"],[68,1,1,"_CPPv4N4espp7WifiSta6Config19num_connect_retriesE","espp::WifiSta::Config::num_connect_retries"],[68,1,1,"_CPPv4N4espp7WifiSta6Config12on_connectedE","espp::WifiSta::Config::on_connected"],[68,1,1,"_CPPv4N4espp7WifiSta6Config15on_disconnectedE","espp::WifiSta::Config::on_disconnected"],[68,1,1,"_CPPv4N4espp7WifiSta6Config9on_got_ipE","espp::WifiSta::Config::on_got_ip"],[68,1,1,"_CPPv4N4espp7WifiSta6Config8passwordE","espp::WifiSta::Config::password"],[68,1,1,"_CPPv4N4espp7WifiSta6Config10set_ap_macE","espp::WifiSta::Config::set_ap_mac"],[68,1,1,"_CPPv4N4espp7WifiSta6Config4ssidE","espp::WifiSta::Config::ssid"],[68,3,1,"_CPPv4N4espp7WifiSta7WifiStaERK6Config","espp::WifiSta::WifiSta"],[68,4,1,"_CPPv4N4espp7WifiSta7WifiStaERK6Config","espp::WifiSta::WifiSta::config"],[68,8,1,"_CPPv4N4espp7WifiSta16connect_callbackE","espp::WifiSta::connect_callback"],[68,8,1,"_CPPv4N4espp7WifiSta19disconnect_callbackE","espp::WifiSta::disconnect_callback"],[68,8,1,"_CPPv4N4espp7WifiSta11ip_callbackE","espp::WifiSta::ip_callback"],[68,3,1,"_CPPv4N4espp7WifiSta12is_connectedEv","espp::WifiSta::is_connected"],[68,3,1,"_CPPv4N4espp7WifiStaD0Ev","espp::WifiSta::~WifiSta"],[13,2,1,"_CPPv4N4espp21__csv_documentation__E","espp::__csv_documentation__"],[62,2,1,"_CPPv4N4espp31__serialization_documentation__E","espp::__serialization_documentation__"],[63,2,1,"_CPPv4N4espp31__state_machine_documentation__E","espp::__state_machine_documentation__"],[63,2,1,"_CPPv4N4espp13state_machine16DeepHistoryStateE","espp::state_machine::DeepHistoryState"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState5entryEv","espp::state_machine::DeepHistoryState::entry"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState4exitEv","espp::state_machine::DeepHistoryState::exit"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState12exitChildrenEv","espp::state_machine::DeepHistoryState::exitChildren"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14getActiveChildEv","espp::state_machine::DeepHistoryState::getActiveChild"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState13getActiveLeafEv","espp::state_machine::DeepHistoryState::getActiveLeaf"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState10getInitialEv","espp::state_machine::DeepHistoryState::getInitial"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14getParentStateEv","espp::state_machine::DeepHistoryState::getParentState"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState11handleEventEP9EventBase","espp::state_machine::DeepHistoryState::handleEvent"],[63,4,1,"_CPPv4N4espp13state_machine16DeepHistoryState11handleEventEP9EventBase","espp::state_machine::DeepHistoryState::handleEvent::event"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState10initializeEv","espp::state_machine::DeepHistoryState::initialize"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState10makeActiveEv","espp::state_machine::DeepHistoryState::makeActive"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setActiveChildEP9StateBase","espp::state_machine::DeepHistoryState::setActiveChild"],[63,4,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setActiveChildEP9StateBase","espp::state_machine::DeepHistoryState::setActiveChild::childState"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setDeepHistoryEv","espp::state_machine::DeepHistoryState::setDeepHistory"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setParentStateEP9StateBase","espp::state_machine::DeepHistoryState::setParentState"],[63,4,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setParentStateEP9StateBase","espp::state_machine::DeepHistoryState::setParentState::parent"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState17setShallowHistoryEv","espp::state_machine::DeepHistoryState::setShallowHistory"],[63,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState4tickEv","espp::state_machine::DeepHistoryState::tick"],[63,2,1,"_CPPv4N4espp13state_machine9EventBaseE","espp::state_machine::EventBase"],[63,2,1,"_CPPv4N4espp13state_machine19ShallowHistoryStateE","espp::state_machine::ShallowHistoryState"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState5entryEv","espp::state_machine::ShallowHistoryState::entry"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState4exitEv","espp::state_machine::ShallowHistoryState::exit"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState12exitChildrenEv","espp::state_machine::ShallowHistoryState::exitChildren"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14getActiveChildEv","espp::state_machine::ShallowHistoryState::getActiveChild"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState13getActiveLeafEv","espp::state_machine::ShallowHistoryState::getActiveLeaf"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState10getInitialEv","espp::state_machine::ShallowHistoryState::getInitial"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14getParentStateEv","espp::state_machine::ShallowHistoryState::getParentState"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState11handleEventEP9EventBase","espp::state_machine::ShallowHistoryState::handleEvent"],[63,4,1,"_CPPv4N4espp13state_machine19ShallowHistoryState11handleEventEP9EventBase","espp::state_machine::ShallowHistoryState::handleEvent::event"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState10initializeEv","espp::state_machine::ShallowHistoryState::initialize"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState10makeActiveEv","espp::state_machine::ShallowHistoryState::makeActive"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setActiveChildEP9StateBase","espp::state_machine::ShallowHistoryState::setActiveChild"],[63,4,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setActiveChildEP9StateBase","espp::state_machine::ShallowHistoryState::setActiveChild::childState"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setDeepHistoryEv","espp::state_machine::ShallowHistoryState::setDeepHistory"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setParentStateEP9StateBase","espp::state_machine::ShallowHistoryState::setParentState"],[63,4,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setParentStateEP9StateBase","espp::state_machine::ShallowHistoryState::setParentState::parent"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState17setShallowHistoryEv","espp::state_machine::ShallowHistoryState::setShallowHistory"],[63,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState4tickEv","espp::state_machine::ShallowHistoryState::tick"],[63,2,1,"_CPPv4N4espp13state_machine9StateBaseE","espp::state_machine::StateBase"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase5entryEv","espp::state_machine::StateBase::entry"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase4exitEv","espp::state_machine::StateBase::exit"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase12exitChildrenEv","espp::state_machine::StateBase::exitChildren"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase14getActiveChildEv","espp::state_machine::StateBase::getActiveChild"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase13getActiveLeafEv","espp::state_machine::StateBase::getActiveLeaf"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase10getInitialEv","espp::state_machine::StateBase::getInitial"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase14getParentStateEv","espp::state_machine::StateBase::getParentState"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase11handleEventEP9EventBase","espp::state_machine::StateBase::handleEvent"],[63,4,1,"_CPPv4N4espp13state_machine9StateBase11handleEventEP9EventBase","espp::state_machine::StateBase::handleEvent::event"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase10initializeEv","espp::state_machine::StateBase::initialize"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase10makeActiveEv","espp::state_machine::StateBase::makeActive"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase14setActiveChildEP9StateBase","espp::state_machine::StateBase::setActiveChild"],[63,4,1,"_CPPv4N4espp13state_machine9StateBase14setActiveChildEP9StateBase","espp::state_machine::StateBase::setActiveChild::childState"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase14setDeepHistoryEv","espp::state_machine::StateBase::setDeepHistory"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase14setParentStateEP9StateBase","espp::state_machine::StateBase::setParentState"],[63,4,1,"_CPPv4N4espp13state_machine9StateBase14setParentStateEP9StateBase","espp::state_machine::StateBase::setParentState::parent"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase17setShallowHistoryEv","espp::state_machine::StateBase::setShallowHistory"],[63,3,1,"_CPPv4N4espp13state_machine9StateBase4tickEv","espp::state_machine::StateBase::tick"]]},objnames:{"0":["c","macro","C macro"],"1":["cpp","member","C++ member"],"2":["cpp","class","C++ class"],"3":["cpp","function","C++ function"],"4":["cpp","functionParam","C++ function parameter"],"5":["cpp","templateParam","C++ template parameter"],"6":["cpp","enum","C++ enum"],"7":["cpp","enumerator","C++ enumerator"],"8":["cpp","type","C++ type"]},objtypes:{"0":"c:macro","1":"cpp:member","2":"cpp:class","3":"cpp:function","4":"cpp:functionParam","5":"cpp:templateParam","6":"cpp:enum","7":"cpp:enumerator","8":"cpp:type"},terms:{"0":[1,2,6,7,9,10,11,12,13,14,15,17,18,21,22,23,24,25,27,32,33,38,40,41,42,43,44,45,47,49,50,51,53,54,55,57,58,59,60,61,64,65,68],"00":18,"000":65,"000f":7,"00b":57,"01":[14,32],"010f":7,"01f":[18,21],"02":6,"024v":1,"02x":58,"03":[44,51],"04":32,"048v":1,"04x":2,"05f":43,"067488":65,"06f":64,"0755":23,"096v":1,"0b00000001":58,"0b00000010":58,"0b00000011":38,"0b00000100":58,"0b00001000":58,"0b0000110":21,"0b00010000":58,"0b00100000":58,"0b00111111":38,"0b0100000":40,"0b01000000":58,"0b0110110":18,"0b10000000":58,"0b11":38,"0b11111":43,"0f":[6,7,12,18,21,22,32,41,42,43,44,45,47,51,59,60],"0s":42,"0x00":[38,40,58],"0x0000":15,"0x000000":58,"0x060504030201":58,"0x10":2,"0x48":1,"0x58":38,"0xa6":58,"0xae":58,"0xff":[2,43,58],"0xffffffffffff":57,"1":[1,2,3,6,7,10,11,12,13,14,15,17,18,21,22,23,24,25,33,38,40,41,42,44,45,47,49,53,54,55,57,58,59,61,62,64,65,67],"10":[2,7,10,14,17,42,44,51,62,64,65],"100":[15,22,40,41,42,59,65],"1000":[3,7,15,17,42,59,61,65],"10000":65,"1000000":60,"10000000":60,"100m":[15,42,51,59,64,68],"1024":[1,2,3,7,9,12,18,21,33,38,40,43,51,54,55,58,60,64,65],"10k":65,"10m":[2,42,54,64,65],"10mhz":60,"12":2,"123":33,"127":[54,55,57],"128":[1,2,54,55,57,61],"12800":15,"128x":2,"13":[38,67],"135":15,"14":38,"144v":1,"14763":65,"15":[2,38,62,65],"1500":61,"152":65,"16":[1,2,15,38,57,58],"1600":1,"16384":[15,18,21],"1678892742599":33,"16kb":58,"16x":2,"1700":[12,41],"18":60,"192":57,"1b":57,"1f":[17,22,41,42,59],"1s":[9,32,33,43,44,51,54,55,59,61,63,64],"2":[1,2,3,7,9,12,13,14,18,21,22,23,24,25,27,38,41,42,44,47,50,51,54,55,57,58,59,60,61],"20":[3,7,15,23,65],"200":[32,61],"200m":[1,58,64],"20143":18,"2046":57,"20df":18,"20m":12,"21":[7,12],"224":[53,54,55],"23017":40,"239":[53,54,55],"23s17":40,"240":15,"2400":1,"2435":61,"2494":65,"24b":58,"25":[22,38,65],"250":1,"250m":17,"255":[11,38,43,53,54,55,57,58,60],"256":[3,57,60,61],"256v":1,"25c":65,"264":61,"265":61,"2657":65,"273":65,"298":65,"2f":[12,22,65],"2pi":[18,21],"2x":2,"3":[1,2,6,7,12,13,14,28,32,38,40,42,54,55,57,60,62,65],"30":65,"300f":7,"300m":44,"31":[12,43,65],"32":[1,2,12,57],"320":[7,15],"32x":2,"33":12,"3300":[1,41,65],"3380":65,"34":[2,7],"3422":65,"3435":65,"3453":65,"3484":60,"3484_datasheet":60,"35981":65,"36":[7,12],"360":[11,18,21,43,60],"36005":18,"37":12,"37ma":38,"38":12,"39":12,"3914752":7,"3940":65,"3950":65,"3986":57,"3f":[1,2,9,17,18,21,33,38,40,44,59,65],"3s":3,"4":[1,2,7,9,12,13,18,21,33,43,45,54,55,57,58,60,64,67],"40":[15,65],"4096":17,"42":[12,62],"43173a3eb323":18,"475":1,"48":[22,57],"4886":38,"48b":58,"490":1,"4b":57,"4kb":58,"4x":2,"5":[1,2,3,7,12,13,18,21,22,25,27,32,33,38,40,43,47,51,54,55,57,58,60,62,65],"50":[15,38,42,58,60,65],"5000":[42,54,55,61],"5001":61,"500m":[3,5,12,22,41,44,51,64],"50c":65,"50m":[18,21,38,40,43,60],"50u":60,"512v":1,"53":15,"53229":65,"5f":[18,21,42,43,47,55,60],"5m":59,"5s":22,"6":[1,2,6,11,12,13,33,54,55,57,60,68],"60":[15,18,21],"61067330":23,"61622309":58,"64":[1,2,60],"649ee61c":18,"64kb":58,"64x":2,"7":[2,7,40,57,62,65],"720":[18,21],"72593":33,"75":[38,65],"8":[1,2,11,14,33,38,40,51,57,58],"80":65,"80552":65,"8192":17,"85":65,"8502":65,"8554":61,"860":1,"8f9a":18,"8x":2,"9":[17,38,60],"920":1,"93hart_equ":65,"9692":10,"9781449324094":57,"9907":65,"9e10":18,"9th":2,"\u03ba":65,"\u03c9":65,"abstract":[35,52,53,64],"boolean":23,"break":63,"byte":[1,2,3,14,15,18,21,23,33,38,40,43,51,53,54,55,57,58,60,61],"case":[18,21,55,60],"char":[23,54,61,64],"class":26,"const":[1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,21,22,23,24,25,27,28,30,32,33,37,38,40,41,42,43,44,45,47,49,50,53,54,55,57,58,59,60,61,64,65,67,68],"default":[1,2,10,12,14,15,32,33,38,40,43,45,47,49,50,51,60,61,62,67,68],"do":[2,5,9,12,13,22,33,51,61,62,63,64],"enum":[1,2,9,12,14,33,38,40,41,43,44,57,65],"final":[12,18,21,38,40,51,57,58,61,63],"float":[1,2,3,5,6,7,9,11,12,14,17,18,21,22,24,25,27,28,32,33,38,40,41,42,43,44,45,46,47,50,51,53,54,55,58,59,60,63,64,65],"function":[1,2,3,5,6,7,9,10,11,12,14,15,17,18,21,22,23,24,25,26,27,28,32,33,34,35,37,38,40,41,42,43,44,45,46,47,49,50,51,52,53,54,55,57,58,59,60,61,63,64,65,67,68],"goto":60,"int":[1,2,5,6,9,10,12,15,17,18,21,22,23,30,38,42,43,50,51,53,54,55,57,58,59,60,61,62,63,64,65],"long":61,"new":[5,6,7,9,10,15,22,24,25,27,28,30,38,41,42,43,44,47,49,50,57,58,59,61,63,64],"public":[1,2,3,5,6,7,9,10,11,12,14,15,17,18,21,22,23,24,25,27,28,30,32,33,37,38,40,41,42,43,44,45,47,49,50,51,53,54,55,57,58,59,60,61,63,64,65,67,68],"return":[1,2,3,5,6,7,9,10,11,12,14,15,17,18,21,22,23,24,25,27,28,30,32,33,38,40,41,42,43,44,45,47,49,50,51,53,54,55,57,58,59,60,61,63,64,65,68],"short":[12,57],"static":[1,2,7,9,10,15,18,21,22,23,32,33,38,40,42,43,46,51,53,54,55,57,58,60,63,64,65],"super":13,"switch":[2,14,60],"throw":[10,23],"true":[2,6,7,9,12,13,14,15,17,18,21,22,23,30,32,37,40,41,42,43,44,49,53,54,55,59,60,61,63,64,68],"void":[1,2,3,6,7,9,10,12,14,15,18,21,22,24,27,30,32,33,37,38,40,41,42,43,44,47,49,50,53,54,55,58,59,60,61,63,65,68],"while":[9,10,15,22,42,44,51,61,63,64,68],A:[2,6,9,12,22,29,30,40,43,54,57,61],And:43,As:22,By:10,For:[14,28,33,61,64],IN:33,IT:[23,58],If:[2,5,6,10,11,32,37,42,49,53,54,55,61,63,64,67,68],In:[12,22,38],Is:[53,54,55,64],It:[2,3,5,7,9,10,12,13,18,21,22,23,30,32,33,38,42,43,59,60,61,63,64,65],NOT:[2,12],No:[2,32,44,57],Not:23,ON:10,ONE:1,On:[2,32],The:[1,2,3,5,6,7,8,9,10,11,12,13,14,17,18,21,22,23,24,25,27,28,29,30,31,32,33,38,40,41,42,43,44,45,46,47,49,50,51,52,53,54,55,57,58,59,60,61,62,63,64,65,67,68],There:[18,20,21,26,34,39,51,63],These:[8,60,61],To:[22,61],Will:[6,18,21,49,51,53,58,61,63],With:41,_1:51,_2:51,_:13,__csv_documentation__:13,__gnu_linux__:[13,62],__linux__:10,__serialization_documentation__:62,__state_machine_documentation__:63,__unnamed11__:58,__unnamed13__:58,__unnamed7__:57,__unnamed9__:57,_activest:63,_build:30,_cli:10,_event_data:63,_in:10,_out:10,_parentst:63,_rate_limit:44,_really_:43,a0:[40,41],a1:41,a2:40,a_0:24,a_1:24,a_2:24,a_gpio:17,a_pin:40,ab:[49,65],abi:[20,35],abi_encod:17,abil:[44,51],abl:[30,41,54],about:[10,13,51,55,57,58,60,63,65],abov:[2,10,18,21,22,38,43,60],absolut:[18,21,23,57],absolute_uri:57,abxi:12,ac:57,acceler:27,accept:[30,54,61],access:[17,23,35,53,58,63,66,68],accord:[23,38,40,41,42,44,61],accordingli:[9,12],accumul:[17,18,21],accur:59,ack:2,acknowledg:54,across:[3,32],act:57,action:[63,64],activ:[2,6,9,12,40,58,61,63],active_high:[2,40],active_level:9,active_low:[2,12],activeleaf:63,activelevel:9,actual:[1,2,12,15,22,32,33,61,63,65],actual_celsiu:65,actual_kelvin:65,actuat:[33,34],ad0:38,ad1:38,ad:[1,2,7,12,22,50,61],adafruit:[12,33,38,57,60],adc1:65,adc:[12,17,33,35,59],adc_atten_db_11:[3,5,12,41,65],adc_channel_1:12,adc_channel_2:12,adc_channel_6:[3,5],adc_channel_7:[3,5,65],adc_channel_8:41,adc_channel_9:41,adc_channel_t:[3,5],adc_conv_single_unit_1:[3,65],adc_digi_convert_mode_t:3,adc_typ:0,adc_unit_1:[3,5,65],adc_unit_2:[12,41],adc_unit_t:5,adcconfig:[3,5,12,41,65],add:[6,11,15,50,53,54,55,61],add_multicast_group:[53,54,55],add_publish:22,add_scan:61,add_subscrib:[9,22],addit:[3,11,14,35,41,50,64],addition:[2,9,10,61],addr:[1,12,33,53,58],address:[1,2,15,18,21,30,33,38,40,53,54,55,57,58,61,68],adjust:[32,54],ads1015:1,ads1015config:[1,12],ads1015rat:1,ads1115:1,ads1115config:1,ads1115rat:1,ads1x15:[4,12,35],ads7128:2,ads7138:[4,35],ads_read:[1,2,12],ads_read_task_fn:[1,2,12],ads_task:[1,2,12],ads_writ:[1,2,12],adventur:13,advis:49,ae:57,affect:[18,21,61],affin:64,after:[2,14,41,43,49,53,54,55,58,60,61,68],again:[22,58],against:58,agent:61,alert:2,alert_1000m:33,alert_750m:33,alert_log:2,alert_pin:2,alert_task:2,alertlog:2,algorithm:[6,7,8,11],alias:[18,21],align:43,aliv:30,all:[2,5,6,10,22,23,33,43,44,49,51,55,60,61,63],all_mv:2,alloc:[3,14,51,64],allocatingconfig:[14,15],allocation_flag:14,allow:[1,2,3,5,6,7,10,12,14,17,18,21,32,33,38,40,41,42,43,47,49,52,53,54,55,58,59,60,61,63,64,65],along:[46,58],alow:47,alpaca:[22,35],alpha:[42,47],alreadi:[22,23,24,54,55,61,64],also:[2,10,12,13,14,15,18,21,22,23,32,33,38,51,60,61,63,64],alter_unit:[3,65],altern:[3,23,57],alwai:[3,5,6,18,21,23,33,49,51,61,63],am:18,amount:[3,23,49,50],amp:7,amplitud:47,an:[0,2,5,6,9,10,11,12,17,18,21,22,23,24,25,27,28,29,31,32,33,37,38,40,41,43,45,47,49,51,53,54,55,57,60,61,63,64,68],analog:[2,3,5,33,41],analog_input:2,analogev:2,analogjoystickconfig:12,analyz:51,anaolg:12,android:[57,58],angl:[7,18,21],angle_filt:7,angle_openloop:7,angle_pid_config:7,ani:[2,5,6,7,9,10,13,18,21,30,43,53,54,55,60,61,63,64],anonym:[22,57],anoth:[10,22,23,50],answer:10,any_edg:9,anyth:[13,44,51,62,63],anywher:10,ap:[35,66,68],ap_mac:68,apa102_start_fram:43,apa:57,api:35,app:[57,58],app_main:51,appear:57,append:[2,61],appli:[3,41],applic:[35,61],appropri:[6,54,55],approxim:[2,41,46],ar:[2,4,6,7,8,10,12,15,16,17,20,22,23,26,32,33,34,38,39,40,41,43,44,49,51,52,54,57,58,59,60,61,62,63,64,66],arari:62,arbitrari:10,area:[14,15],arg:44,argument:[30,44],arithmet:24,around:[3,5,6,9,10,13,14,23,37,41,42,44,45,47,49,53,60,62,63,64],arrai:[1,2,15,18,21,24,27,28,33,38,40,45,53,54,55,58,62],arrow:10,articl:65,artifact:60,as5600:[20,35],as5600_ds000365_5:18,as5600_read:18,as5600_writ:18,asid:42,ask:64,aspect:10,asset:33,assign:50,associ:[0,3,5,9,12,14,15,17,22,37,38,40,41,42,45,50,51,53,54,55,64],associt:[53,54,55],assum:[10,43,54,55,65],assumpt:[18,21],asymmetr:59,ate:23,atom:[7,12],attach:[15,38],attenu:[0,3,5,12,41,65],attribut:[1,2,18,21,38,40,43,58,60],audio:33,audiovib:33,authent:[30,57],auto:[1,2,3,5,7,9,10,12,13,15,17,18,21,22,23,32,33,38,40,41,42,43,44,51,54,55,58,59,60,62,63,64,65],auto_seq:2,autoc:33,automat:[2,10,11,61,64],autonom:2,autostop:64,avail:[3,17,22,50,58],avdd:2,avdd_volt:2,averag:[2,11],aw9523:[35,39],aw9523_read:38,aw9523_writ:38,aw9523b:38,awaken:13,ax:[12,41],axi:[2,7,12,41],b0:57,b1:57,b25:65,b2:57,b3:57,b4:57,b7:40,b:[6,11,12,13,17,29,38,40,43,47,51,57,58,60,62,64,65],b_0:24,b_1:24,b_2:24,b_bright:38,b_down:38,b_gpio:17,b_led:38,b_pin:40,b_up:38,back:[14,23,54,55,60],background:32,backlight:15,backlight_on_valu:15,backlight_pin:15,backspac:10,bad:[11,65],band:57,bandwidth:54,base:[7,11,18,21,24,25,26,27,28,32,42,43,51,53,58,59,60,61,63,65],base_encod:60,basi:2,basic:10,batteri:22,batteryst:22,becaus:[7,18,21,23,60],been:[2,10,24,33,43,54,55,58,60,61,64],befor:[2,17,23,32,43,54,61,63,64,68],beg:23,begin:[10,22,23,54,55,57,64],behavior:[32,59],being:[1,2,3,5,7,10,12,17,18,21,22,33,38,40,41,43,58,59,60,63,64,65],belong:55,below:[2,7,63],beta:[42,47,65],better:[27,59],between:[11,22,31,45,49,58],beyond:[10,13,60],bezier:[35,48],bezierinfo:45,bgr:43,bi:58,bia:32,biequad:24,binari:23,bind:[30,44,51,54,55,61],biquad:[25,26,28,35],biquad_filt:24,biquadfilt:24,biquadfilterdf1:24,biquadfilterdf2:[18,21,24,25,28],biquadrat:24,bit0:60,bit1:60,bit:[2,12,15,38,40,42,57,58],bitfield:2,bitmask:2,bldc:[34,35],bldc_driver:6,bldc_haptic:32,bldc_motor:[7,8],bldc_test_stand:30,bldc_type:7,bldcdriver:[6,7],bldchaptic:32,bldcmotor:[7,18,21,32],ble:[57,58],ble_appear:58,ble_oob_record:58,ble_radio_nam:58,ble_rol:58,blend:11,blerol:[57,58],blob:[10,15],block:[2,3,5,10,32,42,43,54,55,60,61,64],block_siz:60,blue:[11,13,43,60],bluetooth:57,board:15,bob:[7,30],bodmer:15,bool:[2,6,7,9,12,14,15,17,18,21,22,23,30,32,37,40,41,42,43,49,53,54,55,59,60,61,63,64,68],both:[2,3,12,13,24,32,38,41,42,49,57,60],both_unit:[3,65],bound:[32,54,60],bounded_no_det:32,box:[12,58],boxart:13,bp:2,br:57,breathing_period:42,breathing_start:42,bredr:57,bright:[38,43],bro:13,broadcast:[55,57],broken:61,brushless:[6,7,8],bs:22,bsp:15,bt:[57,58],bt_device_class:58,bt_oob_record:58,bt_radio_nam:58,btappear:[57,58],bteir:57,btgoep:57,btl2cap:57,btspp:57,bttype:57,bu:[2,15],bufer:64,buffer:[2,3,9,14,22,54,60,61,62,64],buffer_s:55,build:[26,35,61],built:[13,54,62,63],bundl:12,buscfg:15,busi:55,butterworth:[26,35],butterworth_filt:25,butterworthfilt:[18,21,25,28],button:[2,12,35,37,38],button_component_nam:9,button_top:9,buzz1:33,buzz2:33,buzz3:33,buzz4:33,buzz5:33,byte_ord:43,byteord:43,bytes_encod:60,bytes_encoder_config:60,bytes_written:[9,62],c:[6,10,13,15,22,23,35,57,60,62,65],c_str:23,cach:61,calcul:[2,7,32,65],calibr:[5,7,33,41],call:[3,5,9,10,11,12,14,17,18,21,22,32,33,41,43,44,51,53,54,55,58,59,60,61,63,64,67,68],call_onc:22,callback:[1,2,3,5,7,9,12,14,17,18,21,22,33,38,40,41,42,43,51,52,53,54,55,58,59,60,61,63,64,65],callback_fn:64,camera:61,can:[2,6,7,8,9,10,11,12,14,15,17,18,21,23,30,31,32,33,41,42,43,44,45,49,51,54,55,57,58,59,60,61,62,63,64,65,67],can_chang:42,cannot:[23,54,58,61,62],capabl:[38,57,58],captur:[2,40],carrier:57,catalog:65,caus:[61,63],cb:[15,22,61],cc:58,cdn:[38,60],cell:13,celsiu:65,center:[12,32,41,49],central:57,central_onli:57,central_peripher:57,certain:[32,63],cf:57,ch04:57,ch0:2,ch1:2,ch2:2,ch3:2,ch4:2,ch5:2,ch6:2,ch7:2,chang:[7,9,11,32,38,40,42,44,47,59,61,63],change_gain:59,channel:[0,1,2,3,5,6,11,12,17,41,42,60,61,65,67,68],channel_id:2,channel_sel:2,channelconfig:42,charact:10,chart:51,chdir:23,check:[2,6,7,9,23,30,32,42,53,54,58,61,68],child:63,childstat:63,chip:[1,2,3,17,20,38,39,40,43,58,65],choos:6,chose:65,chrono:[1,2,7,9,14,18,21,33,38,40,42,43,44,51,53,54,55,58,59,60,63,64,65],chrono_liter:[1,2,12,33],chunk:57,cin:[10,63],circl:41,circuit:65,circular:41,clamp:[6,11,59,60],clang:65,class_of_devic:57,classic:57,clean:[23,54,64],cleanup:[23,53],clear:[2,15,17,58,59,61],clear_event_high_flag:2,clear_event_low_flag:2,cli:[35,63],client:[30,31,35,52,53],client_socket:[54,55],client_task:[54,55],client_task_fn:[54,55],clifilesesson:10,clisess:10,clk_speed:[1,2,12,18,21,33,38,40,58],clock:[2,43,57,60],clock_spe:15,clock_speed_hz:15,clock_src:60,close:[7,8,18,21,23,32,54,61],co:[43,60],coars:32,coarse_values_strong_det:32,code:[4,7,8,10,15,16,17,22,23,41,44,51,52,57,59,60,61,62,63,64,66],coeffici:[24,27,29,47,65],collect:[2,61],color:[10,14,15,35,43,60],color_data:14,color_map:15,column:65,com:[2,6,7,10,13,15,18,23,24,28,32,33,38,44,55,57,58,60,61,63,65,67,68],combin:[53,54,55],combo:53,come:55,comma:13,command:[7,15,30,35],common:[12,15,33,57],common_compon:10,commun:[1,2,12,18,21,33,38,40,54,55,58],compat:61,complet:[2,10,13,33,42,57,61,64],complex:64,complex_root:63,compon:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,17,18,19,20,21,22,23,24,25,27,28,29,30,32,33,34,35,37,38,39,40,41,42,43,44,45,46,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],compos:57,comput:[11,18,21,31,49,57,59,65],compute_voltag:65,condit:[17,42,64],condition_vari:[1,2,3,5,7,12,17,18,21,33,38,40,41,43,58,59,60,63,64,65],conf:[3,5],config:[1,2,3,5,6,7,9,12,14,17,18,21,23,25,27,28,32,33,37,38,40,41,42,43,44,45,47,49,51,53,54,55,57,58,59,60,61,64,65,67,68],config_esp32_wifi_nvs_en:[67,68],config_esp_maximum_retri:68,config_esp_wifi_password:[58,67,68],config_esp_wifi_ssid:[58,67,68],config_freertos_generate_run_time_stat:51,config_freertos_use_trace_facil:51,config_hardware_box:15,config_hardware_ttgo:15,config_hardware_wrover_kit:15,config_rtsp_server_port:61,configur:[0,1,2,3,5,6,7,9,10,12,14,15,17,18,21,23,25,27,28,32,33,37,38,40,41,42,43,44,45,47,49,51,53,54,55,57,58,59,60,61,62,63,64,65,68],configure_alert:2,configure_global_control:38,configure_l:38,configure_pow:6,configure_stdin_stdout:[10,63],confirm:57,connect:[7,9,12,30,33,40,42,54,57,61,67,68],connect_callback:68,connect_config:54,connectconfig:54,consecut:2,constant:59,constexpr:[1,2,15,18,21,32,38,40,58,60,62],construct:[1,2,9,10,11,18,19,21,25,28,33,38,40,44,45,47,51,53,58,61],constructor:[2,10,11,22,32,43,44,50,53,60,61,65],consum:63,contain:[0,9,10,11,12,14,15,17,22,23,29,32,37,45,50,51,55,57,58,59,61,62,63,68],content:23,context:[22,63],continu:[2,4,23,33,35,55,64,65],continuous_adc:3,continuousadc:[3,65],control:[2,6,7,8,15,18,21,22,30,32,33,35,38,40,42,43,45,57,59,61],control_point:45,control_socket:61,controller_driv:15,conveni:[10,12,13,18,21,42,53,62,63],convers:[1,2,3,11,18,21,41,53],convert:[2,5,6,7,11,12,18,21,22,23,41,49,53,61,65],convert_mod:[3,65],convieni:[45,47],cool:44,coordin:[15,37],copi:[10,11,23,50,60,63,64],copy_encod:60,core:64,core_id:[7,64],core_update_period:7,corner:15,correct:[7,63],correspond:[2,15,33,38,65],could:[2,11,13,18,23,59,62,63],couldn:[22,23],count:[1,2,7,9,17,18,21,33,38,40,42,43,44,51,58,59,60,64,65],counter:[17,18,21],counter_clockwis:7,counts_per_revolut:[17,18,21],counts_per_revolution_f:[18,21],counts_to_degre:[18,21],counts_to_radian:[18,21],coupl:[22,41],cout:10,cplusplu:10,cpp:[23,30,35,44,58,61],cpprefer:[23,44],cpu:51,cr:61,crd:17,creat:[2,7,9,10,11,12,13,15,17,18,21,23,30,32,41,43,44,49,51,54,55,57,58,59,60,61,63,64,65,67,68],create_directori:23,creation:[18,21],credenti:57,cross:[2,44,64],cs:7,cseq:61,csv2:13,csv:[2,23,35],csv_data:13,ctrl:10,cubic:45,curent:[53,63],current:[6,7,9,10,12,15,17,18,21,22,30,31,32,37,38,42,44,47,50,51,52,59,60,61,65,68],current_directori:30,current_duti:42,current_hfsm_period:63,current_limit:7,current_pid_config:7,current_sens:7,currentlyact:63,currentsensor:7,currentsensorconcept:7,cursor:[10,15],curv:45,custom:[14,22,23,33,60,62],cutoff:[7,25,27],cv:[1,2,3,5,7,12,17,18,21,22,33,38,40,41,42,43,54,58,59,60,63,64,65],cv_retval:64,cv_statu:64,cycl:[6,33,42,60],d2:12,d3:12,d4:12,d5:12,d6:12,d:[7,12,22,44,53,54,55],d_current_filt:7,dam:65,daniele77:10,data:[0,1,2,3,5,7,9,11,12,13,14,15,18,21,22,23,24,25,27,28,30,33,37,38,40,41,43,51,53,54,55,57,58,61,62,63,65,68],data_address:58,data_command_pin:15,data_len:[1,2,12,18,21,33,38,40],data_s:60,data_sheet:65,data_str:22,dataformat:2,datasheet:[18,33,38,58,60,65],datasheet_info:65,date:[3,23],date_tim:23,dav:57,db:65,dbm:57,dc:[6,7,8,15],dc_level_bit:15,dc_pin:15,dc_pin_num:15,de:22,dead_zon:6,deadband:[12,41,49],deadzon:41,deadzone_radiu:41,deal:57,debug:[44,58,63,64],debug_rate_limit:44,decod:[7,18,21,58,61],dedic:12,deep:63,deep_history_st:63,deephistoryst:63,default_address:[1,2,18,21,33,38,40],defautl:47,defin:[22,43,49,60,61,62,63],definit:[19,22],degre:[17,18,21],deinit:[3,68],del:60,delai:[7,24],delet:[5,10,12,17,23,60],delete_fn:60,delimit:13,demo:[10,15],depend:[3,32,49,60,63],depth:60,dequ:10,deriv:[59,63],describ:[14,15,49,54,57,61],descriptor:[53,54,55],deseri:[9,22,57,62],design:[12,18,21,32,34,37,43,61,63,65],desir:[0,6,32],destin:23,destroi:[1,2,3,5,6,7,9,12,17,18,21,30,33,38,40,41,43,58,59,60,61,63,64,65],destruct:64,destructor:[10,22,32,60,61],detail:[7,32,54],detect:9,detent:32,detent_config:32,detentconfig:32,determin:[18,21],determinist:3,dev:15,dev_addr:[1,2,12,18,21,33,38,40],dev_kit:15,devcfg:15,develop:[7,15,57,63],devic:[1,2,15,18,21,32,33,37,38,40,57,58,67],device_address:[1,2,18,21,33,38,40],device_class:57,devkit:15,diagno:33,diagnost:33,did_pub:22,did_sub:[9,22],differ:[2,15,18,19,20,21,22,24,26,33,39,42,43,44,58,59,60,63],digial:27,digit:[2,24,25,28],digital_biquad_filt:[24,28],digital_input:2,digital_output:2,digitalconfig:12,digitalev:2,dim:38,dimension:50,dir_entri:23,direct:[5,12,24,38,40,58],directli:[2,6,8,20,33,34,43,45],directori:[23,30],directory_iter:23,directory_list:23,disabl:[2,6,7,10,17,18,38,58,60],disconnect:[61,68],disconnect_callback:68,discontinu:49,discover:57,discuss:[10,58],displai:[13,35,57,61],display_driv:[15,16],display_event_menu:63,distinguish:62,distribut:[22,49],divid:[11,24,50,59,60,65],divider_config:65,divis:65,dma:[3,60,65],dma_en:60,dnp:2,doc:[6,10,14,30,60,65,67,68],document:[10,13,18,58,60,62,63],doe:[3,5,6,13,17,18,21,23,30,32,38,40,43,53,61,62,63],doesn:[2,23],don:[1,2,3,5,7,12,17,18,21,22,33,38,40,41,43,51,54,55,58,59,60,64,65],done:[22,42,53,54,55],dot:50,doubl:[10,14],double_buff:14,double_click:33,down:[10,12,43,53,54,55,59,63,64],doxygen:30,doxygenfunct:30,drain:2,draw:[14,15],drive:[2,7,22,33,34,38,60],driven:[32,34],driver:[1,2,7,8,10,12,14,16,18,21,34,35,37,38,40,43,58,61],driverconcept:7,drv2605:[34,35],drv:15,ds:[2,33],dsiplai:14,dsp:[24,27],dsprelat:[24,28],dual:[12,57],dualconfig:12,dummycurrentsens:7,durat:[1,2,7,9,14,18,21,32,33,38,40,42,43,44,51,53,54,55,58,59,60,63,64,65],duration0:60,duration1:60,dure:[59,63],duti:[6,42],duty_a:6,duty_b:6,duty_c:6,duty_perc:42,duty_resolut:42,dx:13,dynam:[7,32,47,58,59],dynamictask:64,e2:65,e:[10,23,33,43,47,60,63,65],each:[2,3,5,6,11,12,22,23,28,30,32,38,41,44,51,61,62],earli:[1,2,3,5,7,12,17,18,21,33,38,40,41,43,58,59,60,63,64,65],easili:[2,18,52,64],ec:[9,22,23,61,62],eccentr:[33,34],ecm:33,ed:17,edg:[2,9,18,21,32,33,60],edit:10,edr:57,eeprom:58,effici:13,eh_ctrl:58,eight:1,eir:57,either:[12,17,51,65],el_angl:7,elaps:[1,2,9,33,42,44,59,64,65],electr:7,element:[5,50],els:[2,3,5,7,9,23,38,40,62,63,65],em:[9,22],empti:[33,43,57,61,67,68],en:[6,10,23,24,25,28,30,44,53,54,55,57,58,60,65,67,68],enabl:[2,3,5,6,7,9,10,12,14,22,32,38,51,52,54,58,64,67,68],enable_if:[17,50],enable_reus:[53,54,55],encapsul:58,encod:[32,35,61],encode_fn:60,encoded_symbol:60,encoder_typ:19,encoder_update_period:[18,21],encodertyp:17,encrypt:57,end:[2,10,15,22,23,32,33,43,54,55,57,58,63],end_fram:43,endev:63,endif:15,endl:10,endpoint:[53,54,55],energi:57,enforc:63,english:[38,57],enough:64,ensur:[7,10,49,60,67,68],enter:[2,10,63],enterpris:57,entri:[51,63],enumer:[1,2,9,12,14,33,38,40,41,43,44,57,65],eoi:61,epc:57,equal:10,equat:[17,24,65],equival:[10,13,38],erm:[33,34],err:[1,2,12,18,21,23,33,38,40,58],error:[1,2,9,22,23,33,38,44,59,60,61,65],error_cod:[9,22,23,61,62],error_rate_limit:44,esp32:[3,6,10,12,23,30,32,41,60,61,67,68],esp32s2:3,esp32s3:3,esp:[3,5,6,9,10,15,17,24,27,30,35,42,44,55,58,60,61,64,67,68],esp_err_t:[15,60],esp_err_to_nam:[1,2,33,38],esp_error_check:15,esp_lcd_ili9341:15,esp_log:44,esp_ok:[1,2,12,18,21,33,38,40,58,60],esphom:15,espp:[1,2,3,5,6,7,9,10,11,12,14,15,17,18,21,22,23,24,25,27,28,30,31,32,33,37,38,40,41,42,43,44,45,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],espressif:[6,10,15,27,55,60,67,68],etc:[9,23,38,40,43,59,60,62],evalu:[45,47],even:[58,62],evenli:32,event1:22,event1_cb:22,event2:22,event2_cb:22,event:[2,9,35,58,63,68],event_callback_fn:[9,22],event_count:2,event_flag:2,event_high_flag:2,event_low_flag:2,event_manag:22,eventbas:63,eventdata:68,eventmanag:[9,22],everi:[14,18,21,44],everybodi:10,everyth:10,exactli:57,exampl:[4,8,16,52,66],exceed:68,excel:7,except:[10,23],exchang:57,execut:[10,22,63,64],exis:68,exist:[6,10,13,23,61,62,63],exit:[1,2,3,5,7,10,12,17,18,21,33,38,40,41,43,58,59,60,63,64,65],exitact:10,exitchildren:63,exitselect:63,exp:[47,51],expand:35,explicit:[9,10,53,61,65],explicitli:10,expos:[10,13,44],extend:57,extern:[2,10,33,41,57,63],external_typ:57,extra:[60,61],extra_head:61,exttrigedg:33,exttriglvl:33,f:23,f_cutoff:[25,27],f_sampl:[25,27],facil:51,factor:[18,21,27,32,65],fade:42,fade_time_m:42,fahrenheit:65,fail:[1,2,9,12,18,21,33,38,40,58,62,68],fake:64,fall:[2,9,58,60],falling_edg:9,fals:[1,2,3,5,6,7,9,12,15,17,18,21,22,23,30,32,33,37,38,40,41,42,43,49,51,54,55,58,59,60,61,63,64,65,68],famili:[1,2],far:10,fast:[35,48,58],fast_co:46,fast_ln:46,fast_math:46,fast_sin:46,fast_sqrt:46,fastest:[18,21],fault:6,fclose:23,featur:2,feedback:[32,33,34],feel:7,few:[10,15,22,63],ff:57,fi:[67,68],field:[2,7,23,41,57,58,61],field_fal:58,field_ris:58,figur:[13,23,62,63],file2:23,file:[31,35],file_byt:23,file_cont:23,file_s:23,file_str:23,file_system:23,filenam:13,filesystem:30,fill:[15,24,27,37,41,53,54,55,58],filter:[3,5,7,17,18,21,29,35,65],filter_cutoff_hz:[18,21],filter_fn:[7,18,21],fine:32,fine_values_no_det:32,fine_values_with_det:32,finger563:63,finish:[10,32,60],first:[2,7,22,43,54,55,57,58,61,65],first_row_is_head:13,fish:10,fit:14,fix:65,fixed_length_encod:62,fixed_resistance_ohm:65,flag:[2,15,22,57,58,60],flip:49,floatrangemapp:41,flush:[14,15,23],flush_callback:[14,15],flush_cb:15,flush_fn:14,fmod:42,fmt:[2,3,5,10,12,13,15,17,18,21,22,38,40,41,42,51,54,55,58,59,60,61,62,64,65,68],foc:[6,7],foc_typ:7,foctyp:7,folder:[4,8,10,13,16,17,41,44,51,52,59,62,63,64,66],follow:[2,7,24,32,33,43,46,51,57,58,60,63,65],fopen:23,forc:[6,14],force_refresh:14,form:[24,25,61],format:[2,13,15,22,23,35,51,57,61,64,65],formula:65,forum:57,found:[18,21,33,57,58],four:1,frac:[24,47,65],frag_typ:61,fragment:61,frame:[2,43,61],fread:23,free:[14,23,42,60],free_spac:23,freebook:[24,28],freerto:[51,64],frequenc:[3,5,18,21,25,27,32,42],frequency_hz:42,frequent:[14,59],from:[1,2,3,5,6,7,10,11,12,14,15,18,21,22,23,26,30,32,33,34,35,37,38,40,41,42,44,47,49,50,53,54,55,57,58,59,60,61,62,63,64,65,68],from_sockaddr:53,fs:23,fseek:23,ftell:23,fthat:11,ftm:58,ftp:[35,57,61],ftp_anon:57,ftp_client_sess:30,ftp_ftp:57,ftp_server:30,ftpclientsess:30,ftpserver:30,fulfil:[18,21],full:[6,38,43,61],fulli:[33,63,64],fun:22,further:61,futur:[44,57,61],fwrite:23,g:[11,23,33,38,43,47,60,65],g_bright:38,g_down:38,g_led:38,g_up:38,gain:[1,32,59],game:57,gamepad:[57,58],gamma:[42,47],gate:6,gaussian:[35,42,48],gb:13,gbc:13,gener:[2,18,21,26,53,57,60,61,67,68],generatedeventbas:63,generic_hid:57,geometr:11,get:[1,2,3,6,7,9,10,11,12,13,14,15,17,18,21,22,23,30,32,37,40,41,42,43,47,51,53,54,55,57,58,59,60,61,62,63,64,65,68],get_accumul:[18,21],get_all_mv:2,get_celsiu:65,get_config:59,get_count:[17,18,21],get_data:61,get_degre:[17,18,21],get_digital_input_valu:2,get_duti:42,get_electrical_angl:7,get_error:59,get_event_data:2,get_event_flag:2,get_event_high_flag:2,get_event_low_flag:2,get_fahrenheit:65,get_free_spac:23,get_ftm_length:58,get_head:61,get_height:61,get_histori:10,get_info:64,get_integr:59,get_interrupt_captur:40,get_interrupt_statu:58,get_ipv4_info:[53,54,55],get_jpeg_data:61,get_kelvin:65,get_mechanical_degre:[18,21],get_mechanical_radian:[18,21],get_mjpeg_head:61,get_mount_point:23,get_mv:[2,3,65],get_num_q_t:61,get_offset:[15,61],get_output_cent:49,get_output_max:49,get_output_min:49,get_output_rang:49,get_packet:61,get_partition_label:23,get_payload:61,get_pin:[38,40],get_posit:32,get_power_supply_limit:6,get_q:61,get_q_tabl:61,get_quantization_t:61,get_radian:[17,18,21],get_rat:3,get_remote_info:54,get_resist:65,get_revolut:17,get_root_path:23,get_rpm:[18,21],get_rpt_head:61,get_rtp_header_s:61,get_scan_data:61,get_session_id:61,get_shaft_angl:7,get_shaft_veloc:7,get_siz:57,get_stat:12,get_total_spac:23,get_type_specif:61,get_used_spac:23,get_user_input:10,get_user_select:63,get_valu:[12,41],get_values_fn:41,get_vers:61,get_voltag:65,get_voltage_limit:6,get_width:61,getactivechild:63,getactiveleaf:63,getiniti:63,getinputhistori:10,getlin:10,getparentst:63,getsocknam:[53,54,55],getter:[50,61],gettimerperiod:63,gettin:41,gimbal:32,github:[10,13,15,32,45,55,58,60,61,63],give:[53,63,64],given:[2,22,25,61,63],glitch:17,global:[3,38],go:[22,23,63],goe:2,gone:64,goodby:10,googl:58,got:[2,22,61,68],gotten:[7,10,68],gpio:[2,6,9,12,17,38,40,42,60],gpio_a:12,gpio_a_h:[6,7],gpio_a_l:[6,7],gpio_b:12,gpio_b_h:[6,7],gpio_b_l:[6,7],gpio_c_h:[6,7],gpio_c_l:[6,7],gpio_config:2,gpio_config_t:2,gpio_down:12,gpio_en:[6,7],gpio_evt_queu:2,gpio_fault:[6,7],gpio_i:12,gpio_install_isr_servic:2,gpio_intr_negedg:2,gpio_isr_handl:2,gpio_isr_handler_add:2,gpio_joystick_select:12,gpio_left:12,gpio_mode_input:2,gpio_num:[9,43,60],gpio_num_18:15,gpio_num_19:15,gpio_num_22:15,gpio_num_23:15,gpio_num_2:9,gpio_num_45:15,gpio_num_48:15,gpio_num_4:15,gpio_num_5:15,gpio_num_6:15,gpio_num_7:15,gpio_num_t:15,gpio_pullup:12,gpio_pullup_dis:2,gpio_pullup_en:[1,2,12,18,21,33,38,40,58],gpio_right:12,gpio_select:12,gpio_start:12,gpio_up:12,gpio_x:12,gpo:58,grab:41,gradient:11,grai:44,graphic:11,grb:43,greater:44,green:[11,43,44,60],ground:12,group:[23,53,54,55,57],guarante:43,guard:63,gui:[14,15,51],guid:[10,67,68],h:[10,11,15,44,61],ha:[2,7,10,12,17,18,21,22,23,30,33,38,40,42,43,51,54,55,57,58,60,61,63,64,68],half:[18,21,24],handl:[9,10,30,38,40,43,54,55,60,63,64],handle_all_ev:63,handleev:63,handler:[2,9,55],handov:57,happen:22,haptic:35,haptic_config:32,haptic_motor:32,hapticconfig:32,hardawr:42,hardwar:[7,17,27,38,42,43,61],hart:65,has_q_tabl:61,has_stop:63,has_valu:[3,5,12,41,42,65],hash:57,have:[2,7,10,13,14,22,24,32,33,38,41,42,43,44,51,54,59,60,61,63,64,65,67,68],hc:57,heart:7,height:[14,15,61],hello:[10,58],hello_everysess:10,help:57,helper:53,henri:7,here:[10,13,18,22,33,38,40,58,59],hid:57,high:[2,3,6,9,14,17,32,40,51,60],high_level:9,high_limit:17,high_resolution_clock:[1,2,7,9,18,21,33,38,40,42,43,44,51,58,59,60,64,65],high_threshold_mv:2,high_water_mark:51,higher:[24,27],histori:[10,24,25,27,28,63],history_s:10,hmi:15,hold:[14,57,58],home:37,hop:[53,54,55],host:[2,15,38,57,67],hot:65,how:[7,13,14,17,59,62,63,65],howev:24,hpp:[0,1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,19,21,22,23,24,25,27,28,29,30,32,33,37,38,40,41,42,43,44,45,46,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],hr:57,hs:57,hsfm:63,hsv:[11,43,60],html:[6,10,14,15,24,28,57,60,67,68],http:[2,6,7,10,13,14,15,18,23,24,25,28,32,33,38,44,45,53,54,55,57,58,60,61,63,65,67,68],http_www:57,https_www:57,hue:[11,43,60],human:[13,23],human_read:23,hz:[3,32],i2c:[4,18,20,21,33,35,38,39,40,43,58],i2c_cfg:[1,2,12,18,21,33,38,40,58],i2c_config_t:[1,2,12,18,21,33,38,40,58],i2c_driver_instal:[1,2,12,18,21,33,38,40,58],i2c_freq_hz:[1,2,12,18,21,33,38,40,58],i2c_master_read_from_devic:2,i2c_master_write_read_devic:[1,12,18,21,33,38,40,58],i2c_master_write_to_devic:[1,2,12,18,21,33,38,40,58],i2c_mode_mast:[1,2,12,18,21,33,38,40,58],i2c_num:[1,2,12,18,21,33,38,40,58],i2c_param_config:[1,2,12,18,21,33,38,40,58],i2c_read:33,i2c_scl_io:[1,2,12,18,21,33,38,40,58],i2c_sda_io:[1,2,12,18,21,33,38,40,58],i2c_timeout_m:[1,2,12,18,21,33,38,40,58],i2c_writ:33,i:[2,7,13,17,35,39,43,51,59,62,63,64,65],i_gpio:17,id:[2,30,33,57,61,64],ident:10,identifi:[33,57,61],idf:[3,5,6,9,10,35,42,44,55,60,67,68],ifs:23,ifstream:23,ignor:17,iir:27,il:57,imag:61,imap:57,imax:38,imax_25:38,imax_50:38,imax_75:38,immedi:[63,64],imped:6,impl:[25,28],implement:[2,6,7,8,10,11,24,25,27,28,30,31,32,45,46,47,50,57,61,63],implicit:[18,21],impuls:27,includ:[0,1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,19,21,22,23,24,25,27,28,29,30,32,33,37,38,40,41,42,43,44,45,46,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],incom:54,incomplet:57,increas:[9,17,44,59],increment:[2,17,38],incur:14,independ:[41,50],index:[2,17,43,50,61,65],indic:[38,40,54,55,57,58,64],individu:[41,45],induct:7,infinit:27,info:[1,2,3,5,7,9,12,17,22,32,33,41,43,44,51,53,54,55,59,60,61,65],info_rate_limit:44,inform:[11,14,18,21,25,28,38,40,41,43,45,51,53,54,55,57,58,60,63,65,67,68],infrar:60,inherit:10,init:[41,53,54],init_ipv4:53,initail:[3,65],initi:[1,2,3,5,6,7,9,12,14,15,17,18,21,27,33,37,38,40,41,42,47,49,53,54,55,58,60,63,64,67,68],inlin:[1,2,3,5,6,7,9,10,12,14,15,17,18,21,22,23,24,25,27,28,30,32,33,37,38,40,41,42,43,44,45,47,49,50,51,53,54,55,57,58,59,60,61,63,64,65,67,68],inout:2,input:[2,7,9,10,12,18,21,24,25,27,28,32,33,35,38,40,41,49],input_delay_n:15,input_driv:37,input_valu:2,inquiri:57,insert:10,insid:2,instal:[1,2,9,12,18,21,33,38,40,58],instanc:[22,23],instant:42,instanti:51,instead:[10,30,49,62,63],instruct:27,instrument:[2,33],int16_t:17,int8_t:62,integ:[6,17,46,53],integr:59,integrator_max:[7,59],integrator_min:[7,59],intend:[45,63,64],interact:[10,20,22,23,39,61],interest:[12,22],interfac:[6,8,9,14,20,23,30,32,33,35,38,39,40,43,60,61],interfer:32,intermedi:57,intern:[2,10,12,15,17,24,25,27,28,33,38,40,53,63],interpol:11,interrupt:[2,9,17,38,40,58,64],interrupt_typ:9,interrupttyp:9,intr_typ:2,introduc:49,inttrig:33,invalid:[10,11],invalid_argu:10,invers:42,invert:[12,37,38,40,42,49],invert_color:15,invert_i:37,invert_input:49,invert_output:49,invert_x:37,invoc:59,io:[14,15,23,35,45,57],io_conf:2,io_num:2,ip2str:68,ip:[30,53,54,55,61,68],ip_add_membership:[53,54,55],ip_address:[30,54,55,61],ip_callback:68,ip_event_got_ip_t:68,ip_evt:68,ip_info:68,ip_multicast_loop:[53,54,55],ip_multicast_ttl:[53,54,55],ipv4:53,ipv4_ptr:53,ipv6:53,ipv6_ptr:53,ir:60,irdaobex:57,is_a_press:12,is_act:61,is_al:30,is_b_press:12,is_charg:22,is_clos:61,is_complet:61,is_connect:[30,54,61,68],is_dir:23,is_directori:23,is_down_press:12,is_en:[6,7],is_fault:6,is_floating_point:50,is_left_press:12,is_multicast_endpoint:55,is_passive_data_connect:30,is_press:[9,12],is_right_press:12,is_run:[32,64],is_select_press:12,is_start:64,is_start_press:12,is_up_press:12,is_valid:[53,54,55],isr:[2,9],issu:10,istream:10,it_st:58,item:[13,23],iter:[15,22,23,54,55,64],its:[2,3,18,21,22,30,32,38,40,47,51,53,54,55,58,59,63,67],itself:[14,22,37,61,64],join:[53,54,55],joybonnet:[1,12],joystick:[2,12,35,57],joystick_config:12,joystick_i:12,joystick_select:12,joystick_x:12,jpeg:61,jpeg_data:61,jpeg_fram:61,jpeg_frame_callback_t:61,jpeg_head:61,jpegfram:61,jpeghead:61,jpg:13,js1:41,js2:41,jump:49,just:[2,12,18,21,22,57,60,61,62,63,65],k:[10,65],k_bemf:7,kbit:58,kd:[7,32,59],kd_factor_max:32,kd_factor_min:32,keepal:54,kei:[10,57,58,61],kelvin:65,keyboard:[10,57],ki:[7,59],kind:[19,63],know:[14,18,21,22,64],known:[57,63],kohm:40,kp:[7,32,59],kp_factor:32,kv:7,kv_rate:7,label:[15,23],lack:23,lambda:[1,2,12,18,21,33,38,40,44,58,65],landscap:[14,15],landscape_invert:14,larg:61,larger:[3,10,61],last:[12,17,41,43,57,59,63],last_unus:12,latch:60,later:[6,15,17],latest:[6,10,37,41,51,59,60,65,67,68],launch:57,launcher:58,launcher_record:58,lazi:13,lcd:15,lcd_send_lin:15,lcd_spi_post_transfer_callback:15,lcd_spi_pre_transfer_callback:15,lcd_write:15,le:57,le_rol:57,le_sc_confirm:57,le_sc_random:57,lead:[3,11],leaf:63,learn:[33,57],least:[17,43,54],leav:2,led:[2,35,38,60],led_callback:42,led_channel:42,led_encod:[43,60],led_encoder_st:60,led_fade_time_m:42,led_reset_cod:60,led_stip:60,led_strip:[43,60],led_task:42,ledc:42,ledc_channel_5:42,ledc_channel_t:42,ledc_high_speed_mod:42,ledc_mode_t:42,ledc_timer_10_bit:42,ledc_timer_13_bit:42,ledc_timer_2:42,ledc_timer_bit_t:42,ledc_timer_t:42,ledstrip:43,left:[12,15,17,43],legaci:57,legend:13,len:43,length16:58,length:[2,15,24,27,43,50,57,58,60],less:[6,41,57,58,64],let:[10,14,22,51],level0:60,level1:60,level:[6,7,8,9,22,32,33,40,43,44,53,54,55,57,60,61,63,65],leverag:27,lib:33,libarari:62,libfmt:44,librari:[10,22,23,32,33,35,57,62],life:[10,62],lifecycl:14,light:[11,37,44,62,63],like:[22,53],limit:[6,7,10,17,44,57,59],limit_voltag:[6,7],line:35,line_input:10,linear:[33,34],lineinput:10,link:[13,23],links_awaken:13,list:[2,23,33,57],list_directori:23,listconfig:23,listen:[30,54,61],lit:[2,33],littl:[22,42],littlef:23,lk:[1,2,3,5,7,12,17,18,21,22,33,38,40,41,42,43,58,59,60,63,64,65],ll:[1,2,12,18,21,22,33,38,40,43,58],ln:65,load:[12,13,57],local:57,lock:[54,64],log:[2,7,9,22,32,33,35,37,38,40,42,43,51,58,60,61,64,65],log_level:[1,2,3,5,6,7,9,12,14,17,18,21,32,33,37,38,40,41,42,43,54,55,58,59,60,61,63,64,65,67,68],logger1:44,logger1_thread:44,logger2:44,logger2_thread:44,logger:[1,2,3,5,6,7,9,12,14,17,18,21,22,23,32,33,35,37,38,40,41,42,43,53,54,55,58,59,60,61,63,64,65,67,68],logger_:[14,41],logger_config:53,logger_fn:44,logic:[2,12,55,57],long_local_nam:57,longer:10,loop:[7,8,10,18,21,23,32,44,64],loop_foc:7,loop_iter:44,loopback_en:[53,54,55],loos:22,lose:10,lot:9,low:[2,5,6,7,8,9,12,17,22,40,53,57,60],low_level:9,low_limit:17,low_threshold_mv:2,lower:[17,38,40,65],lowest:64,lowpass:[26,35],lowpass_filt:27,lowpassfilt:27,lra:[33,34],lsb:[2,38],lv_area_t:[14,15],lv_color_t:[14,15],lv_disp_drv_t:[14,15],lv_disp_flush_readi:14,lv_tick_inc:14,lvgl:[14,15,37],lvgl_esp32_driv:15,lvgl_tft:15,m:[1,2,3,5,7,12,17,18,21,22,32,33,38,40,41,42,43,44,54,58,59,60,63,64,65],m_pi:[18,21,51],ma:65,mac:[57,68],mac_addr:57,mac_address:57,machin:35,macro:44,made:58,magic_enum_no_check_support:63,magnet:[20,32,35],magnetic_det:32,magnitud:[41,50,59],magnitude_squar:50,mai:[2,3,9,32,43,57,58,63],mailbox:58,mailto:57,main:[7,14,60],mainli:14,maintain:[14,18,21,58],make:[1,2,7,12,18,21,22,23,33,38,40,53,57,58,61,63,65],make_android_launch:[57,58],make_ev:63,make_le_oob_pair:[57,58],make_multicast:[53,54,55],make_oob_pair:[57,58],make_shar:[7,15],make_text:[57,58],make_uniqu:[1,2,10,12,33,42,51,54,55,60,64],make_uri:[57,58],make_wifi_config:[57,58],makeact:63,malloc_cap_8bit:14,malloc_cap_dma:14,manag:[5,11,12,13,14,23,35,38,40,42,54,55,57,58],mani:[7,9,17,22,54,55,68],manipul:9,manual:[2,10,32,61,63],manual_chid:2,map:[12,41,49,61],mapper:[35,41,48],mario:13,mark:[51,61],marker:61,mask:[38,40],maskaravivek:57,mass:[33,34],master:[1,2,10,12,15,18,21,33,38,40,55,58,60],match:[23,30],math:[35,45,47,49,50],max:[2,6,17,32,33,38,47,49,54,55,59,67],max_connect:54,max_data_s:61,max_glitch_n:17,max_led_curr:38,max_num_byt:[54,55],max_number_of_st:67,max_pending_connect:54,max_receive_s:54,max_transfer_sz:15,maximum:[6,12,18,21,38,41,49,54,55,59,61],maxledcurr:38,maybe_duti:42,maybe_mv:[3,5,65],maybe_r:3,maybe_x_mv:[12,41],maybe_y_mv:[12,41],mb:[23,57],mb_ctrl:58,mcp23x17:[35,39],mcp23x17_read:40,mcp23x17_write:40,mcpwm:[6,32],me:57,mean:[6,11,18,21,24,41,49,51,60,62,64],measur:[3,5,7,17,18,21,41,59,65],mechan:[3,7,18,21,22,30],media:57,mega_man:13,megaman1:13,megaman:13,member:[1,2,3,5,6,7,9,11,12,14,17,18,21,23,25,27,32,33,37,38,40,41,42,43,44,45,47,49,51,53,54,55,57,58,59,60,61,64,65,67,68],memori:[10,14,24,27,42,58,60,64],memset:[1,2,12,15,18,21,33,38,40,58],mention:10,menu:10,menuconfig:23,mere:6,messag:[2,9,22,23,57,58,61,62],method:[7,9,17,23,45,47,59,61,62],metroid1:13,metroid:13,micro:15,micros_per_sec:60,middl:57,millisecond:42,millivolt:65,mime_media:57,min:[2,32,49],minimum:[12,41,49,59],minu:61,minut:[18,21],mireq:15,mirror:40,mirror_i:15,mirror_x:15,miso_io_num:15,mix:11,mjepg:61,mjpeg:61,mkdir:23,mode:[1,2,3,9,12,15,18,21,32,33,38,40,42,57,58],model:[11,63],moder:5,modif:7,modifi:[15,38,61],modulo:[18,21],monitor:35,more:[2,3,10,11,14,25,26,28,33,41,42,43,44,47,53,54,55,60,63,65],mosi:15,mosi_io_num:15,most:[3,7,12,18,21,41,59],motion:[7,32],motion_control_typ:7,motioncontroltyp:7,motoion:7,motor:[6,8,18,21,32,34,35],motor_task:7,motor_task_fn:7,motor_typ:33,motorconcept:32,motortyp:33,mount:23,mount_point:23,mous:57,move:[7,10,43,51,60,64],movement:10,ms:14,msb:[2,38],msb_first:60,mt6701:[7,20,35],mt6701_read:[7,21],mt6701_write:[7,21],much:24,multi_rev_no_det:32,multicast:[53,54],multicast_address:[53,54,55],multicast_group:[53,54,55],multipl:[3,5,7,12,32,33,34,44,59,61],multipli:[32,50,59],must:[2,5,7,10,17,22,23,51,53,54,55,57,58,62,63,64,67,68],mutabl:[50,64],mutat:64,mute:2,mutex:[1,2,3,5,7,12,17,18,21,22,33,38,40,41,42,43,54,58,59,60,63,64,65],mux:2,mv:[1,2,3,5,41,65],mystruct:62,n:[2,3,5,10,12,13,17,18,21,22,23,24,28,29,38,40,41,42,51,54,55,58,59,60,61,62,64,65,68],name:[1,2,3,5,7,12,13,17,18,21,22,33,38,40,41,42,43,51,54,55,57,58,59,60,61,62,63,64,65],namespac:[1,2,12,23,33],nanosecond:17,navig:10,ndef:[35,56,58],ndeflib:57,ndefmessag:57,ne:13,nearest:[32,46],necessari:[7,64],need:[3,5,9,10,18,21,22,23,24,32,38,51,57,59,60,63,64],needs_zero_search:[18,21],neg:[43,50,59,65],negat:[12,50],neo_bff_io:43,neo_bff_num_l:43,neopixel_writ:43,network:[35,54,55,57,67],new_duti:42,new_object:62,new_siz:10,new_target:7,newli:64,newlin:51,next:[10,32,60],nf:57,nfault:7,nfc:[35,57,58],nicer:44,nm:7,no_timeout:64,nocolor:10,node:[53,54,55,63],nois:49,nomin:65,nominal_resistance_ohm:65,non:[3,32,49,58],nonallocatingconfig:14,none:[2,14,30,44,57,63],normal:[14,22,24,50],normalizd:[25,27],normalized_cutoff_frequ:[18,21,25,27],note:[1,2,3,5,7,9,10,12,17,18,21,22,23,30,32,33,38,40,41,43,44,54,55,58,59,60,62,63,64,65],noth:[6,51],notifi:[2,61,64],now:[1,2,7,9,13,18,21,22,32,33,38,40,42,43,44,51,54,55,58,59,60,64,65],ntc:65,ntc_smd_standard_series_0402:65,ntcg103jf103ft1:65,nthe:68,nullopt:[42,55],nullptr:[7,10,18,21,23,50,54,55,63,68],num:61,num_connect_retri:68,num_l:43,num_periods_to_run:42,num_pole_pair:7,num_seconds_to_run:[42,44,59,64],num_steps_per_iter:64,num_task:[51,64],num_touch:37,number:[1,2,3,7,9,10,14,15,17,18,21,23,24,27,32,33,37,38,40,42,43,46,53,54,55,57,58,60,61,65,67,68],number_of_link:23,nvs_flash_init:[67,68],o:[2,35,39],object:[7,9,10,11,13,22,43,44,47,51,57,60,61,62,63,65],occur:[22,61,63],off:[2,6,10,17,32,38,44,61,65],offset:[15,58,61],offset_i:15,offset_x:15,ofs:23,ofstream:23,ohm:[7,65],ok:61,oldest:10,on_connect:68,on_disconnect:68,on_got_ip:68,on_jpeg_fram:61,on_off_strong_det:32,on_receive_callback:55,on_response_callback:[54,55],onc:[12,17,18,21,22,61],once_flag:22,one:[2,9,10,18,21,22,30,42,43,54,55,58,60,63],oneshot:[4,35],oneshot_adc:5,oneshotadc:[5,12,41],onli:[2,7,12,13,17,18,21,22,24,41,44,50,55,57,58,60,61,62,63],oob:[57,58],open:[2,7,8,10,23,32,54,57,67,68],open_drain:[2,38],oper:[2,11,23,25,27,28,45,47,50,59,65],oppos:11,opposit:42,optim:[7,24,46],option:[3,5,6,7,10,12,14,15,18,21,37,41,42,43,44,49,53,54,55,58,61,62,64],order:[2,24,25,26,29,35,43,44,54],oreilli:57,org:[24,25,28,53,54,55,65],orient:[7,14],origin:23,oscil:[2,49],osr_128:2,osr_16:2,osr_2:2,osr_32:2,osr_4:2,osr_64:2,osr_8:2,ostream:10,ostringstream:13,other:[7,10,11,14,50,53,54,55,58,59,62,63,64,67],otherwis:[6,7,9,12,22,30,32,40,41,42,54,55,57,60,61,63,64,68],our:[42,53,54,55,64],out:[10,13,23,51,53,54,55,57,58,60,62,63,65],output:[2,7,8,10,17,22,23,24,25,27,28,30,37,38,40,42,44,47,49,51,58,59],output_cent:49,output_drive_mode_p0:38,output_invert:42,output_max:[7,49,59],output_min:[7,49,59],output_mod:2,output_rang:49,outputdrivemodep0:38,outputmod:2,outsid:[2,10,11],over:[2,6,20,23,39,42,52,54,55,61,64],overflow:[17,24],overhead:[14,22],overload:23,oversampl:2,oversampling_ratio:2,oversamplingratio:2,overstai:44,overth:2,overwrit:61,own:[3,14,18,21,30,38,40,53,54,55,67],owner:23,p0:38,p0_0:38,p0_1:38,p0_2:38,p0_3:38,p0_5:38,p1:38,p1_0:38,p1_1:38,p1_5:38,p1_6:38,p1_7:38,p1_8:38,p:[2,10,13,59],pack:12,packag:57,packet:[53,54,55,57,61],packet_:61,pad:12,page:[23,65],pair:[7,57,58],panel:37,param:[1,2,7,14,18,21,22,33,37,38,40,41,43,53,54,55,58,60,64,68],paramet:[1,2,3,5,6,7,9,10,11,12,14,15,19,22,23,24,25,27,28,30,32,33,37,38,40,41,42,43,44,45,47,49,50,53,54,55,57,58,59,60,61,63,64,65,67,68],parent:63,pars:[13,51,61],part:[6,15,32,37,65],parti:62,partit:23,partition_label:23,pass:[9,15,22,30,44,49],passiv:30,password:[30,57,67,68],pasv:30,pat:57,path:[23,30,61],paus:[14,61],payload:[57,58,61],payload_s:61,pdf:[2,18,33,38,58,60,65],pend:54,per:[1,2,3,7,18,21],perceiv:11,percent:42,percentag:[6,32,42],perform:[2,3,5,11,23,41,64],perhipher:42,period:[9,12,14,18,21,22,38,40,51,58,63],peripher:[6,17,32,34,42,43,57,60],peripheral_centr:57,peripheral_onli:[57,58],permiss:23,person:57,phase:[6,7],phase_induct:7,phase_resist:7,phone:[57,58],photo:58,pick:17,pico:41,pid:[7,32,35],pid_config:59,pin:[1,2,6,7,9,12,15,33,38,40,42,60,64],pin_bit_mask:2,pin_mask:40,pinout:7,pixel:[14,15,43,61],pixel_buffer_s:[14,15],place:[22,32],plai:[33,61],plan:65,platform:[44,64],play_hapt:32,playback:33,pleas:[10,11,13,28,33,63],plot:2,pn532:57,point:[11,17,23,24,27,32,35,37,42,45,46,50,54,55,57,66,68],pointer:[1,2,14,15,18,21,24,27,32,33,37,38,40,41,43,53,54,58,60,61,63,64,68],pokemon:13,pokemon_blu:13,pokemon_r:13,pokemon_yellow:13,polar:40,pole:7,poll:[12,18,21,38,40,58],pomax:45,pop:57,popul:55,port0:38,port1:38,port:[7,14,30,38,40,53,54,55,61],port_0_direction_mask:38,port_0_interrupt_mask:38,port_1_direction_mask:38,port_1_interrupt_mask:38,port_a:40,port_a_direction_mask:40,port_a_interrupt_mask:40,port_b:40,port_b_direction_mask:40,port_b_interrupt_mask:40,portmax_delai:2,portrait:[14,15],portrait_invert:14,porttick_period_m:[1,2,12,18,21,33,38,40,58],pos_typ:23,posit:[7,15,17,18,21,32,37,41,49],posix:[52,53],possibl:[2,6,14,49,57],post:57,post_cb:15,post_transfer_callback:14,poster:57,potenti:[3,24,30],power:[2,6,7,43,57],power_supply_voltag:[6,7],pranav:13,pre:[15,59,60],pre_cb:15,precis:60,preconfigur:33,predetermin:2,prefer:57,prefix:[2,23],prepend:44,present:[57,61],preset:33,press:[2,9,12,37],prevent:[14,59],previou:[10,42],previous:[6,7,49],primari:60,primarili:10,primary_data:60,print:[2,3,5,10,12,13,17,18,21,22,38,40,41,42,44,51,54,55,58,59,60,61,62,64,65,68],printf:[12,18,21,38,40,58],prior:[58,67,68],prioriti:[3,7,14,44,51,64],privat:10,process:[42,54,55,64],processor:[2,27,64],produc:11,product:[38,50,60,63,65],profil:32,programm:2,programmed_data:58,project:[6,10,30,60,61,67,68],prompt:10,prompt_fn:10,proper:[11,63],properli:[5,61],proport:59,protocol:[30,43,54,55,60],protocol_examples_common:10,prototyp:[22,37],provid:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,20,21,22,23,24,25,26,27,28,29,31,32,34,35,37,38,39,40,41,42,43,44,45,46,47,49,50,51,52,53,54,55,57,58,59,60,61,62,63,64,65,66,68],prt:53,pseudost:63,pub:22,publish:[9,22],pull:[2,38,40],pull_up_en:2,pulldown:9,pulldown_en:9,pullup:9,pullup_en:9,puls:[2,17,60],pulsed_high:2,pulsed_low:2,pulsing_strong_1:33,pulsing_strong_2:33,pure:[17,63],push:2,push_pul:2,push_push:38,put:58,pwm:[6,7,8,33,42],pwmanalog:33,py:41,python:51,q0:61,q0_tabl:61,q1:61,q1_tabl:61,q:[7,27,61],q_current_filt:7,q_factor:27,qt:41,quadhd_io_num:15,quadratur:17,quadwp_io_num:15,qualiti:27,quantiz:61,question:[10,13,42,58],queu:60,queue:[2,9,10,60],queue_siz:15,quickli:63,quit:58,quit_test:[12,18,21,40,58],quote_charact:13,r0:65,r1:[2,65],r25:65,r2:[2,65],r:[11,23,38,43,49,57,60,65],r_0:65,r_bright:38,r_down:38,r_led:38,r_scale:65,r_up:38,race:42,rad:7,radian:[7,17,18,21,50],radio:[57,58],radio_mac_addr:58,radiu:41,rainbow:[43,60],ram:14,ranav:13,random:57,rang:[1,6,11,18,21,23,25,27,32,34,35,41,47,48,65,67],range_mapp:49,rangemapp:[41,49],rate:[1,3,7,18,21,38,40,44],rate_limit:44,ratio:2,ration:45,raw:[1,2,5,7,12,18,21,41,45,53,57,58],rb:23,re:[10,12,18,21,33,53,54,55,60,63,65],reach:[33,54,58,63],read:[1,2,3,5,7,9,10,12,18,21,23,33,37,38,40,41,54,58,65],read_fn:[1,2,18,21,33,38,40,58],read_joystick:[12,41],read_mv:[5,12,41,65],read_mv_fn:65,read_raw:5,read_valu:13,readabl:[13,23],reader:[3,5,41],readthedoc:57,real:[22,33],realli:[13,62,63],realtim:33,reason:[62,64],receic:22,receiv:[2,15,53,54,55,58,61],receive_callback_fn:[53,54,55],receive_config:55,receiveconfig:55,recent:[2,3,7,12,18,21,41,59],recommend:[18,21,22,41],record:[57,58],rectangular:41,recurs:[23,63],recursive_directory_iter:23,recvfrom:[53,55],red:[11,13,43,44,60],redraw:14,reepres:61,refer:35,reference_wrapp:32,refresh:14,reg:58,reg_addr:[1,12,18,21,33,38,40,58],regard:[18,21],regardless:41,region:2,regist:[1,2,9,18,21,22,33,37,38,40,58,61],registr:22,registri:22,reinit:54,reiniti:54,reistor:38,rel:49,relat:[10,42],releas:9,relev:[23,65],reli:63,reliabl:[18,21,54],remain:44,remot:[35,54,55,57],remote_control:57,remote_info:55,remov:[6,10,22,23],remove_publish:22,remove_subscrib:22,renam:23,render:[14,51],repeatedli:[60,64],replac:10,report:58,repres:[11,18,21,30,42,50,57,58,59,60,61],represent:11,request:[2,30,53,54,55,57,58,61],requir:[7,58],rescal:11,reserv:57,reset:[2,15,17,58,59,60],reset_fn:60,reset_pin:15,reset_st:59,reset_tick:60,resist:[7,65],resistor:[9,38,65],resistordividerconfig:65,resiz:[10,23,51,64],resolut:[42,60],resolution_hz:[43,60],resolv:30,reson:[33,34],resourc:[5,53,54,55,58,60],respect:[4,61,63],respond:[53,54,55],respons:[14,23,27,30,57,59,61],response_callback_fn:[53,54,55],response_s:[54,55],response_timeout:55,restart:63,restartselect:63,restrict:[18,21],result:[2,3,11,50,61],resum:14,ret:15,ret_stat:60,retri:[61,68],retriev:[3,12,37,41],return_to_center_with_det:32,return_to_center_with_detents_and_multiple_revolut:32,reusabl:[10,35],revers:[54,55],revolut:[17,18,21,32],rf:58,rf_activ:58,rf_get_msg:58,rf_intterupt:58,rf_put_msg:58,rf_user:58,rf_write:58,rfc:[57,61],rfid:[57,58],rgb:[11,43,60],rh:[11,50],right:[7,12,30,43,58],rise:[9,33,58,60],rising_edg:9,risk:24,rmdir:23,rmt:[35,43],rmt_bytes_encoder_config_t:60,rmt_channel_handle_t:60,rmt_clk_src_default:60,rmt_clock_source_t:60,rmt_encod:60,rmt_encode_state_t:60,rmt_encoder_handle_t:60,rmt_encoder_t:60,rmt_encoding_complet:60,rmt_encoding_mem_ful:60,rmt_encoding_reset:60,rmt_symbol_word_t:60,rmtencod:[43,60],robust:44,robustli:49,role:57,root:[23,30,63],root_list:23,root_menu:10,root_path:23,rotari:32,rotat:[7,14,15,18,21,32,33,34,43,50,60],round:46,routin:41,row:13,row_index:13,rpm:[7,18,21],rpm_to_rad:7,rstp:57,rt_fmt_str:44,rtcp:61,rtcp_packet:61,rtcp_port:61,rtcppacket:61,rtd:57,rtp:[33,61],rtp_jpeg_packet:61,rtp_packet:61,rtp_port:61,rtpjpegpacket:61,rtppacket:61,rtsp:[35,57],rtsp_client:61,rtsp_path:61,rtsp_port:61,rtsp_server:61,rtsp_session:61,rtspclient:61,rtspserver:61,rtspsession:61,run:[3,7,10,14,18,21,22,30,32,42,44,51],runtim:44,s2:[3,15],s3:[3,12],s:[2,7,8,9,10,11,13,18,21,22,30,32,38,40,41,42,43,44,49,51,55,60,62,63,64,65],s_isdir:23,safe:[42,59],same:[2,5,7,22,57,59],sampl:[1,2,3,7,10,18,21,24,25,27,28,58,59,65],sample_mv:[1,12],sample_r:1,sample_rate_hz:[3,65],sandbox:23,sar:2,sarch:[18,21],satisfi:63,satur:[11,59],scalar:50,scale:[7,47,50,59,65],scaler:47,scan:[2,61,68],scan_data:61,scenario:[67,68],scheme:7,scl:2,scl_io_num:[1,2,12,18,21,33,38,40,58],scl_pullup_en:[1,2,12,18,21,33,38,40,58],sclk:15,sclk_io_num:15,scottbez1:32,screen:15,sda_io_num:[1,2,12,18,21,33,38,40,58],sda_pullup_en:[1,2,12,18,21,33,38,40,58],sdp:61,search:[18,21],second:[1,2,3,7,18,21,25,26,35,38,40,42,44,50,58,61,64,65],secondari:14,seconds_per_minut:[18,21],seconds_since_start:51,section:[11,25,26,35],sectionimpl:28,secur:[57,67,68],security_manager_flag:57,security_manager_tk:57,see:[2,7,10,11,13,14,15,17,24,25,28,33,41,45,51,53,54,55,57,58,60,63,65,67,68],seek_end:23,seek_set:23,seekg:23,seem:[23,61],segment:14,sel:2,select:[2,3,12,30,33,43,57,63],select_bit_mask:2,select_librari:33,select_press:2,select_valu:2,send:[9,14,15,30,43,54,55,58,60,61],send_bright:43,send_command:15,send_config:[54,55],send_data:15,send_fram:61,send_request:61,send_rtcp_packet:61,send_rtp_packet:61,sendconfig:55,sender:[53,54,55],sender_info:[53,54,55],sendto:53,sens:7,sensor:[7,18,21,65],sensor_direct:7,sensorconcept:7,sensordirect:7,sent:[2,15,30,43,54,55,60,61],separ:[12,13,14,51],sequenc:[2,22,33,51,57,58,63],seri:[28,61,65],serial:[9,20,22,33,35,38,39,40,57,58,61],serializa:62,series_second_order_sect:[24,28],serizalizt:13,server:[31,35,52,53],server_address:[54,55,61],server_config:55,server_port:61,server_socket:[54,55],server_task:54,server_task_config:[54,55],server_task_fn:54,server_uri:61,servic:[2,57],session:[10,30,60,61],session_st:60,set:[2,6,7,9,10,15,22,33,38,40,41,42,43,46,47,49,51,53,54,55,57,58,60,61,63,65,67,68],set_al:43,set_analog_alert:2,set_ap_mac:68,set_calibr:41,set_config:59,set_deadzon:41,set_digital_alert:2,set_digital_output_mod:2,set_digital_output_valu:2,set_direct:[38,40],set_drawing_area:15,set_duti:42,set_encod:[43,60],set_fade_with_tim:42,set_histori:10,set_history_s:10,set_input_polar:40,set_interrupt:38,set_interrupt_mirror:40,set_interrupt_on_chang:40,set_interrupt_on_valu:40,set_interrupt_polar:40,set_label:15,set_log_level:22,set_met:15,set_mod:33,set_motion_control_typ:7,set_offset:15,set_payload:61,set_phase_st:6,set_phase_voltag:7,set_pin:[38,40],set_pixel:43,set_pull_up:40,set_pwm:6,set_receive_timeout:[53,54,55],set_record:58,set_session_log_level:61,set_verbos:44,set_vers:61,set_voltag:6,set_waveform:33,setactivechild:63,setcolor:10,setdeephistori:63,setinputhistori:10,setinputhistorys:10,setnocolor:10,setparentst:63,setpoint:[7,32],setshallowhistori:63,setter:[50,61],setup:[2,61],sever:[20,26,39],sftp:57,sgn:46,shaft:[7,18,21],shallow:63,shallow_history_st:63,shallowhistoryst:63,shape:47,share:57,shared_ptr:7,sharp_click:33,sheet:2,shield:12,shift:[43,47],shift_bi:43,shift_left:43,shift_right:43,shifter:47,shop:[38,60],short_local_nam:57,shorten:57,should:[6,7,10,11,12,14,15,23,24,27,40,41,42,43,50,53,54,55,59,60,61,63,64],shouldn:[23,44],show:[10,43,63],showcas:22,shown:44,shut:64,side:[6,31],sign:[17,46,49],signal:[2,12,14,24,25,27,28,33,43,59,60],signatur:64,similar:60,simpl:[0,5,9,22,23,29,30,44,57,59,62,65],simplefoc:7,simpler:[42,60],simpli:[2,3,10,18],simplifi:61,simultan:[10,57],sin:51,sinc:[2,17,18,21,22,23,38,60,61,64,65],singl:[2,5,17,32,43,44],single_unit_1:[3,65],single_unit_2:3,singleton:[22,23],sinusoid:7,sip:57,sixteen:1,size:[1,9,10,12,14,23,33,51,54,55,57,58,60,61,62,64,65],size_t:[1,2,3,7,9,10,12,13,14,15,17,18,21,23,24,25,27,28,33,38,40,42,43,44,51,53,54,55,60,61,62,64,68],sizeof:[1,2,12,15,18,21,33,38,40,58,60,61],sk6085:60,sk6805:60,sk6805_10mhz_bytes_encoder_config:60,sk6805_freq_hz:43,sk6812:43,sleep:[1,2,3,5,7,12,17,18,21,22,33,38,40,41,42,43,44,51,58,59,60,63,64,65],sleep_for:[3,9,15,22,42,43,44,51,54,55,59,61,63,64,68],sleep_until:64,slope:47,slot:33,slow:5,small:[32,47],smart:57,smartknob:32,smb:57,snap:32,snprintf:64,so:[1,2,5,7,10,12,13,15,17,18,21,22,23,26,30,32,33,35,38,40,43,49,51,58,59,60,61,63,64,65],so_recvtimeo:[53,54,55],so_reuseaddr:[53,54,55],so_reuseport:[53,54,55],sockaddr:53,sockaddr_in6:53,sockaddr_in:53,sockaddr_storag:[53,54,55],socket:[30,35,52,61],socket_fd:[53,54,55],soft_bump:33,soft_fuzz:33,softwar:[2,14,22],software_rotation_en:[14,15],some:[1,2,7,10,12,18,20,21,22,23,26,32,33,38,40,44,46,51,53,57,58,60,63,64],someth:[14,64],somewhat:32,sos_filt:28,sosfilt:[25,28],sourc:[55,60],source_address:53,sp:57,sp_hash_c192:57,sp_hash_c256:57,sp_hash_r256:57,sp_random_r192:57,space:[7,11,23,32,43,60],space_vector_pwm:7,sparignli:49,sparkfun:12,spawn:[18,21,30,61,63,64],spawn_endevent_ev:63,spawn_event1_ev:63,spawn_event2_ev:63,spawn_event3_ev:63,spawn_event4_ev:63,specfici:1,special:[19,33,38,60],specif:[11,32,34,37,61,63,64],specifi:[18,21,23,32,44,55,61],speed:[7,18,21,42,54],speed_mod:42,spi2_host:15,spi:[15,18,21,40],spi_bus_add_devic:15,spi_bus_config_t:15,spi_bus_initi:15,spi_device_interface_config_t:15,spi_dma_ch_auto:15,spi_num:15,spi_queue_s:15,spic:15,spics_io_num:15,spike:47,sporad:5,spot:7,sps128:1,sps1600:1,sps16:1,sps2400:1,sps250:1,sps32:1,sps3300:1,sps475:1,sps490:1,sps64:1,sps860:1,sps8:1,sps920:1,squar:50,sr:57,ssid:[57,58,67,68],st25dv04k:58,st25dv:[35,56],st25dv_read:58,st25dv_write:58,st7789_defin:15,st7789v_8h_sourc:15,st:[23,58],st_mode:23,st_size:23,sta:[35,66],stabl:57,stack:[9,51,64],stack_size_byt:[1,2,7,12,18,21,33,38,40,43,51,54,55,58,60,64],stackoverflow:[23,58],stand:7,standalon:[20,39],standard:[23,44,49,61],star:33,start:[1,2,3,5,7,9,10,12,14,15,17,18,21,22,30,32,33,38,40,41,42,43,44,50,51,52,54,55,58,59,60,61,63,64,65],start_fast_transfer_mod:58,start_fram:43,start_receiv:55,startup:[18,21],stat:[23,51],state:[6,9,12,18,21,22,24,25,27,28,33,35,37,38,40,51,58,59,60],state_a:6,state_b:6,state_bas:63,state_c:6,state_machin:63,state_of_charg:22,statebas:63,static_cast:[2,44,60],station:[35,66,67],statist:2,statistics_en:2,statu:[2,58],std:[1,2,3,5,7,9,10,12,13,14,15,17,18,21,22,28,30,32,33,37,38,40,41,42,43,44,45,49,50,51,52,53,54,55,57,58,59,60,61,62,63,64,65,67,68],stdby:7,stdin:63,stdin_out:10,stdout:63,steinhart:65,step:64,still:41,stop:[1,2,3,5,7,12,14,17,18,21,22,30,32,33,38,40,41,42,43,51,54,55,58,59,60,61,63,65,68],stop_fast_transfer_mod:58,storag:[10,53],store:[10,12,15,23,29,47,57,58,61,65],str:13,strcutur:15,stream:[10,13,61],streamer:61,strength:32,strictli:62,string:[9,10,13,22,23,44,51,53,54,55,57,61,62,64,67,68],string_view:[15,23,30,44,54,55,57,58,61,64],strip:[35,60],strong:32,strong_buzz:33,strong_click:33,strongli:62,struct:[1,2,3,5,6,7,9,11,12,14,17,18,21,22,23,25,27,29,32,33,37,38,40,41,42,43,44,45,47,49,51,53,54,55,57,58,59,60,61,62,64,65,67,68],structur:[1,2,7,12,14,15,22,33,37,38,40,41,42,45,47,53,54,55,57,59,63,67,68],sub:[10,22],sub_menu:10,sub_sub_menu:10,subclass:[28,53,61,63],subdirectori:23,submenu:10,submodul:10,subscib:22,subscrib:[9,22],subscript:22,subsequ:[2,57],subset:12,substat:63,subsub:10,subsubmenu:10,subsystem:[3,5,14,42],subtract:50,subystem:68,success:[2,61],successfulli:[17,22,53,54,55,60,61,62],suffix:44,suggest:60,suit:11,super_mario_1:13,super_mario_3:13,super_mario_bros_1:13,super_mario_bros_3:13,suppli:[6,65],supply_mv:65,support:[2,7,10,11,12,17,19,23,33,38,43,52,57,58,61],sure:[7,61],swap:37,swap_xi:37,symlink:[2,33],symmetr:47,syst_address:58,system:[10,13,22,35,51,58,62,63,64,65],sytl:62,t5t:58,t:[1,2,3,5,7,12,13,15,17,18,21,22,23,33,38,40,41,42,43,44,45,47,49,50,51,54,55,57,58,59,60,64,65],t_0:65,ta:12,tabl:[2,23,51,57,61,65],tag:[44,57,58],take:[5,23],taken:23,talk:[38,43],target:[7,68],task1:22,task2:22,task:[1,2,3,5,7,9,12,14,17,18,21,22,30,32,33,35,38,40,41,42,43,54,55,58,59,60,61,63,65],task_1_fn:22,task_2_fn:22,task_callback:51,task_config:55,task_fn:[3,5,12,17,18,21,33,38,40,41,43,51,58,59,60,63,64,65],task_id:51,task_iter:64,task_monitor:51,task_nam:[51,64],task_prior:3,task_stack_size_byt:[9,51],taskmonitor:51,tb:12,tcp:[35,52,61],tcp_socket:54,tcpclientsess:54,tcpobex:57,tcpserver:54,tcpsocket:[53,54,61],tcptransmitconfig:54,tdata:62,tdk:65,tdown:12,tear:[53,54,55,64],teardown:61,tel:57,tell:[43,60],tellg:23,telnet:57,temp:65,temperatur:65,temperature_celsiu:22,templat:[7,17,19,23,25,28,30,32,44,45,49,50,64],termin:[10,63,64],test2:23,test:[3,7],test_dir:23,test_fil:23,test_start:64,texa:[2,33],text:[57,58],text_record:58,tflite:15,tft_driver:15,tft_espi:15,tftp:57,th:[14,29],than:[6,10,14,41,44,58,61],thank:10,thei:[10,12,32,61,63,64],them:[2,11,12,22,47,58,60,61,63,64],therefor:[3,5,10,11,18,21,33,49,64],thermistor:35,thermistor_ntcg_en:65,thi:[1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,21,22,23,24,30,32,33,35,38,40,41,42,43,44,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],thin:47,thing:51,third:62,this_thread:[3,9,15,22,42,43,44,51,54,55,59,61,63,64,68],those:[22,38,44,51,63],though:22,thread:[22,30,32,42,51,54,55,59,61,64],threshold:2,through:[2,7,32,33,43,49,60,63],throughput:3,ti:[2,33],tick:63,tickselect:63,time:[2,5,6,12,18,21,22,23,33,38,40,42,43,44,51,55,58,59,60,63,64,65,68],time_point:23,time_t:[23,30],time_to_l:[53,54,55],timeout:[53,54,55,64],timer:42,tinys3:[7,60],tk:57,tkip:57,tleft:12,tloz_links_awaken:13,tloz_links_awakening_dx:13,tlv:58,tm:51,tmc6300:7,tname:62,tnf:57,to_time_t:[23,30],toler:65,tone:43,too:61,top:63,topic:[9,22],torqu:7,torque_control:7,torquecontroltyp:7,total:[17,23],total_spac:23,touch:37,touchpad:[35,36,57],touchpad_input:37,touchpad_read:37,touchpad_read_fn:37,touchpadinput:37,tp:[23,30],tpd_commercial_ntc:65,trace:51,track:59,transact:60,transaction_queue_depth:60,transceiv:35,transfer:[15,26,31,35,58],transfer_funct:29,transferfunct:[28,29],transform:[7,22],transit:63,transition_click_1:33,transition_hum_1:33,transmiss:[54,60],transmit:[22,43,53,54,55,57],transmit_config:54,transmitt:60,transport:61,tree:[55,60,63],trigger:[2,5,32,33,40,58],tright:12,trim_polici:13,trim_whitespac:13,triple_click:33,truncat:10,ts:33,tselect:12,tstart:12,ttl:[53,54,55],tup:12,tupl:65,turn:[2,44],tvalu:62,two:[1,11,12,14,38,40,44,51,60],twothird:1,tx:57,tx_power_level:57,type5tagtyp:58,type:[1,2,4,7,9,10,12,14,17,18,20,21,22,23,26,32,33,35,37,38,39,40,41,43,44,50,53,54,55,57,58,60,61,62,64,65,68],type_specif:61,typedef:[1,2,7,9,10,14,18,21,22,33,37,38,40,41,43,53,54,55,58,60,64,65,68],typenam:[23,30,44,45,49,50],u:[50,57],ua:6,uart:10,uart_serial_plott:2,ub:6,uc:6,ud:7,udp:[35,52,61],udp_multicast:55,udp_socket:55,udpserv:55,udpsocket:[53,55],uic:[57,58],uint16_t:[1,14,15,30,37,38,57,58,60],uint32_t:[2,12,14,15,42,57,58,61,62],uint64_t:[57,58],uint8_t:[1,2,9,12,14,15,18,21,22,33,37,38,40,43,44,53,54,55,57,58,60,62,67,68],uint:60,unabl:30,unbound:32,unbounded_no_det:32,uncalibr:[12,41],uncent:49,unchang:57,under:[17,23],underflow:17,understand:57,unicast:55,uniqu:[54,61,64],unique_lock:[1,2,3,5,7,12,17,18,21,22,33,38,40,41,42,43,54,58,59,60,63,64,65],unique_ptr:[51,54,61,64],unit:[0,3,5,7,12,17,23,24,41,50,65],univers:10,unknown:[57,68],unless:22,unlimit:10,unlink:23,unmap:41,unord:55,unordered_map:61,unregist:37,unreli:55,until:[2,10,22,23,32,33,42,43,54,55,60,63,64],unus:[12,17,32],unweight:45,unwind:63,up:[2,3,10,12,14,17,23,33,38,40,47,54,58,59,61,63,64],upat:14,updat:[6,7,9,12,14,18,21,24,25,27,28,32,38,40,41,42,44,47,49,50,53,58,59,63],update_detent_config:32,update_period:[7,14,18,21],upper:[15,65],uq:7,uri:[57,58,61],uri_record:58,urn:57,urn_epc:57,urn_epc_id:57,urn_epc_pat:57,urn_epc_raw:57,urn_epc_tag:57,urn_nfc:57,us:[1,2,3,5,6,7,8,9,10,11,12,14,15,17,18,19,21,22,23,24,25,30,31,32,33,34,38,40,41,42,43,44,45,47,49,51,52,53,54,55,57,58,60,61,62,63,64,65],usag:[10,13],used_spac:23,user:[2,3,5,8,9,10,15,17,18,21,30,32,33,38,40,60,61,64],usernam:30,ust:22,util:[23,41,44,46,50,51,53,57,58],uuid:57,uuids_128_bit_complet:57,uuids_128_bit_parti:57,uuids_16_bit_complet:57,uuids_16_bit_parti:57,uuids_32_bit_complet:57,uuids_32_bit_parti:57,v:[7,11,49,50],v_in:65,val_mask:40,valid:[30,33,43,53,54,55,61],valu:[1,2,3,5,9,11,12,13,14,17,18,21,23,27,32,33,38,40,41,42,43,44,45,46,47,49,50,57,58,59,60,61,62,64,65],vari:32,variabl:[15,41,44,64],varieti:2,variou:43,ve:[10,23,64],vector2d:[35,45,48],vector2f:41,vector:[2,3,5,7,9,12,13,22,23,27,41,42,43,50,51,53,54,55,57,61,62,64,65],veloc:[7,18,21],velocity_filt:[7,18,21],velocity_filter_fn:[18,21],velocity_limit:7,velocity_openloop:7,velocity_pid_config:7,veloicti:7,veolciti:[18,21],verbos:[1,2,3,5,6,7,9,12,14,17,18,21,22,32,33,37,38,40,41,42,43,54,55,58,59,60,61,63,64,65,67,68],version:[10,50,61],via:[23,33,38,40],vibe:33,vibrat:[32,33],video:[14,61],view:[54,55,57],vio:7,virtual:[12,63],visual:51,volt:[2,6],voltag:[1,2,3,5,6,7,8,22,65],voltage_limit:6,vram0:14,vram1:14,vram:14,vram_size_byt:14,vram_size_px:14,vtaskgetinfo:51,w:[23,33,44,49],wa:[2,3,5,6,9,10,12,15,17,18,21,22,30,41,53,54,55,60,61,63,64],wai:[1,2,3,5,7,10,12,13,17,18,21,23,32,33,38,40,41,43,57,58,59,60,62,63,64,65],wait:[22,32,54,55,64],wait_for:[1,3,5,12,17,18,21,22,33,38,40,41,42,43,54,58,59,60,63,64],wait_for_respons:[54,55],wait_tim:42,wait_until:[2,7,64,65],want:[1,2,3,5,7,10,12,14,17,18,21,22,32,33,38,40,41,42,43,51,54,55,58,59,60,64,65],warn:[1,2,3,5,6,7,9,12,14,17,18,21,22,23,33,37,38,40,41,42,43,44,54,55,58,59,60,61,64,65,67,68],warn_rate_limit:44,watch:57,water:51,wave:47,waveform:33,we:[1,2,6,7,10,12,18,21,22,23,32,33,38,40,42,43,53,54,55,58,60,63,64,65],weak:32,webgm:63,weight:45,weightedconfig:45,welcom:44,well:[2,12,20,22,26,28,33,47,51,54,57,58,61,63,64],well_known:57,wep:57,were:[6,10,41,53,54,55,59,64],what:[5,6,22,60,63],whatev:[38,40],whe:68,when:[1,2,3,5,7,10,12,15,17,18,19,21,22,32,33,38,40,41,43,49,53,54,55,58,59,60,61,62,63,64,65,68],whenev:63,where:[8,17,32,51,55,63,65],whether:[3,9,12,14,18,21,23,42,43,49,53,54,55,60,61,64,68],which:[1,2,3,5,7,8,9,10,11,12,13,14,18,21,22,23,24,25,26,27,32,33,34,38,39,40,42,43,44,45,46,49,50,51,54,55,57,58,60,61,63,64,65,67,68],who:15,whole:[61,63],wi:[67,68],width:[14,15,32,61],wifi:[35,57,58],wifi_ap:67,wifi_record:58,wifi_sta:68,wifiap:67,wifiauthenticationtyp:57,wificonfig:57,wifiencryptiontyp:57,wifista:68,wiki:[24,25,28,53,54,55,65],wikipedia:[17,24,25,28,53,54,55,65],wind:59,window_size_byt:[3,65],windup:59,wire:60,wireless:58,wish:[10,12],witdth:17,within:[11,18,20,21,22,32,44,49,55,64,65],without:[2,3,7,10,32,51,58,60,61],work:[7,9,10,23,32,51,61,64],world:10,worri:65,would:[17,22,63,64],wpa2:57,wpa2_enterpris:57,wpa2_person:57,wpa:57,wpa_enterpris:57,wpa_person:57,wpa_wpa2_person:57,wrap:[6,17,22,38,60],wrapper:[3,5,9,10,13,14,23,37,41,42,44,45,47,60,62,63],write:[1,2,7,10,12,14,15,18,21,23,27,33,38,40,43,58],write_fn:[1,2,18,21,33,38,40,43,58],write_row:13,written:[43,57,58,63],wrote:[13,23],ws2811:43,ws2812:43,ws2812_10mhz_bytes_encoder_config:60,ws2812_freq_hz:60,ws2812b:60,ws2813:43,www:[2,24,28,33,57,58],x1:50,x2:50,x:[2,10,12,15,24,37,38,40,41,50,51,58,61],x_calibr:[12,41],x_mv:[1,2,12,41],xe:15,xml:30,xml_in:30,xqueuecreat:2,xqueuerec:2,xs:15,y1:50,y2:50,y:[2,12,15,24,37,41,44,47,50,61,67,68],y_calibr:[12,41],y_mv:[1,2,12,41],ye:[15,68],yellow:[13,44],yet:[7,18,21,31,64],yield:60,you:[3,7,10,12,13,14,17,22,23,42,43,44,47,49,51,58,59,60,61,62,63,67,68],your:[22,44,51],yourself:63,ys:15,z:17,zelda1:13,zelda2:13,zelda:13,zelda_2:13,zero:[7,17,43,49,58,65],zero_electric_offset:7},titles:["ADC Types","ADS1x15 I2C ADC","ADS7138 I2C ADC","Continuous ADC","ADC APIs","Oneshot ADC","BLDC Driver","BLDC Motor","BLDC APIs","Button APIs","Command Line Interface (CLI) APIs","Color APIs","Controller APIs","CSV APIs","Display","Display Drivers","Display APIs","ABI Encoder","AS5600 Magnetic Encoder","Encoder Types","Encoder APIs","MT6701 Magnetic Encoder","Event Manager APIs","File System APIs","Biquad Filter","Butterworth Filter","Filter APIs","Lowpass Filter","Second Order Sections (SoS) Filter","Transfer Function API","FTP Server","FTP APIs","BLDC Haptics","DRV2605 Haptic Motor Driver","Haptics APIs","ESPP Documentation","Input APIs","Touchpad Input","AW9523 I/O Expander","IO Expander APIs","MCP23x17 I/O Expander","Joystick APIs","LED APIs","LED Strip APIs","Logging APIs","Bezier","Fast Math","Gaussian","Math APIs","Range Mapper","Vector2d","Monitoring APIs","Network APIs","Sockets","TCP Sockets","UDP Sockets","NFC APIs","NDEF","ST25DV","PID APIs","Remote Control Transceiver (RMT)","RTSP APIs","Serialization APIs","State Machine APIs","Task APIs","Thermistor APIs","WiFi APIs","WiFi Access Point (AP)","WiFi Station (STA)"],titleterms:{"1":[32,43,60],"2":32,"class":[1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,21,22,23,24,25,27,28,30,32,33,37,38,40,41,42,43,44,45,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],"function":[29,30],"long":64,abi:17,abiencod:17,access:67,adc:[0,1,2,3,4,5,41,65],ads1x15:1,ads7138:2,alpaca:62,analog:12,ap:67,apa102:43,api:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,20,21,22,23,24,25,26,27,28,29,30,31,32,33,34,36,37,38,39,40,41,42,43,44,45,46,47,48,49,50,51,52,53,54,55,56,57,58,59,60,61,62,63,64,65,66,67,68],as5600:18,aw9523:38,basic:[32,44,51,59,64],bench:63,bezier:45,biquad:24,bldc:[6,7,8,32],box:15,breath:42,butterworth:25,button:9,buzz:32,cli:10,click:32,client:[54,55,61],color:11,command:10,complex:[13,59,62,63],config:15,continu:3,control:[12,60],csv:13,data:60,de:62,devic:63,digit:12,displai:[14,15,16],document:35,driver:[6,15,33],drv2605:33,encod:[17,18,19,20,21,60],esp32:15,espp:35,event:22,exampl:[1,2,3,5,7,9,10,12,13,15,17,18,21,22,23,32,33,38,40,41,42,43,44,51,54,55,58,59,60,61,62,63,64,65,67,68],expand:[38,39,40],fast:46,file:[0,1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,19,21,22,23,24,25,27,28,29,30,32,33,37,38,40,41,42,43,44,45,46,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],filesystem:23,filter:[24,25,26,27,28],format:44,ftp:[30,31],gaussian:47,gener:63,get_latest_info:51,haptic:[32,33,34],header:[0,1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,19,21,22,23,24,25,27,28,29,30,32,33,37,38,40,41,42,43,44,45,46,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],hfsm:63,i2c:[1,2,12],i:[38,40],ili9341:15,info:[23,64],input:[36,37],interfac:10,io:39,joystick:41,kit:15,led:[42,43],line:10,linear:[17,42],log:44,logger:44,lowpass:27,machin:63,macro:[10,13,62,63],magnet:[18,21],manag:22,mani:64,mapper:49,math:[46,48],mcp23x17:40,monitor:51,motor:[7,33],mt6701:21,multicast:55,ndef:57,network:52,newlib:23,nfc:56,o:[38,40],oneshot:[5,10],order:28,pid:59,plai:32,point:67,posix:23,rang:49,reader:13,real:63,refer:[0,1,2,3,5,6,7,9,10,11,12,13,14,15,17,18,19,21,22,23,24,25,27,28,29,30,32,33,37,38,40,41,42,43,44,45,46,47,49,50,51,53,54,55,57,58,59,60,61,62,63,64,65,67,68],remot:60,request:64,respons:[54,55],rmt:60,rotat:17,rtsp:61,run:[63,64],s3:15,second:28,section:28,serial:62,server:[30,54,55,61],so:28,socket:[53,54,55],spi:43,st25dv:58,st7789:15,sta:68,state:63,station:68,std:23,stop:64,strip:43,structur:62,system:23,task:[51,64],tcp:54,test:63,thermistor:65,thread:44,touchpad:37,transceiv:60,transfer:29,transmit:60,ttgo:15,type:[0,19],udp:55,union:[57,58],usag:[7,32],valid:65,vector2d:50,verbos:44,via:43,wifi:[66,67,68],writer:13,wrover:15,ws2812:60}}) \ No newline at end of file diff --git a/docs/serialization.html b/docs/serialization.html index ce308dbff..dfadf60fb 100644 --- a/docs/serialization.html +++ b/docs/serialization.html @@ -135,7 +135,7 @@
  • »
  • Serialization APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,14 +163,14 @@

    API Reference

    Header File

    Macros

    -__gnu_linux__
    +__gnu_linux__
    diff --git a/docs/state_machine.html b/docs/state_machine.html index 1b7c67347..258812ab5 100644 --- a/docs/state_machine.html +++ b/docs/state_machine.html @@ -139,7 +139,7 @@
  • »
  • State Machine APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -162,7 +162,7 @@

    API Reference

    Header File

    @@ -274,7 +274,7 @@

    Running the HFSM Test Bench on a Real Device:

    Header File

    @@ -424,7 +424,7 @@

    Classes

    Header File

    @@ -565,7 +565,7 @@

    Classes

    Header File

    diff --git a/docs/task.html b/docs/task.html index 055527878..d5ad59e4a 100644 --- a/docs/task.html +++ b/docs/task.html @@ -133,7 +133,7 @@
  • »
  • Task APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -156,7 +156,7 @@

    API Reference

    Header File

    @@ -390,6 +390,17 @@

    Task Request Stop Example +
    +inline bool is_running()
    +

    Is the task running?

    +
    +
    Returns
    +

    true if the task is running, false otherwise.

    +
    +
    +
    +

    Public Static Functions

    diff --git a/docs/thermistor.html b/docs/thermistor.html index a44993f56..0a569af15 100644 --- a/docs/thermistor.html +++ b/docs/thermistor.html @@ -133,7 +133,7 @@
  • »
  • Thermistor APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -173,7 +173,7 @@

    API Reference

    Header File

    diff --git a/docs/wifi/index.html b/docs/wifi/index.html index 59e994832..a3aeca093 100644 --- a/docs/wifi/index.html +++ b/docs/wifi/index.html @@ -129,7 +129,7 @@
  • »
  • WiFi APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/wifi/wifi_ap.html b/docs/wifi/wifi_ap.html index 960cbb119..49c25b5f8 100644 --- a/docs/wifi/wifi_ap.html +++ b/docs/wifi/wifi_ap.html @@ -136,7 +136,7 @@
  • WiFi APIs »
  • WiFi Access Point (AP)
  • - Edit on GitHub + Edit on GitHub

  • @@ -153,7 +153,7 @@

    API Reference

    Header File

    diff --git a/docs/wifi/wifi_sta.html b/docs/wifi/wifi_sta.html index c72f69fca..7748bfa05 100644 --- a/docs/wifi/wifi_sta.html +++ b/docs/wifi/wifi_sta.html @@ -137,7 +137,7 @@
  • WiFi APIs »
  • WiFi Station (STA)
  • - Edit on GitHub + Edit on GitHub

  • @@ -154,7 +154,7 @@

    API Reference

    Header File