diff --git a/.github/workflows/static_analysis.yml b/.github/workflows/static_analysis.yml new file mode 100644 index 000000000..5dfd6da6c --- /dev/null +++ b/.github/workflows/static_analysis.yml @@ -0,0 +1,31 @@ +name: Static analysis + +on: [pull_request] + +jobs: + static_analysis: + runs-on: ubuntu-latest + + steps: + - name: Checkout repo + uses: actions/checkout@v2 + with: + submodules: 'recursive' + + - name: Run static analysis + uses: esp-cpp/StaticAnalysis@master + with: + # only analyze changes in this PR (not recommended, since changed code + # can affect other code in the repo); We may turn this on since we have + # analyzed the rest of the code and the analysis takes a _long_ time + # (>20 minutes) + report_pr_changes_only: false + + # Do not build the project and do not use cmake to generate compile_commands.json + use_cmake: false + + # Use the 5.2 release version since it's what we build with + esp_idf_version: release/v5.2 + + # (Optional) cppcheck args + cppcheck_args: -i$GITHUB_WORKSPACE/lib -i$GITHUB_WORKSPACE/external -i$GITHUB_WORKSPACE/components/esp_littlefs -i$GITHUB_WORKSPACE/components/lvgl -i$GITHUB_WORKSPACE/components/esp-dsp --force --enable=all --inline-suppr --inconclusive --platform=mips32 --suppressions-list=$GITHUB_WORKSPACE/suppressions.txt diff --git a/components/adc/include/continuous_adc.hpp b/components/adc/include/continuous_adc.hpp index ca4cb5821..be356b42e 100644 --- a/components/adc/include/continuous_adc.hpp +++ b/components/adc/include/continuous_adc.hpp @@ -3,6 +3,7 @@ #include #include #include +#include #include "esp_adc/adc_cali.h" #include "esp_adc/adc_cali_scheme.h" @@ -48,17 +49,15 @@ class ContinuousAdc { * @brief Initialize and start the continuous adc reader. * @param config Config used to initialize the reader. */ - ContinuousAdc(const Config &config) + explicit ContinuousAdc(const Config &config) : sample_rate_hz_(config.sample_rate_hz), window_size_bytes_(config.window_size_bytes), num_channels_(config.channels.size()), conv_mode_(config.convert_mode), + result_data_(window_size_bytes_, 0xcc), logger_({.tag = "Continuous Adc", .rate_limit = std::chrono::milliseconds(100), .level = config.log_level}) { // initialize the adc continuous subsystem init(config.channels); - // allocate memory for the task to store result data from DMA - result_data_ = new uint8_t[window_size_bytes_]; - memset(result_data_, 0xcc, window_size_bytes_); // and start the task using namespace std::placeholders; task_ = @@ -78,12 +77,11 @@ class ContinuousAdc { vTaskNotifyGiveFromISR(task_handle_, &mustYield); // then stop the task task_->stop(); - delete[] result_data_; stop(); ESP_ERROR_CHECK(adc_continuous_deinit(handle_)); // clean up the calibration data - for (auto &config : configs_) { - auto id = get_id(config); + for (const auto &config : configs_) { + [[maybe_unused]] auto id = get_id(config); #if ADC_CALI_SCHEME_CURVE_FITTING_SUPPORTED ESP_ERROR_CHECK(adc_cali_delete_scheme_curve_fitting(cali_handles_[id])); #elif ADC_CALI_SCHEME_LINE_FITTING_SUPPORTED @@ -173,14 +171,14 @@ class ContinuousAdc { // wait until conversion is ready (will be notified by the registered ulTaskNotifyTake(pdTRUE, portMAX_DELAY); auto current_timestamp = std::chrono::high_resolution_clock::now(); - for (auto &config : configs_) { + for (const auto &config : configs_) { auto id = get_id(config); sums_[id] = 0; num_samples_[id] = 0; } esp_err_t ret; uint32_t ret_num = 0; - ret = adc_continuous_read(handle_, result_data_, window_size_bytes_, &ret_num, 0); + ret = adc_continuous_read(handle_, result_data_.data(), window_size_bytes_, &ret_num, 0); if (ret == ESP_ERR_TIMEOUT) { // this is ok, we read faster than the hardware could give us data return false; @@ -341,21 +339,20 @@ class ContinuousAdc { bool calibrated = false; #if ADC_CALI_SCHEME_CURVE_FITTING_SUPPORTED - if (!calibrated) { - logger_.info("calibration scheme version is {}", "Curve Fitting"); - adc_cali_curve_fitting_config_t cali_config = { - .unit_id = unit, - .atten = atten, - .bitwidth = bitwidth, - }; - ret = adc_cali_create_scheme_curve_fitting(&cali_config, &handle); - if (ret == ESP_OK) { - calibrated = true; - } + logger_.info("calibration scheme version is {}", "Curve Fitting"); + adc_cali_curve_fitting_config_t cali_config = { + .unit_id = unit, + .atten = atten, + .bitwidth = bitwidth, + }; + ret = adc_cali_create_scheme_curve_fitting(&cali_config, &handle); + if (ret == ESP_OK) { + calibrated = true; } #endif #if ADC_CALI_SCHEME_LINE_FITTING_SUPPORTED + // cppcheck-suppress knownConditionTrueFalse if (!calibrated) { logger_.info("calibration scheme version is {}", "Line Fitting"); adc_cali_line_fitting_config_t cali_config = { @@ -373,6 +370,7 @@ class ContinuousAdc { *out_handle = handle; if (ret == ESP_OK) { logger_.info("Calibration Success"); + // cppcheck-suppress knownConditionTrueFalse } else if (ret == ESP_ERR_NOT_SUPPORTED || !calibrated) { logger_.warn("eFuse not burnt, skip software calibration"); } else { @@ -399,11 +397,11 @@ class ContinuousAdc { adc_continuous_handle_t handle_; adc_digi_convert_mode_t conv_mode_; adc_digi_output_format_t output_format_; + std::vector result_data_; Logger logger_; std::unique_ptr task_; TaskHandle_t task_handle_{NULL}; std::mutex data_mutex_; - uint8_t *result_data_; std::atomic running_{false}; diff --git a/components/adc/include/oneshot_adc.hpp b/components/adc/include/oneshot_adc.hpp index 18a9e9002..acce851ef 100644 --- a/components/adc/include/oneshot_adc.hpp +++ b/components/adc/include/oneshot_adc.hpp @@ -43,7 +43,8 @@ class OneshotAdc { * @brief Initialize the oneshot adc reader. * @param config Config used to initialize the reader. */ - OneshotAdc(const Config &config) : logger_({.tag = "Oneshot Adc", .level = config.log_level}) { + explicit OneshotAdc(const Config &config) + : logger_({.tag = "Oneshot Adc", .level = config.log_level}) { init(config); } diff --git a/components/ads1x15/include/ads1x15.hpp b/components/ads1x15/include/ads1x15.hpp index 1c5c4dacf..d2bd596fc 100644 --- a/components/ads1x15/include/ads1x15.hpp +++ b/components/ads1x15/include/ads1x15.hpp @@ -34,8 +34,7 @@ class Ads1x15 { * @param data_len Number of data bytes to read. * @return True if the read was successful. */ - typedef std::function - read_fn; + typedef std::function read_fn; /** * @brief Gain values for the ADC conversion. @@ -104,7 +103,7 @@ class Ads1x15 { * @brief Construct Ads1x15 specficially for ADS1015. * @param config Configuration structure. */ - Ads1x15(const Ads1015Config &config) + explicit Ads1x15(const Ads1015Config &config) : gain_(config.gain), ads1015rate_(config.sample_rate), bit_shift_(4), address_(config.device_address), write_(config.write), read_(config.read), logger_({.tag = "Ads1015", .level = config.log_level}) {} @@ -113,7 +112,7 @@ class Ads1x15 { * @brief Construct Ads1x15 specficially for ADS1115. * @param config Configuration structure. */ - Ads1x15(const Ads1115Config &config) + explicit Ads1x15(const Ads1115Config &config) : gain_(config.gain), ads1115rate_(config.sample_rate), bit_shift_(0), address_(config.device_address), write_(config.write), read_(config.read), logger_({.tag = "Ads1115", .level = config.log_level}) {} @@ -138,7 +137,7 @@ class Ads1x15 { bool conversion_complete(std::error_code &ec); - float raw_to_mv(int16_t raw) { + float raw_to_mv(int16_t raw) const { // see data sheet Table 3 float fsRange; switch (gain_) { diff --git a/components/ads1x15/src/ads1x15.cpp b/components/ads1x15/src/ads1x15.cpp index 133a39b64..08756b58d 100644 --- a/components/ads1x15/src/ads1x15.cpp +++ b/components/ads1x15/src/ads1x15.cpp @@ -56,13 +56,14 @@ int16_t Ads1x15::sample_raw(int channel, std::error_code &ec) { return 0; } // Start with default values - uint16_t config = REG_CONFIG_CQUE_1CONV | // Comparator enabled and asserts on 1 - // match - REG_CONFIG_CLAT_NONLAT | // non-latching (default val) - REG_CONFIG_CPOL_ACTVLOW | // Alert/Rdy active low (default val) - REG_CONFIG_CMODE_TRAD | // Traditional comparator (default val) - REG_CONFIG_MODE_SINGLE; // Single conversion mode - // Set PGA/voltage range + uint16_t config = REG_CONFIG_MODE_SINGLE; + // This is equivalent to the below (since the rest are 0x0000): + // + // REG_CONFIG_CQUE_1CONV | // Comparator enabled and asserts on 1 match + // REG_CONFIG_CLAT_NONLAT | // non-latching (default val) + // REG_CONFIG_CPOL_ACTVLOW | // Alert/Rdy active low (default val) + // REG_CONFIG_CMODE_TRAD | // Traditional comparator (default val) + // REG_CONFIG_MODE_SINGLE; // Single conversion mode Set PGA/voltage range config |= (uint16_t)gain_; // Set data rate config |= rate_; diff --git a/components/ads7138/include/ads7138.hpp b/components/ads7138/include/ads7138.hpp index bc4346f4b..759df4f88 100644 --- a/components/ads7138/include/ads7138.hpp +++ b/components/ads7138/include/ads7138.hpp @@ -4,6 +4,7 @@ #include #include #include +#include #include #include @@ -177,7 +178,7 @@ class Ads7138 { * @brief Construct Ads7138 * @param config Configuration structure. */ - Ads7138(const Config &config) + explicit Ads7138(const Config &config) : config_(config), mode_(config.mode), avdd_mv_(config.avdd_volts * 1000.0f) // Convert to mV , data_format_(config.oversampling_ratio == OversamplingRatio::NONE ? DataFormat::RAW @@ -920,16 +921,16 @@ class Ads7138 { logger_.info("Statistics enabled set to {}", statistics_enabled_); } + static uint8_t bit_pred(uint8_t value, Channel channel) { + return value | (1 << static_cast(channel)); + }; + void set_pin_configuration(std::error_code &ec) { logger_.info("Setting digital mode for outputs {} and inputs {}", digital_outputs_, digital_inputs_); uint8_t data = 0; - for (auto channel : digital_inputs_) { - data |= 1 << static_cast(channel); - } - for (auto channel : digital_outputs_) { - data |= 1 << static_cast(channel); - } + std::accumulate(digital_inputs_.begin(), digital_inputs_.end(), data, bit_pred); + std::accumulate(digital_outputs_.begin(), digital_outputs_.end(), data, bit_pred); // don't have to do anything for analog inputs since they are the default // state (0) write_one_(Register::PIN_CFG, data, ec); @@ -939,9 +940,7 @@ class Ads7138 { logger_.info("Setting digital output for pins {}", digital_outputs_); // default direction is input (0) uint8_t data = 0; - for (auto channel : digital_outputs_) { - data |= 1 << static_cast(channel); - } + std::accumulate(digital_outputs_.begin(), digital_outputs_.end(), data, bit_pred); write_one_(Register::GPIO_CFG, data, ec); } @@ -951,9 +950,7 @@ class Ads7138 { logger_.info("Setting analog inputs for autonomous mode"); // configure the analog inputs for autonomous conversion sequence uint8_t data = 0; - for (auto channel : analog_inputs_) { - data |= 1 << static_cast(channel); - } + std::accumulate(analog_inputs_.begin(), analog_inputs_.end(), data, bit_pred); write_one_(Register::AUTO_SEQ_CH_SEL, data, ec); } } @@ -1204,7 +1201,7 @@ class Ads7138 { * @param raw Raw ADC value. * @return Voltage in mV. */ - float raw_to_mv(uint16_t raw) { + float raw_to_mv(uint16_t raw) const { // we have a 16-bit ADC, so we can represent 2^16 = 65536 values // we were configured with avdd_mv_ as the reference voltage, so we // can represent avdd_mv_ volts with 65536 values @@ -1218,7 +1215,7 @@ class Ads7138 { * @param mv Voltage in mV. * @return Raw ADC value. */ - uint16_t mv_to_raw(float mv) { + uint16_t mv_to_raw(float mv) const { // we have a 16-bit ADC, so we can represent 2^16 = 65536 values // we were configured with avdd_mv_ as the reference voltage, so we // can represent avdd_mv_ volts with 65536 values @@ -1512,7 +1509,7 @@ class Ads7138 { write_many_(reg, (uint8_t *)&value, 2, ec); } - void write_many_(Register reg, uint8_t *data, uint8_t len, std::error_code &ec) { + void write_many_(Register reg, const uint8_t *data, uint8_t len, std::error_code &ec) { std::lock_guard lock(mutex_); uint8_t total_len = len + 2; uint8_t data_with_header[total_len]; diff --git a/components/as5600/include/as5600.hpp b/components/as5600/include/as5600.hpp index f6c1653ce..7ad19480c 100644 --- a/components/as5600/include/as5600.hpp +++ b/components/as5600/include/as5600.hpp @@ -93,7 +93,7 @@ class As5600 { /** * @brief Construct the As5600 and start the update task. */ - As5600(const Config &config) + explicit As5600(const Config &config) : address_(config.device_address), write_(config.write), read_(config.read), velocity_filter_(config.velocity_filter), update_period_(config.update_period), logger_({.tag = "As5600", .level = config.log_level}) { diff --git a/components/aw9523/include/aw9523.hpp b/components/aw9523/include/aw9523.hpp index 4614670b5..bae93505f 100644 --- a/components/aw9523/include/aw9523.hpp +++ b/components/aw9523/include/aw9523.hpp @@ -86,7 +86,7 @@ class Aw9523 { * @brief Construct the Aw9523. Will call initialize() if auto_init is true. * @param config Config structure for configuring the AW9523 */ - Aw9523(const Config &config) + explicit Aw9523(const Config &config) : config_(config), address_(config.device_address), write_(config.write), read_(config.read), logger_({.tag = "Aw9523", .level = config.log_level}) { if (config.auto_init) { @@ -305,7 +305,7 @@ class Aw9523 { void set_interrupt(uint8_t p0, uint8_t p1, std::error_code &ec) { logger_.debug("Setting interrupt on change p0:{}, p1:{}", p0, p1); auto addr = Registers::INTPORT0; - uint8_t data[] = {p0, p1}; + const uint8_t data[] = {p0, p1}; write_many_((uint8_t)addr, data, 2, ec); } @@ -330,7 +330,7 @@ class Aw9523 { void set_direction(uint8_t p0, uint8_t p1, std::error_code &ec) { logger_.debug("Setting direction p0:{}, p1:{}", p0, p1); auto addr = Registers::DIRPORT0; - uint8_t data[] = {p0, p1}; + const uint8_t data[] = {p0, p1}; write_many_((uint8_t)addr, data, 2, ec); } @@ -355,7 +355,7 @@ class Aw9523 { void configure_led(uint8_t p0, uint8_t p1, std::error_code &ec) { logger_.debug("Configuring LED function p0:{}, p1:{}", p0, p1); auto addr = Registers::LEDMODE0; - uint8_t data[] = {p0, p1}; + const uint8_t data[] = {p0, p1}; write_many_((uint8_t)addr, data, 2, ec); } @@ -370,7 +370,7 @@ class Aw9523 { uint8_t p1 = (mask >> 8) & 0xFF; logger_.debug("Configuring LED function p0:{}, p1:{}", p0, p1); auto addr = Registers::LEDMODE0; - uint8_t data[] = {p0, p1}; + const uint8_t data[] = {p0, p1}; write_many_((uint8_t)addr, data, 2, ec); } @@ -540,7 +540,7 @@ class Aw9523 { write_many_(reg_addr, &data, 1, ec); } - void write_many_(uint8_t reg_addr, uint8_t *write_data, size_t write_data_len, + void write_many_(uint8_t reg_addr, const uint8_t *write_data, size_t write_data_len, std::error_code &ec) { uint8_t total_len = 1 + write_data_len; uint8_t data[total_len]; diff --git a/components/bldc_driver/include/bldc_driver.hpp b/components/bldc_driver/include/bldc_driver.hpp index 1f18d30a4..1fd092316 100644 --- a/components/bldc_driver/include/bldc_driver.hpp +++ b/components/bldc_driver/include/bldc_driver.hpp @@ -47,7 +47,7 @@ class BldcDriver { * @note Enables the driver. * @param config Config used to initialize the driver. */ - BldcDriver(const Config &config) + explicit BldcDriver(const Config &config) : gpio_ah_((gpio_num_t)config.gpio_a_h), gpio_al_((gpio_num_t)config.gpio_a_l), gpio_bh_((gpio_num_t)config.gpio_b_h), gpio_bl_((gpio_num_t)config.gpio_b_l), gpio_ch_((gpio_num_t)config.gpio_c_h), gpio_cl_((gpio_num_t)config.gpio_c_l), diff --git a/components/bldc_haptics/include/bldc_haptics.hpp b/components/bldc_haptics/include/bldc_haptics.hpp index c24fbebca..048957f90 100644 --- a/components/bldc_haptics/include/bldc_haptics.hpp +++ b/components/bldc_haptics/include/bldc_haptics.hpp @@ -1,5 +1,6 @@ #pragma once +#include #include #include @@ -111,7 +112,7 @@ template class BldcHaptics { /// @brief Constructor for the haptic motor /// @param config Configuration for the haptic motor - BldcHaptics(const Config &config) + explicit BldcHaptics(const Config &config) : detent_pid_({.kp = 0, // will be set later (motor_task) .ki = 0, // not configurable for now .kd = 0, // will be set later (update_detent_config) @@ -276,7 +277,7 @@ template class BldcHaptics { /// @param cv Condition variable to use for the task /// @return True if the task should be stopped, false otherwise bool motor_task(std::mutex &m, std::condition_variable &cv) { - auto start = std::chrono::steady_clock::now(); + auto start_time = std::chrono::steady_clock::now(); // if we are not moving, and we're close to the center (but not exactly at // the center), slowly move back to the center @@ -389,13 +390,9 @@ template class BldcHaptics { if (!out_of_bounds && detent_config.detent_positions.size() > 0) { // if there are manually specified detents, then we only apply torque // if we're in a detent - bool in_detent = false; - for (auto &detent : detent_config.detent_positions) { - if (detent == current_position_) { - in_detent = true; - break; - } - } + bool in_detent = std::any_of(detent_config.detent_positions.begin(), + detent_config.detent_positions.end(), + [this](int y) { return current_position_ == y; }); // if we're not in a detent, then we don't apply any torque if (!in_detent) { input = 0; @@ -415,7 +412,7 @@ template class BldcHaptics { { using namespace std::chrono_literals; std::unique_lock lk(m); - cv.wait_until(lk, start + 1ms); + cv.wait_until(lk, start_time + 1ms); } // don't want to stop the task diff --git a/components/bldc_motor/include/bldc_motor.hpp b/components/bldc_motor/include/bldc_motor.hpp index b4e842882..a4790548f 100644 --- a/components/bldc_motor/include/bldc_motor.hpp +++ b/components/bldc_motor/include/bldc_motor.hpp @@ -129,7 +129,7 @@ class BldcMotor { * @brief Create and initialize the BLDC motor, running through any * necessary sensor calibration. */ - BldcMotor(const Config &config) + explicit BldcMotor(const Config &config) : num_pole_pairs_(config.num_pole_pairs), phase_resistance_(config.phase_resistance), phase_inductance_(config.phase_inductance), kv_rating_(config.kv_rating * _SQRT2), current_limit_(config.current_limit), velocity_limit_(config.velocity_limit), @@ -844,8 +844,10 @@ class BldcMotor { // calculate the sample time from last call float Ts = std::chrono::duration(now - openloop_timestamp).count(); // quick fix for strange cases (micros overflow + timestamp not defined) - if (Ts <= 0 || Ts > 0.5f) + if (Ts <= 0 || Ts > 0.5f) { + // cppcheck-suppress unreadVariable Ts = 1e-3f; + } // save timestamp for next call openloop_timestamp = now; @@ -902,8 +904,8 @@ class BldcMotor { DqCurrent current_{0, 0}; //!< current d and q current measured // configuration parameters - float voltage_sensor_align_; // sensor and motor align voltage parameter - float velocity_index_search_; // target velocity for index search + float voltage_sensor_align_; // sensor and motor align voltage parameter + float velocity_index_search_{1.0f}; // target velocity for index search // motor physical parameters int num_pole_pairs_; diff --git a/components/bm8563/include/bm8563.hpp b/components/bm8563/include/bm8563.hpp index 55082b1e6..aab237ccf 100644 --- a/components/bm8563/include/bm8563.hpp +++ b/components/bm8563/include/bm8563.hpp @@ -20,7 +20,7 @@ class Bm8563 { /// @param data The data to write. /// @param size The number of bytes to write. /// @return True if the write was successful, false otherwise. - typedef std::function write_fn; + typedef std::function write_fn; /// @brief Function prototype for the I2C read function. /// @param address The I2C address to read from. @@ -28,19 +28,19 @@ class Bm8563 { /// @param data The data to read into. /// @param size The number of bytes to read. /// @return True if the read was successful, false otherwise. - typedef std::function read_fn; + typedef std::function read_fn; /// @brief The date structure. struct Date { - uint16_t year; ///< The year. - uint8_t month; ///< The month. + uint16_t year; ///< The year. + uint8_t month; ///< The month. uint8_t weekday; ///< The day of the week. - uint8_t day; ///< The day of the month. + uint8_t day; ///< The day of the month. }; /// @brief The time structure. struct Time { - uint8_t hour; ///< The hour. + uint8_t hour; ///< The hour. uint8_t minute; ///< The minute. uint8_t second; ///< The second. }; @@ -54,16 +54,16 @@ class Bm8563 { /// @brief The configuration structure. struct Config { write_fn write; ///< The I2C write function. - read_fn read; ///< The I2C read function. - espp::Logger::Verbosity log_level{espp::Logger::Verbosity::WARN}; ///< Log verbosity for the input driver. + read_fn read; ///< The I2C read function. + espp::Logger::Verbosity log_level{ + espp::Logger::Verbosity::WARN}; ///< Log verbosity for the input driver. }; /// @brief Constructor. /// @param config The configuration. - explicit Bm8563(const Config& config) - : write_(config.write), - read_(config.read), - logger_({.tag = "Bm8563", .level = config.log_level}) { + explicit Bm8563(const Config &config) + : write_(config.write), read_(config.read), + logger_({.tag = "Bm8563", .level = config.log_level}) { std::error_code ec; init(ec); if (ec) { @@ -74,33 +74,32 @@ class Bm8563 { /// @brief Convert a BCD value to a byte. /// @param value The BCD value. /// @return The byte value. - static uint8_t bcd2byte(uint8_t value) { - return (value >> 4) * 10 + (value & 0x0f); - } + static uint8_t bcd2byte(uint8_t value) { return (value >> 4) * 10 + (value & 0x0f); } /// @brief Convert a byte value to BCD. /// @param value The byte value. /// @return The BCD value. - static uint8_t byte2bcd(uint8_t value) { - return ((value / 10) << 4) + value % 10; - } + static uint8_t byte2bcd(uint8_t value) { return ((value / 10) << 4) + value % 10; } /// @brief Get the date and time. /// @return The date and time. DateTime get_date_time(std::error_code &ec) { DateTime dt; dt.time = get_time(ec); - if (ec) return {}; + if (ec) + return {}; dt.date = get_date(ec); - if (ec) return {}; + if (ec) + return {}; return dt; } /// @brief Set the date and time. /// @param dt The date and time. - void set_date_time(DateTime &dt, std::error_code &ec) { + void set_date_time(const DateTime &dt, std::error_code &ec) { set_date(dt.date, ec); - if (ec) return; + if (ec) + return; set_time(dt.time, ec); } @@ -124,14 +123,11 @@ class Bm8563 { /// @brief Set the date. /// @param d The date. - void set_date(const Date& d, std::error_code& ec) { + void set_date(const Date &d, std::error_code &ec) { logger_.info("setting date"); - uint8_t data[] = { - byte2bcd(d.day), - byte2bcd(d.weekday), - (uint8_t)(byte2bcd(d.month) | ((d.year < 2000) ? 0x80 : 0x00)), - byte2bcd(d.year % 100) - }; + const uint8_t data[] = {byte2bcd(d.day), byte2bcd(d.weekday), + (uint8_t)(byte2bcd(d.month) | ((d.year < 2000) ? 0x80 : 0x00)), + byte2bcd(d.year % 100)}; write_register(Registers::DATE, data, 4, ec); } @@ -153,54 +149,50 @@ class Bm8563 { /// @brief Set the time. /// @param t The time. - void set_time(const Time& t, std::error_code& ec) { + void set_time(const Time &t, std::error_code &ec) { logger_.info("Setting time"); - uint8_t data[] = { - byte2bcd(t.second), - byte2bcd(t.minute), - byte2bcd(t.hour) - }; + const uint8_t data[] = {byte2bcd(t.second), byte2bcd(t.minute), byte2bcd(t.hour)}; write_register(Registers::TIME, data, 3, ec); } protected: void init(std::error_code &ec) { logger_.info("initializing"); - uint8_t data[] = {0, 0}; + const uint8_t data[] = {0, 0}; write_register(Registers::CONTROL_STATUS1, data, 2, ec); } static constexpr int CENTURY_BIT = 0b10000000; enum class Registers : uint8_t { - CONTROL_STATUS1 = 0x00, - CONTROL_STATUS2 = 0x01, - TIME = 0x02, // seconds, minutes, hours - SECONDS = 0x02, - MINUTES = 0x03, - HOURS = 0x04, - DATE = 0x05, // day, weekday, month, year - DAY = 0x05, - WEEKDAY = 0x06, - MONTH = 0x07, - YEAR = 0x08, - - MINUTE_ALARM = 0x09, - HOUR_ALARM = 0x0a, - DAY_ALARM = 0x0b, - WEEKDAY_ALARM = 0x0c, - - TIMER_CONTROL = 0x0e, - TIMER = 0x0f, + CONTROL_STATUS1 = 0x00, + CONTROL_STATUS2 = 0x01, + TIME = 0x02, // seconds, minutes, hours + SECONDS = 0x02, + MINUTES = 0x03, + HOURS = 0x04, + DATE = 0x05, // day, weekday, month, year + DAY = 0x05, + WEEKDAY = 0x06, + MONTH = 0x07, + YEAR = 0x08, + + MINUTE_ALARM = 0x09, + HOUR_ALARM = 0x0a, + DAY_ALARM = 0x0b, + WEEKDAY_ALARM = 0x0c, + + TIMER_CONTROL = 0x0e, + TIMER = 0x0f, }; - void read_register(Registers reg, uint8_t* data, size_t size, std::error_code& ec) { + void read_register(Registers reg, uint8_t *data, size_t size, std::error_code &ec) { bool success = read_(DEFAULT_ADDRESS, (uint8_t)reg, data, size); if (!success) { ec = std::make_error_code(std::errc::io_error); } } - void write_register(Registers reg, uint8_t* data, size_t size, std::error_code& ec) { + void write_register(Registers reg, const uint8_t *data, size_t size, std::error_code &ec) { uint8_t buf[size + 1]; buf[0] = (uint8_t)reg; memcpy(buf + 1, data, size); @@ -216,16 +208,19 @@ class Bm8563 { }; } // namespace espp -[[maybe_unused]] static bool operator==(const espp::Bm8563::Date &lhs, const espp::Bm8563::Date &rhs) { +[[maybe_unused]] static bool operator==(const espp::Bm8563::Date &lhs, + const espp::Bm8563::Date &rhs) { return lhs.year == rhs.year && lhs.month == rhs.month && lhs.weekday == rhs.weekday && lhs.day == rhs.day; } -[[maybe_unused]] static bool operator==(const espp::Bm8563::Time &lhs, const espp::Bm8563::Time &rhs) { +[[maybe_unused]] static bool operator==(const espp::Bm8563::Time &lhs, + const espp::Bm8563::Time &rhs) { return lhs.hour == rhs.hour && lhs.minute == rhs.minute && lhs.second == rhs.second; } -[[maybe_unused]] static bool operator==(const espp::Bm8563::DateTime &lhs, const espp::Bm8563::DateTime &rhs) { +[[maybe_unused]] static bool operator==(const espp::Bm8563::DateTime &lhs, + const espp::Bm8563::DateTime &rhs) { return lhs.date == rhs.date && lhs.time == rhs.time; } // for allowing easy serialization/printing of the @@ -233,21 +228,18 @@ class Bm8563 { template <> struct fmt::formatter { template constexpr auto parse(ParseContext &ctx) { return ctx.begin(); } - template - auto format(espp::Bm8563::Date const &d, FormatContext &ctx) { - return fmt::format_to( - ctx.out(), "{{.year = {}, .month = {}, .weekday = {}, .day = {}}}", d.year, d.month, - d.weekday, d.day); + template auto format(espp::Bm8563::Date const &d, FormatContext &ctx) { + return fmt::format_to(ctx.out(), "{{.year = {}, .month = {}, .weekday = {}, .day = {}}}", + d.year, d.month, d.weekday, d.day); } }; template <> struct fmt::formatter { template constexpr auto parse(ParseContext &ctx) { return ctx.begin(); } - template - auto format(espp::Bm8563::Time const &t, FormatContext &ctx) { - return fmt::format_to(ctx.out(), "{{.hour = {}, .minute = {}, .second = {}}}", t.hour, - t.minute, t.second); + template auto format(espp::Bm8563::Time const &t, FormatContext &ctx) { + return fmt::format_to(ctx.out(), "{{.hour = {}, .minute = {}, .second = {}}}", t.hour, t.minute, + t.second); } }; diff --git a/components/button/include/button.hpp b/components/button/include/button.hpp index 74e36b0a7..c45a2f54a 100644 --- a/components/button/include/button.hpp +++ b/components/button/include/button.hpp @@ -66,10 +66,8 @@ class Button { /// \param config The configuration for the button explicit Button(const Config &config) : gpio_num_(config.gpio_num), callback_(config.callback), active_level_(config.active_level), + event_queue_(xQueueCreate(10, sizeof(EventData))), logger_({.tag = config.name, .level = config.log_level}) { - // make the event queue - event_queue_ = xQueueCreate(10, sizeof(EventData)); - // configure the GPIO for an interrupt gpio_config_t io_conf; memset(&io_conf, 0, sizeof(io_conf)); diff --git a/components/cli/include/line_input.hpp b/components/cli/include/line_input.hpp index 3476f6172..996eacd54 100644 --- a/components/cli/include/line_input.hpp +++ b/components/cli/include/line_input.hpp @@ -300,8 +300,8 @@ class LineInput { return false; } - int terminal_width_; - int terminal_height_; + int terminal_width_{80}; + int terminal_height_{24}; size_t history_size_ = 0; History input_history_; std::atomic should_handle_resize_{true}; diff --git a/components/color/include/color.hpp b/components/color/include/color.hpp index 05eb14df9..e0c8bf8af 100644 --- a/components/color/include/color.hpp +++ b/components/color/include/color.hpp @@ -28,7 +28,7 @@ class Rgb { * @param b Floating point value for the blue channel, should be in range * [0, 1] */ - Rgb(const float &r, const float &g, const float &b); + explicit Rgb(const float &r, const float &g, const float &b); /** * @brief Copy-construct an Rgb object from the provided object. @@ -47,7 +47,7 @@ class Rgb { * color will be changed. * @param hsv Hsv object to copy. */ - Rgb(const Hsv &hsv); + explicit Rgb(const Hsv &hsv); Rgb &operator=(const Rgb &other) = default; @@ -88,7 +88,7 @@ class Hsv { * @param s Saturation - will be clamped to be in range [0, 1] * @param v Value - will be clamped to be in range [0, 1] */ - Hsv(const float &h, const float &s, const float &v); + explicit Hsv(const float &h, const float &s, const float &v); /** * @brief Copy-construct the Hsv object @@ -101,7 +101,7 @@ class Hsv { * the conversion. * @param rgb The Rgb object to convert and copy. */ - Hsv(const Rgb &rgb); + explicit Hsv(const Rgb &rgb); Hsv &operator=(const Hsv &other) = default; diff --git a/components/color/src/color.cpp b/components/color/src/color.cpp index 27178f5ec..de81ffab7 100644 --- a/components/color/src/color.cpp +++ b/components/color/src/color.cpp @@ -40,7 +40,7 @@ Rgb &Rgb::operator+=(const Rgb &rhs) { Hsv Rgb::hsv() const { Hsv HSV; - float max = std::max(r, std::max(g, b)), min = std::min(r, std::min(g, b)), d; + float max = std::max(r, std::max(g, b)), min = std::min(r, std::min(g, b)); HSV.v = max; if (max == 0.0f) { @@ -49,7 +49,7 @@ Hsv Rgb::hsv() const { HSV.s = (max - min) / max; } if (HSV.s > 0.0f) { - d = max - min; + float d = max - min; if (r == max) { // color is between yellow and magenta HSV.h = (g - b) / d; diff --git a/components/controller/include/controller.hpp b/components/controller/include/controller.hpp index 9bcd74b02..57edd67e4 100644 --- a/components/controller/include/controller.hpp +++ b/components/controller/include/controller.hpp @@ -1,6 +1,8 @@ #pragma once +#include #include +#include #include "driver/dedic_gpio.h" #include "driver/gpio.h" @@ -134,7 +136,7 @@ class Controller { /** * @brief Create a Digital controller. */ - Controller(const DigitalConfig &config) + explicit Controller(const DigitalConfig &config) : logger_({.tag = "Digital Controller", .level = config.log_level}) { gpio_.assign((int)Button::LAST_UNUSED, -1); input_state_.assign((int)Button::LAST_UNUSED, false); @@ -154,7 +156,7 @@ class Controller { /** * @brief Create an analog joystick controller. */ - Controller(const AnalogJoystickConfig &config) + explicit Controller(const AnalogJoystickConfig &config) : joystick_(std::make_unique(config.joystick_config)), logger_({.tag = "Analog Joystick Controller", .level = config.log_level}) { gpio_.assign((int)Button::LAST_UNUSED, -1); @@ -172,7 +174,7 @@ class Controller { /** * @brief Create a dual d-pad + analog joystick controller. */ - Controller(const DualConfig &config) + explicit Controller(const DualConfig &config) : logger_({.tag = "Dual Digital Controller", .level = config.log_level}) { gpio_.assign((int)Button::LAST_UNUSED, -1); input_state_.assign((int)Button::LAST_UNUSED, false); @@ -241,11 +243,11 @@ class Controller { // configured (-1) in our vector, but the returned bitmask simply orders // them (low bit is low member in originally provided vector) so we need to // track the actual bit corresponding to the pin in the pin_state. - int bit = 0; // and pull out the state into the vector accordingly logger_.debug("Parsing bundle state from pin state 0x{:04X}", pin_state); { std::scoped_lock lk(state_mutex_); + int bit = 0; for (int i = 0; i < gpio_.size(); i++) { auto gpio = gpio_[i]; if (gpio != -1) { @@ -285,16 +287,12 @@ class Controller { void init_gpio(bool active_low) { // select only the gpios that are used (not -1) std::vector actual_gpios; - for (auto gpio : gpio_) { - if (gpio != -1) { - actual_gpios.push_back(gpio); - } - } + std::copy_if(gpio_.begin(), gpio_.end(), std::back_inserter(actual_gpios), + [](int gpio) { return gpio != -1; }); uint64_t pin_mask = 0; - for (auto gpio : actual_gpios) { - pin_mask |= (1ULL << gpio); - } + std::accumulate(actual_gpios.begin(), actual_gpios.end(), pin_mask, + [](uint64_t mask, int gpio) { return mask | (1ULL << gpio); }); gpio_config_t io_config = { .pin_bit_mask = pin_mask, .mode = GPIO_MODE_INPUT, diff --git a/components/display/include/display.hpp b/components/display/include/display.hpp index 3bd3353ff..5291acf4a 100644 --- a/components/display/include/display.hpp +++ b/components/display/include/display.hpp @@ -99,11 +99,18 @@ class Display { * @param config Display configuration including buffer size and flush * callback. */ - Display(const AllocatingConfig &config) + explicit Display(const AllocatingConfig &config) : width_(config.width), height_(config.height), display_buffer_px_size_(config.pixel_buffer_size), - led_channel_configs_(std::vector{{.gpio = (size_t)config.backlight_pin, .channel = LEDC_CHANNEL_0, .timer = LEDC_TIMER_0, .output_invert = !config.backlight_on_value}}), - backlight_(Led::Config{.timer = LEDC_TIMER_0, .frequency_hz = 5000, .channels = led_channel_configs_, .duty_resolution = LEDC_TIMER_10_BIT}), + led_channel_configs_( + std::vector{{.gpio = (size_t)config.backlight_pin, + .channel = LEDC_CHANNEL_0, + .timer = LEDC_TIMER_0, + .output_invert = !config.backlight_on_value}}), + backlight_(Led::Config{.timer = LEDC_TIMER_0, + .frequency_hz = 5000, + .channels = led_channel_configs_, + .duty_resolution = LEDC_TIMER_10_BIT}), update_period_(config.update_period), logger_({.tag = "Display", .level = config.log_level}) { logger_.debug("Initializing with allocating config!"); @@ -124,12 +131,18 @@ class Display { * @param config Display configuration including pointers to display buffer * memory, the pixel buffer size and flush callback. */ - Display(const NonAllocatingConfig &config) + explicit Display(const NonAllocatingConfig &config) : width_(config.width), height_(config.height), display_buffer_px_size_(config.pixel_buffer_size), vram_0_(config.vram0), - vram_1_(config.vram1), - led_channel_configs_(std::vector{{.gpio = (size_t)config.backlight_pin, .channel = LEDC_CHANNEL_0, .timer = LEDC_TIMER_0, .output_invert = !config.backlight_on_value}}), - backlight_(Led::Config{.timer = LEDC_TIMER_0, .frequency_hz = 5000, .channels = led_channel_configs_, .duty_resolution = LEDC_TIMER_10_BIT}), + vram_1_(config.vram1), led_channel_configs_(std::vector{ + {.gpio = (size_t)config.backlight_pin, + .channel = LEDC_CHANNEL_0, + .timer = LEDC_TIMER_0, + .output_invert = !config.backlight_on_value}}), + backlight_(Led::Config{.timer = LEDC_TIMER_0, + .frequency_hz = 5000, + .channels = led_channel_configs_, + .duty_resolution = LEDC_TIMER_10_BIT}), update_period_(config.update_period), logger_({.tag = "Display", .level = config.log_level}) { logger_.debug("Initializing with non-allocating config!"); @@ -199,7 +212,7 @@ class Display { * (to draw to it with something other than LVGL) and want to switch * back to the LVGL gui. Normally you should not call this function. */ - void force_refresh() { + void force_refresh() const { auto disp = lv_disp_get_default(); // lv_refr_now(disp); lv_area_t area = {.x1 = 0, .y1 = 0, .x2 = (int16_t)width_, .y2 = (int16_t)height_}; @@ -222,13 +235,13 @@ class Display { * @brief Return the number of pixels that vram() can hold. * @return size_t Number of pixels that fit in the display buffer. */ - size_t vram_size_px() { return display_buffer_px_size_; } + size_t vram_size_px() const { return display_buffer_px_size_; } /** * @brief Return the number of bytes that vram() can hold. * @return size_t Number of bytes that fit in the display buffer. */ - size_t vram_size_bytes() { return display_buffer_px_size_ * sizeof(lv_color_t); } + size_t vram_size_bytes() const { return display_buffer_px_size_ * sizeof(lv_color_t); } protected: /** diff --git a/components/display_drivers/example/main/display_drivers_example.cpp b/components/display_drivers/example/main/display_drivers_example.cpp index 376a15b9e..afb5e700e 100644 --- a/components/display_drivers/example/main/display_drivers_example.cpp +++ b/components/display_drivers/example/main/display_drivers_example.cpp @@ -192,7 +192,11 @@ extern "C" void app_main(void) { bool backlight_on_value = false; bool reset_value = false; bool invert_colors = false; - auto flush_cb = espp::Ili9341::flush; + int offset_x = 0; + int offset_y = 0; + bool mirror_x = false; + bool mirror_y = false; + using DisplayDriver = espp::Ili9341; auto rotation = espp::Display::Rotation::LANDSCAPE; //! [wrover_kit_config example] #endif @@ -213,7 +217,11 @@ extern "C" void app_main(void) { bool backlight_on_value = false; bool reset_value = false; bool invert_colors = false; - auto flush_cb = espp::St7789::flush; + int offset_x = 40; + int offset_y = 53; + bool mirror_x = false; + bool mirror_y = false; + using DisplayDriver = espp::St7789; auto rotation = espp::Display::Rotation::PORTRAIT; //! [ttgo_config example] #endif @@ -234,7 +242,11 @@ extern "C" void app_main(void) { bool backlight_on_value = true; bool reset_value = false; bool invert_colors = true; - auto flush_cb = espp::St7789::flush; + int offset_x = 0; + int offset_y = 0; + bool mirror_x = true; + bool mirror_y = true; + using DisplayDriver = espp::St7789; auto rotation = espp::Display::Rotation::LANDSCAPE; //! [box_config example] #endif @@ -269,50 +281,30 @@ extern "C" void app_main(void) { ret = spi_bus_add_device(spi_num, &devcfg, &spi); ESP_ERROR_CHECK(ret); -#if CONFIG_HARDWARE_WROVER_KIT - // initialize the controller - espp::Ili9341::initialize(espp::display_drivers::Config{.lcd_write = lcd_write, - .lcd_send_lines = lcd_send_lines, - .reset_pin = reset, - .data_command_pin = dc_pin, - .reset_value = reset_value, - .invert_colors = invert_colors}); -#endif -#if CONFIG_HARDWARE_TTGO - // initialize the controller - espp::St7789::initialize(espp::display_drivers::Config{ - .lcd_write = lcd_write, - .lcd_send_lines = lcd_send_lines, - .reset_pin = reset, - .data_command_pin = dc_pin, - .invert_colors = invert_colors, - .offset_x = 40, - .offset_y = 53, - }); -#endif -#if CONFIG_HARDWARE_BOX // initialize the controller - espp::St7789::initialize(espp::display_drivers::Config{ + DisplayDriver::initialize(espp::display_drivers::Config{ .lcd_write = lcd_write, .lcd_send_lines = lcd_send_lines, .reset_pin = reset, .data_command_pin = dc_pin, + .reset_value = reset_value, .invert_colors = invert_colors, - .mirror_x = true, - .mirror_y = true, + .offset_x = offset_x, + .offset_y = offset_y, + .mirror_x = mirror_x, + .mirror_y = mirror_y, }); -#endif - // initialize the display / lvgl auto display = std::make_shared( espp::Display::AllocatingConfig{.width = width, .height = height, .pixel_buffer_size = pixel_buffer_size, - .flush_callback = flush_cb, + .flush_callback = DisplayDriver::flush, .backlight_pin = backlight, .backlight_on_value = backlight_on_value, .rotation = rotation, .software_rotation_enabled = true}); + // initialize the gui Gui gui({.display = display}); size_t iterations = 0; diff --git a/components/display_drivers/example/main/gui.hpp b/components/display_drivers/example/main/gui.hpp index 3610f86d7..2999ef83a 100644 --- a/components/display_drivers/example/main/gui.hpp +++ b/components/display_drivers/example/main/gui.hpp @@ -14,7 +14,7 @@ class Gui { espp::Logger::Verbosity log_level{espp::Logger::Verbosity::WARN}; }; - Gui(const Config &config) + explicit Gui(const Config &config) : display_(config.display), logger_({.tag = "Gui", .level = config.log_level}) { init_ui(); // now start the gui updater task diff --git a/components/drv2605/include/drv2605.hpp b/components/drv2605/include/drv2605.hpp index 549d4aa61..3d437fc69 100644 --- a/components/drv2605/include/drv2605.hpp +++ b/components/drv2605/include/drv2605.hpp @@ -92,12 +92,12 @@ class Drv2605 { }; /** - * @brief The library of waveforms to use. - * @note The DRV2605 has 7 different libraries of waveforms. The first - * library is empty, and the next 5 are ERM (eccentric rotating mass) - * libraries. The last library is an LRA (linear resonant actuator) - * library. - */ + * @brief The library of waveforms to use. + * @note The DRV2605 has 7 different libraries of waveforms. The first + * library is empty, and the next 5 are ERM (eccentric rotating mass) + * libraries. The last library is an LRA (linear resonant actuator) + * library. + */ enum class Library { EMPTY = 0, ERM_0 = 1, @@ -124,7 +124,7 @@ class Drv2605 { /** * @brief Construct and initialize the DRV2605. */ - Drv2605(const Config &config) + explicit Drv2605(const Config &config) : motor_type_(config.motor_type), address_(config.device_address), write_(config.write), read_(config.read), logger_({.tag = "Drv2605", .level = config.log_level}) { if (config.auto_init) { @@ -299,7 +299,7 @@ class Drv2605 { write_many_(reg_addr, &data, 1, ec); } - void write_many_(uint8_t reg_addr, uint8_t *write_data, size_t write_data_len, + void write_many_(uint8_t reg_addr, const uint8_t *write_data, size_t write_data_len, std::error_code &ec) { uint8_t total_len = 1 + write_data_len; uint8_t data[total_len]; @@ -320,12 +320,10 @@ class Drv2605 { } // namespace espp // for easy printing of the enums with the libfmt library: -template <> -struct fmt::formatter { +template <> struct fmt::formatter { constexpr auto parse(format_parse_context &ctx) { return ctx.begin(); } - template - auto format(espp::Drv2605::Mode m, FormatContext &ctx) { + template auto format(espp::Drv2605::Mode m, FormatContext &ctx) { switch (m) { case espp::Drv2605::Mode::INTTRIG: return fmt::format_to(ctx.out(), "INTTRIG"); @@ -349,12 +347,10 @@ struct fmt::formatter { } }; -template <> -struct fmt::formatter { +template <> struct fmt::formatter { constexpr auto parse(format_parse_context &ctx) { return ctx.begin(); } - template - auto format(espp::Drv2605::Waveform w, FormatContext &ctx) { + template auto format(espp::Drv2605::Waveform w, FormatContext &ctx) { switch (w) { case espp::Drv2605::Waveform::END: return fmt::format_to(ctx.out(), "END"); @@ -400,12 +396,10 @@ struct fmt::formatter { } }; -template <> -struct fmt::formatter { +template <> struct fmt::formatter { constexpr auto parse(format_parse_context &ctx) { return ctx.begin(); } - template - auto format(espp::Drv2605::Library l, FormatContext &ctx) { + template auto format(espp::Drv2605::Library l, FormatContext &ctx) { switch (l) { case espp::Drv2605::Library::EMPTY: return fmt::format_to(ctx.out(), "EMPTY"); diff --git a/components/encoder/include/abi_encoder.hpp b/components/encoder/include/abi_encoder.hpp index 22cab7e68..c04fe9752 100644 --- a/components/encoder/include/abi_encoder.hpp +++ b/components/encoder/include/abi_encoder.hpp @@ -47,7 +47,8 @@ template class AbiEncoder { * call the start() method at least once. */ template - AbiEncoder(const Config &config) : logger_({.tag = "AbiEncoder", .level = config.log_level}) { + explicit AbiEncoder(const Config &config) + : logger_({.tag = "AbiEncoder", .level = config.log_level}) { // we only care about counts_per_revolution if it is EncoderType::ROTATIONAL if constexpr (type == EncoderType::ROTATIONAL) { if (config.counts_per_revolution == 0) { diff --git a/components/file_system/example/main/file_system_example.cpp b/components/file_system/example/main/file_system_example.cpp index 7085cc4cb..e735dece2 100644 --- a/components/file_system/example/main/file_system_example.cpp +++ b/components/file_system/example/main/file_system_example.cpp @@ -14,27 +14,29 @@ extern "C" void app_main(void) { // This example shows using the file system to read/write files logger.info("Running file system example!"); - //! [file_system info example] - auto &fs = espp::FileSystem::get(); - // NOTE: partition label is configured by menuconfig and should match the - // partition label in the partition table (partitions.csv). - // returns a const char* - auto partition_label = fs.get_partition_label(); - // returns a std::string - auto mount_point = fs.get_mount_point(); - // returns a std::filesystem::path - auto root_path = fs.get_root_path(); - logger.info("Partition label: {}", partition_label); - logger.info("Mount point: {}", mount_point); - logger.info("Root path: {}", root_path.string()); - // human_readable returns a string with the size and unit, e.g. 1.2 MB - auto total_space = fs.human_readable(fs.get_total_space()); - auto free_space = fs.human_readable(fs.get_free_space()); - auto used_space = fs.human_readable(fs.get_used_space()); - logger.info("Total space: {}", total_space); - logger.info("Free space: {}", free_space); - logger.info("Used space: {}", used_space); - //! [file_system info example] + { + //! [file_system info example] + auto &fs = espp::FileSystem::get(); + // NOTE: partition label is configured by menuconfig and should match the + // partition label in the partition table (partitions.csv). + // returns a const char* + auto partition_label = fs.get_partition_label(); + // returns a std::string + auto mount_point = fs.get_mount_point(); + // returns a std::filesystem::path + auto root_path = fs.get_root_path(); + logger.info("Partition label: {}", partition_label); + logger.info("Mount point: {}", mount_point); + logger.info("Root path: {}", root_path.string()); + // human_readable returns a string with the size and unit, e.g. 1.2 MB + auto total_space = fs.human_readable(fs.get_total_space()); + auto free_space = fs.human_readable(fs.get_free_space()); + auto used_space = fs.human_readable(fs.get_used_space()); + logger.info("Total space: {}", total_space); + logger.info("Free space: {}", free_space); + logger.info("Used space: {}", used_space); + //! [file_system info example] + } const std::string_view test_dir = "sandbox"; const std::string_view test_file = "test.csv"; diff --git a/components/filters/example/main/filters_example.cpp b/components/filters/example/main/filters_example.cpp index 233524b4c..8f7477d56 100644 --- a/components/filters/example/main/filters_example.cpp +++ b/components/filters/example/main/filters_example.cpp @@ -16,9 +16,9 @@ using namespace std::chrono_literals; float get_random() { return ((float)esp_random() / (float)UINT32_MAX) * 2.0f - 1.0f; } extern "C" void app_main(void) { - size_t num_seconds_to_run = 10; - { + size_t num_seconds_to_run = 10; + fmt::print("Running both Lowpass and Butterworth Filter for {} seconds\n", num_seconds_to_run); //! [filter example] static constexpr float sample_freq_hz = 50.0f; diff --git a/components/filters/include/biquad_filter.hpp b/components/filters/include/biquad_filter.hpp index ff60230b0..1305cb560 100644 --- a/components/filters/include/biquad_filter.hpp +++ b/components/filters/include/biquad_filter.hpp @@ -30,11 +30,11 @@ class BiquadFilterDf1 { public: BiquadFilterDf1() {} - BiquadFilterDf1(const TransferFunction<3> &tf) + explicit BiquadFilterDf1(const TransferFunction<3> &tf) : BiquadFilterDf1(tf.b, std::array{{tf.a[1], tf.a[2]}}, tf.a[0]) {} - BiquadFilterDf1(const std::array &b, const std::array &a, const float &a0, - const float &gain = 1.0f) { + explicit BiquadFilterDf1(const std::array &b, const std::array &a, + const float &a0, const float &gain = 1.0f) { b_[0] = b[0] * gain / a0; b_[1] = b[1] * gain / a0; b_[2] = b[2] * gain / a0; @@ -95,11 +95,11 @@ class BiquadFilterDf2 { public: BiquadFilterDf2() {} - BiquadFilterDf2(const TransferFunction<3> &tf) + explicit BiquadFilterDf2(const TransferFunction<3> &tf) : BiquadFilterDf2(tf.b, std::array{{tf.a[1], tf.a[2]}}, tf.a[0]) {} - BiquadFilterDf2(const std::array &b, const std::array &a, const float &a0, - const float &gain = 1.0f) { + explicit BiquadFilterDf2(const std::array &b, const std::array &a, + const float &a0, const float &gain = 1.0f) { b_[0] = b[0] * gain / a0; b_[1] = b[1] * gain / a0; b_[2] = b[2] * gain / a0; @@ -122,7 +122,7 @@ class BiquadFilterDf2 { * @param length Number of samples, should be >= length of input & output memory. */ void update(const float *input, float *output, size_t length) { - dsps_biquad_f32(input, output, length, coeffs_, w_.data()); + dsps_biquad_f32(input, output, length, coeffs_.data(), w_.data()); } /** @@ -133,14 +133,14 @@ class BiquadFilterDf2 { */ float update(const float input) { float result; - dsps_biquad_f32(&input, &result, 1, coeffs_, w_.data()); + dsps_biquad_f32(&input, &result, 1, coeffs_.data(), w_.data()); return result; } friend struct fmt::formatter; protected: - float coeffs_[5]; + std::array coeffs_ = {{0}}; std::array b_ = {{0}}; std::array a_ = {{0}}; diff --git a/components/filters/include/butterworth_filter.hpp b/components/filters/include/butterworth_filter.hpp index ba4e9bc63..e0c98217f 100644 --- a/components/filters/include/butterworth_filter.hpp +++ b/components/filters/include/butterworth_filter.hpp @@ -31,7 +31,7 @@ class ButterworthFilter : public SosFilter<(ORDER + 1) / 2, Impl> { * @brief Construct the butterworth filter for the given config. * @param config The configuration struct for the Butterworth Filter */ - ButterworthFilter(const Config &config) + explicit ButterworthFilter(const Config &config) : SosFilter<(ORDER + 1) / 2, Impl>(make_filter_config(config.normalized_cutoff_frequency)) {} friend struct fmt::formatter>; diff --git a/components/filters/include/lowpass_filter.hpp b/components/filters/include/lowpass_filter.hpp index 40833c184..90e95672c 100644 --- a/components/filters/include/lowpass_filter.hpp +++ b/components/filters/include/lowpass_filter.hpp @@ -25,7 +25,7 @@ class LowpassFilter { * @brief Initialize the lowpass filter coefficients based on the config. * @param config Configuration struct. */ - LowpassFilter(const Config &config) { init(config); } + explicit LowpassFilter(const Config &config) { init(config); } /** * @brief Filter the input samples, updating internal state, and writing the diff --git a/components/filters/include/sos_filter.hpp b/components/filters/include/sos_filter.hpp index 72f52ab94..8d79a422d 100644 --- a/components/filters/include/sos_filter.hpp +++ b/components/filters/include/sos_filter.hpp @@ -18,7 +18,7 @@ template class SosFilter { * @brief Construct a second order sections filter. * @param config Array of TransferFunction<3> for configuring each of the biquad sections. */ - SosFilter(const std::array, N> &config) { + explicit SosFilter(const std::array, N> &config) { for (int i = 0; i < N; i++) { sections_[i] = SectionImpl(config[i]); } diff --git a/components/ftp/include/ftp_client.hpp b/components/ftp/include/ftp_client.hpp index 65db157e1..d14f05b3b 100644 --- a/components/ftp/include/ftp_client.hpp +++ b/components/ftp/include/ftp_client.hpp @@ -155,7 +155,7 @@ class FtpClient { /// \param arguments The arguments to the command. /// \param response The response from the FTP server. /// \return True if the command was sent successfully, false otherwise. - bool send_command(const std::string_view command, std::vector &arguments, + bool send_command(const std::string_view command, const std::vector &arguments, Response &response) { std::string command_string = command.data(); for (const auto &argument : arguments) { @@ -228,7 +228,6 @@ class FtpClient { // encountered int code = 0; std::string message; - std::vector lines; std::string line; std::istringstream stream(response.data()); bool multiline = false; diff --git a/components/ftp/include/ftp_client_session.hpp b/components/ftp/include/ftp_client_session.hpp index 32fe35d78..1b38c89b6 100644 --- a/components/ftp/include/ftp_client_session.hpp +++ b/components/ftp/include/ftp_client_session.hpp @@ -207,7 +207,7 @@ class FtpClientSession { while (true) { std::vector buffer(1024); std::size_t received = data_socket_->receive(buffer.data(), buffer.size()); - if (received <= 0) { + if (received == 0) { break; } data.insert(data.end(), buffer.begin(), buffer.begin() + received); @@ -300,7 +300,7 @@ class FtpClientSession { while (true) { std::vector buffer(1024); std::size_t received = data_socket_->receive(buffer.data(), buffer.size()); - if (received <= 0) { + if (received == 0) { break; } total_size += received; @@ -372,7 +372,7 @@ class FtpClientSession { while (true) { file.read(buffer.get(), buffer_size); std::size_t bytes_read = file.gcount(); - if (bytes_read <= 0) { + if (bytes_read == 0) { break; } std::string_view data(buffer.get(), bytes_read); diff --git a/components/gt911/include/gt911.hpp b/components/gt911/include/gt911.hpp index 21bfebeda..011ed4acd 100644 --- a/components/gt911/include/gt911.hpp +++ b/components/gt911/include/gt911.hpp @@ -63,7 +63,7 @@ class Gt911 { return false; } // convert the data pointer to a GTPoint* - GTPoint *point = (GTPoint *)&data[0]; + const GTPoint *point = (GTPoint *)&data[0]; x_ = point->x; y_ = point->y; logger_.debug("Touch at ({}, {})", x_, y_); @@ -242,7 +242,7 @@ class Gt911 { void write(Registers reg, uint8_t val, std::error_code &ec) { write(reg, &val, 1, ec); } - void write(Registers reg, uint8_t *data, size_t len, std::error_code &ec) { + void write(Registers reg, const uint8_t *data, size_t len, std::error_code &ec) { uint16_t reg_addr = (uint16_t)reg; size_t d_len = 2 + len; uint8_t d[d_len]; diff --git a/components/input_drivers/include/encoder_input.hpp b/components/input_drivers/include/encoder_input.hpp index eabb66402..0f70a91ad 100644 --- a/components/input_drivers/include/encoder_input.hpp +++ b/components/input_drivers/include/encoder_input.hpp @@ -32,9 +32,8 @@ class EncoderInput { * encoder. * @param config Configuration structure for the EncoderInput. */ - EncoderInput(const Config &config) - : read_(config.read) - logger_({.tag = "EncoderInput", .level = config.log_level}) { + explicit EncoderInput(const Config &config) + : read_(config.read), logger_({.tag = "EncoderInput", .level = config.log_level}) { init(); } @@ -92,7 +91,7 @@ class EncoderInput { } } - void button_read_impl(lv_indev_data_t *data) { + void button_read_impl(lv_indev_data_t *data) const { data->state = button_pressed_ ? LV_INDEV_STATE_PRESSED : LV_INDEV_STATE_RELEASED; } diff --git a/components/input_drivers/include/keypad_input.hpp b/components/input_drivers/include/keypad_input.hpp index e9f528dba..4f1a671c1 100644 --- a/components/input_drivers/include/keypad_input.hpp +++ b/components/input_drivers/include/keypad_input.hpp @@ -15,7 +15,9 @@ namespace espp { */ class KeypadInput { public: - typedef std::function read_fn; + typedef std::function + read_fn; /** * @brief Configuration structure, containing the read function for the @@ -32,9 +34,8 @@ class KeypadInput { * keypad. * @param config Configuration structure for the KeypadInput. */ - KeypadInput(const Config &config) - : read_(config.read), - logger_({.tag = "KeypadInput", .level = config.log_level}) { + explicit KeypadInput(const Config &config) + : read_(config.read), logger_({.tag = "KeypadInput", .level = config.log_level}) { init(); } @@ -67,7 +68,7 @@ class KeypadInput { return; } logger_.info("Reading keypad..."); - bool up,down,left,right,enter,escape; + bool up, down, left, right, enter, escape; read_(&up, &down, &left, &right, &enter, &escape); data->state = LV_INDEV_STATE_PRESSED; if (escape) { @@ -85,8 +86,8 @@ class KeypadInput { } else { data->state = LV_INDEV_STATE_RELEASED; } - logger_.debug("Keypad state: up: {}, down: {}, left: {}, right: {}, enter: {}, escape: {}", - up, down, left, right, enter, escape); + logger_.debug("Keypad state: up: {}, down: {}, left: {}, right: {}, enter: {}, escape: {}", up, + down, left, right, enter, escape); logger_.debug("Keypad data: state: {}, key: {}", (int)data->state, (int)data->key); } diff --git a/components/input_drivers/include/touchpad_input.hpp b/components/input_drivers/include/touchpad_input.hpp index 54efb3790..928eb84e0 100644 --- a/components/input_drivers/include/touchpad_input.hpp +++ b/components/input_drivers/include/touchpad_input.hpp @@ -47,7 +47,7 @@ class TouchpadInput { * touchpad. * @param config Configuration structure for the TouchpadInput. */ - TouchpadInput(const Config &config) + explicit TouchpadInput(const Config &config) : touchpad_read_(config.touchpad_read), swap_xy_(config.swap_xy), invert_x_(config.invert_x), invert_y_(config.invert_y), logger_({.tag = "TouchpadInput", .level = config.log_level}) { init(); @@ -113,13 +113,13 @@ class TouchpadInput { } static void home_button_read(lv_indev_drv_t *drv, lv_indev_data_t *data) { - TouchpadInput *tpi = (TouchpadInput *)drv->user_data; + const TouchpadInput *tpi = (const TouchpadInput *)drv->user_data; if (tpi) { tpi->home_button_read_impl(data); } } - void home_button_read_impl(lv_indev_data_t *data) { + void home_button_read_impl(lv_indev_data_t *data) const { data->state = home_button_pressed_ ? LV_INDEV_STATE_PRESSED : LV_INDEV_STATE_RELEASED; } diff --git a/components/joystick/include/joystick.hpp b/components/joystick/include/joystick.hpp index 43c213b9d..64235f128 100644 --- a/components/joystick/include/joystick.hpp +++ b/components/joystick/include/joystick.hpp @@ -60,7 +60,7 @@ class Joystick { * @brief Initalize the joystick using the provided configuration. * @param config Config structure with initialization information. */ - Joystick(const Config &config) + explicit Joystick(const Config &config) : x_mapper_(config.x_calibration), y_mapper_(config.y_calibration), deadzone_(config.deadzone), deadzone_radius_(config.deadzone_radius), get_values_(config.get_values), logger_({.tag = "Joystick", .level = config.log_level}) {} @@ -101,18 +101,18 @@ class Joystick { logger_.error("No function provided with which to get values!"); return; } - float x, y; + float _x, _y; logger_.info("Getting x,y values"); - bool success = get_values_(&x, &y); + bool success = get_values_(&_x, &_y); if (!success) { logger_.error("Could not get values!"); return; } - logger_.debug("Got x,y values: ({}, {})", x, y); - raw_.x(x); - raw_.y(y); - position_.x(x_mapper_.map(x)); - position_.y(y_mapper_.map(y)); + logger_.debug("Got x,y values: ({}, {})", _x, _y); + raw_.x(_x); + raw_.y(_y); + position_.x(x_mapper_.map(_x)); + position_.y(y_mapper_.map(_y)); // if we're configured to use a circular deadzone, then we apply a // circular deadzone on the vector. if (deadzone_ == Deadzone::CIRCULAR) { @@ -188,7 +188,7 @@ template <> struct fmt::formatter { return it; } - template auto format(espp::Joystick const &j, FormatContext &ctx) { + template auto format(espp::Joystick const &j, FormatContext &ctx) const { switch (presentation) { case 'v': return fmt::format_to(ctx.out(), "{}", j.position_); diff --git a/components/led/include/led.hpp b/components/led/include/led.hpp index 837108987..a4a1454b7 100644 --- a/components/led/include/led.hpp +++ b/components/led/include/led.hpp @@ -33,7 +33,7 @@ class Led { float duty{ 0}; /**< The starting duty cycle (%) [0, 100] that you want the LED channel to have. */ ledc_mode_t speed_mode{ - LEDC_LOW_SPEED_MODE}; /**< The LEDC speed mode you want for this LED channel. */ + LEDC_LOW_SPEED_MODE}; /**< The LEDC speed mode you want for this LED channel. */ bool output_invert{false}; /**< Whether to invert the GPIO output for this LED channel. */ }; @@ -58,7 +58,7 @@ class Led { * @brief Initialize the LEDC subsystem according to the configuration. * @param config The configuration structure for the LEDC subsystem. */ - Led(const Config &config) + explicit Led(const Config &config) : duty_resolution_(config.duty_resolution), max_raw_duty_((uint32_t)(std::pow(2, (int)duty_resolution_) - 1)), channels_(config.channels), logger_({.tag = "Led", .level = config.log_level}) { @@ -134,7 +134,7 @@ class Led { if (index == -1) { return false; } - auto sem = fade_semaphores_[index]; + auto &sem = fade_semaphores_[index]; return uxSemaphoreGetCount(sem) == 1; } @@ -149,7 +149,7 @@ class Led { if (index == -1) { return {}; } - const auto& conf = channels_[index]; + const auto &conf = channels_[index]; auto raw_duty = ledc_get_duty(conf.speed_mode, conf.channel); return (float)raw_duty / (float)max_raw_duty_ * 100.0f; } @@ -167,7 +167,7 @@ class Led { return; } auto conf = channels_[index]; - auto sem = fade_semaphores_[index]; + auto &sem = fade_semaphores_[index]; // ensure that it's not fading if it is xSemaphoreTake(sem, portMAX_DELAY); uint32_t actual_duty = std::clamp(duty_percent, 0.0f, 100.0f) * max_raw_duty_ / 100.0f; @@ -192,7 +192,7 @@ class Led { return; } auto conf = channels_[index]; - auto sem = fade_semaphores_[index]; + auto &sem = fade_semaphores_[index]; // ensure that it's not fading if it is xSemaphoreTake(sem, portMAX_DELAY); uint32_t actual_duty = std::clamp(duty_percent, 0.0f, 100.0f) * max_raw_duty_ / 100.0f; diff --git a/components/led_strip/include/led_strip.hpp b/components/led_strip/include/led_strip.hpp index be94d4f9f..b28dfdde9 100644 --- a/components/led_strip/include/led_strip.hpp +++ b/components/led_strip/include/led_strip.hpp @@ -74,7 +74,7 @@ class LedStrip { /// \brief Constructor /// \param config Configuration for the LedStrip class - LedStrip(const Config &config) + explicit LedStrip(const Config &config) : num_leds_(config.num_leds), send_brightness_(config.send_brightness), byte_order_(config.byte_order), write_(config.write), logger_({.tag = "LedStrip", .level = config.log_level}) { diff --git a/components/logger/include/logger.hpp b/components/logger/include/logger.hpp index 1fce74738..18481e647 100644 --- a/components/logger/include/logger.hpp +++ b/components/logger/include/logger.hpp @@ -49,7 +49,7 @@ class Logger { * * @param config configuration for the logger. */ - Logger(const Config &config) + explicit Logger(const Config &config) : tag_(config.tag), rate_limit_(config.rate_limit), level_(config.level) {} /** diff --git a/components/math/include/bezier.hpp b/components/math/include/bezier.hpp index dadd235c4..a87a43f33 100644 --- a/components/math/include/bezier.hpp +++ b/components/math/include/bezier.hpp @@ -34,14 +34,15 @@ template class Bezier { * @brief Construct an unweighted cubic bezier curve for evaluation. * @param config Unweighted Config structure containing the control points. */ - Bezier(const Config &config) : weighted_(false), control_points_(config.control_points) {} + explicit Bezier(const Config &config) + : weighted_(false), control_points_(config.control_points) {} /** * @brief Construct a rational / weighted cubic bezier curve for evaluation. * @param config Rational / weighted WeightedConfig structure containing the * control points and their weights. */ - Bezier(const WeightedConfig &config) + explicit Bezier(const WeightedConfig &config) : weighted_(true), control_points_(config.control_points), weights_(config.weights) {} /** @@ -82,8 +83,8 @@ template class Bezier { auto mt = 1.0f - t; auto mt2 = mt * mt; auto mt3 = mt2 * mt; - float f[] = {weights_[0] * mt3, weights_[1] * 3.0f * mt2 * t, weights_[2] * 3.0f * mt * t2, - weights_[3] * t3}; + const float f[] = {weights_[0] * mt3, weights_[1] * 3.0f * mt2 * t, + weights_[2] * 3.0f * mt * t2, weights_[3] * t3}; float basis = f[0] + f[1] + f[2] + f[3]; return (f[0] * control_points_[0] + f[1] * control_points_[1] + f[2] * control_points_[2] + f[3] * control_points_[3]) / @@ -92,6 +93,6 @@ template class Bezier { bool weighted_{false}; std::array control_points_; - std::array weights_; + std::array weights_ = {{1.0f, 1.0f, 1.0f, 1.0f}}; }; } // namespace espp diff --git a/components/math/include/gaussian.hpp b/components/math/include/gaussian.hpp index 1939a0732..04cfe7ddc 100644 --- a/components/math/include/gaussian.hpp +++ b/components/math/include/gaussian.hpp @@ -26,7 +26,8 @@ class Gaussian { * @brief Construct the gaussian object, configuring its parameters. * @param config Config structure for the gaussian. */ - Gaussian(const Config &config) : gamma_(config.gamma), alpha_(config.alpha), beta_(config.beta) {} + explicit Gaussian(const Config &config) + : gamma_(config.gamma), alpha_(config.alpha), beta_(config.beta) {} /** * @brief Get the currently configured gamma (shape). diff --git a/components/math/include/range_mapper.hpp b/components/math/include/range_mapper.hpp index 5ac3f83bd..d0209a08c 100644 --- a/components/math/include/range_mapper.hpp +++ b/components/math/include/range_mapper.hpp @@ -57,7 +57,7 @@ template class RangeMapper { * @brief Initialize the RangeMapper. * @param config Configuration describing the input distribution. */ - RangeMapper(const Config &config) { configure(config); } + explicit RangeMapper(const Config &config) { configure(config); } /** * @brief Update the input / output distribution with the new configuration. diff --git a/components/math/include/vector2d.hpp b/components/math/include/vector2d.hpp index d03a62b02..b7b32d0fe 100644 --- a/components/math/include/vector2d.hpp +++ b/components/math/include/vector2d.hpp @@ -17,7 +17,7 @@ template class Vector2d { * @param x The starting X value. * @param y The starting Y value. */ - Vector2d(T x = T(0), T y = T(0)) : x_(x), y_(y) {} + explicit Vector2d(T x = T(0), T y = T(0)) : x_(x), y_(y) {} /** * @brief Vector copy constructor. @@ -177,9 +177,9 @@ template class Vector2d { * @return Resultant scaled vector. */ Vector2d operator/(const Vector2d &v) const { - auto x = v.x_ != T(0) ? (x_ / v.x_) : x_; - auto y = v.y_ != T(0) ? (y_ / v.y_) : y_; - return Vector2d(x, y); + auto _x = v.x_ != T(0) ? (x_ / v.x_) : x_; + auto _y = v.y_ != T(0) ? (y_ / v.y_) : y_; + return Vector2d(_x, _y); } /** diff --git a/components/mcp23x17/include/mcp23x17.hpp b/components/mcp23x17/include/mcp23x17.hpp index d4f495dc1..e09e3af7f 100644 --- a/components/mcp23x17/include/mcp23x17.hpp +++ b/components/mcp23x17/include/mcp23x17.hpp @@ -64,8 +64,7 @@ class Mcp23x17 { * @brief Construct the Mcp23x17 and configure it. * @param config Config structure for configuring the MCP23X17 */ - Mcp23x17(const Config &config) - + explicit Mcp23x17(const Config &config) : address_(config.device_address), port_0_direction_mask_(config.port_0_direction_mask), port_0_interrupt_mask_(config.port_0_interrupt_mask), port_1_direction_mask_(config.port_1_direction_mask), diff --git a/components/monitor/include/task_monitor.hpp b/components/monitor/include/task_monitor.hpp index fdf14cdae..138285d65 100644 --- a/components/monitor/include/task_monitor.hpp +++ b/components/monitor/include/task_monitor.hpp @@ -42,7 +42,8 @@ class TaskMonitor { 8 * 1024}; /**< Stack size (B) allocated to the TaskMonitor::task_callback. */ }; - TaskMonitor(const Config &config) : period_(config.period), logger_({.tag = "TaskMonitor"}) { + explicit TaskMonitor(const Config &config) + : period_(config.period), logger_({.tag = "TaskMonitor"}) { #if CONFIG_FREERTOS_USE_TRACE_FACILITY && CONFIG_FREERTOS_GENERATE_RUN_TIME_STATS using namespace std::placeholders; task_ = Task::make_unique({.name = "TaskMonitor Task", diff --git a/components/mt6701/include/mt6701.hpp b/components/mt6701/include/mt6701.hpp index 75a026192..8762757de 100644 --- a/components/mt6701/include/mt6701.hpp +++ b/components/mt6701/include/mt6701.hpp @@ -91,7 +91,7 @@ class Mt6701 { /** * @brief Construct the Mt6701 and start the update task. */ - Mt6701(const Config &config) + explicit Mt6701(const Config &config) : address_(config.device_address), write_(config.write), read_(config.read), velocity_filter_(config.velocity_filter), update_period_(config.update_period), logger_({.tag = "Mt6701", .level = config.log_level}) { diff --git a/components/ndef/include/ndef.hpp b/components/ndef/include/ndef.hpp index 9232a93aa..94488911b 100644 --- a/components/ndef/include/ndef.hpp +++ b/components/ndef/include/ndef.hpp @@ -244,7 +244,7 @@ class Ndef { * @param type String view for the type of this packet * @param payload The payload data for the packet */ - Ndef(TNF tnf, std::string_view type, std::string_view payload) + explicit Ndef(TNF tnf, std::string_view type, std::string_view payload) : tnf_(tnf), type_(type), payload_(payload) {} /** @@ -304,19 +304,19 @@ class Ndef { */ static Ndef make_wifi_config(const WifiConfig &config) { // make the payload - std::vector payload; - add_wifi_field(payload, WifiFieldId::SSID, config.ssid); - add_wifi_field(payload, WifiFieldId::NETWORK_KEY, config.key); + std::vector _payload; + add_wifi_field(_payload, WifiFieldId::SSID, config.ssid); + add_wifi_field(_payload, WifiFieldId::NETWORK_KEY, config.key); uint8_t auth_bytes[] = { (uint8_t)(0x00), (uint8_t)(config.authentication), }; auto sv_auth = std::string_view{(const char *)auth_bytes, 2}; - add_wifi_field(payload, WifiFieldId::AUTH_TYPE, sv_auth); + add_wifi_field(_payload, WifiFieldId::AUTH_TYPE, sv_auth); // now encapsulate it into a wifi credential std::vector data; - auto sv_payload = std::string_view{(const char *)payload.data(), payload.size()}; + auto sv_payload = std::string_view{(const char *)_payload.data(), _payload.size()}; add_wifi_field(data, WifiFieldId::CREDENTIAL, sv_payload); // TODO: add fields for the credential @@ -333,11 +333,11 @@ class Ndef { * @return NDEF record object. */ static Ndef make_collision_resolution_record(uint16_t random_number) { - std::vector payload; - payload.push_back(random_number >> 8); - payload.push_back(random_number & 0xFF); + std::vector _payload; + _payload.push_back(random_number >> 8); + _payload.push_back(random_number & 0xFF); return Ndef(TNF::WELL_KNOWN, "cr", - std::string_view{(const char *)payload.data(), payload.size()}); + std::string_view{(const char *)_payload.data(), _payload.size()}); } /** @@ -350,16 +350,17 @@ class Ndef { * @return NDEF record object. */ static Ndef make_handover_select(int carrier_data_ref) { - std::vector payload; - payload.push_back(HANDOVER_VERSION); + std::vector _payload; + _payload.push_back(HANDOVER_VERSION); Ndef alternative_carrier = make_alternative_carrier(CarrierPowerState::ACTIVE, carrier_data_ref); auto alternative_carrier_data = alternative_carrier.serialize(true, true); - payload.insert(payload.end(), alternative_carrier_data.begin(), alternative_carrier_data.end()); + _payload.insert(_payload.end(), alternative_carrier_data.begin(), + alternative_carrier_data.end()); return Ndef(TNF::WELL_KNOWN, "Hs", - std::string_view{(const char *)payload.data(), payload.size()}); + std::string_view{(const char *)_payload.data(), _payload.size()}); } /** @@ -372,8 +373,8 @@ class Ndef { * @return NDEF record object. */ static Ndef make_handover_request(int carrier_data_ref) { - std::vector payload; - payload.push_back(HANDOVER_VERSION); + std::vector _payload; + _payload.push_back(HANDOVER_VERSION); // Handover request requires a collision resolution record, so we'll just // add collision resolution record which contains a random number. @@ -381,17 +382,18 @@ class Ndef { uint16_t random_number = esp_random() & 0xFFFF; Ndef collision_resolution_record = make_collision_resolution_record(random_number); auto collision_resolution_data = collision_resolution_record.serialize(true, false); - payload.insert(payload.end(), collision_resolution_data.begin(), - collision_resolution_data.end()); + _payload.insert(_payload.end(), collision_resolution_data.begin(), + collision_resolution_data.end()); // now make the alternative carrier record Ndef alternative_carrier = make_alternative_carrier(CarrierPowerState::ACTIVE, carrier_data_ref); auto alternative_carrier_data = alternative_carrier.serialize(true, true); - payload.insert(payload.end(), alternative_carrier_data.begin(), alternative_carrier_data.end()); + _payload.insert(_payload.end(), alternative_carrier_data.begin(), + alternative_carrier_data.end()); return Ndef(TNF::WELL_KNOWN, "Hr", - std::string_view{(const char *)payload.data(), payload.size()}); + std::string_view{(const char *)_payload.data(), _payload.size()}); } /** @@ -404,17 +406,17 @@ class Ndef { * @return NDEF record object. */ static Ndef make_alternative_carrier(const CarrierPowerState &power_state, int carrier_data_ref) { - std::vector payload; + std::vector _payload; // first byte is carrier power state - payload.push_back((uint8_t)power_state); + _payload.push_back((uint8_t)power_state); // second byte is carrier data reference length - payload.push_back(0x01); + _payload.push_back(0x01); // third byte is carrier data reference (ascii), e.g. '0' - payload.push_back((uint8_t)carrier_data_ref); + _payload.push_back((uint8_t)carrier_data_ref); // fourth byte is auxiliary data reference count - payload.push_back(0x00); // no auxiliary data + _payload.push_back(0x00); // no auxiliary data return Ndef(TNF::WELL_KNOWN, "ac", - std::string_view{(const char *)payload.data(), payload.size()}); + std::string_view{(const char *)_payload.data(), _payload.size()}); } /** @@ -676,7 +678,7 @@ class Ndef { } static int add_wifi_field(std::vector &data, WifiFieldId field, - std::string_view payload) { + std::string_view _payload) { // field ID = short // field size = short // payload @@ -689,22 +691,20 @@ class Ndef { data.push_back(field_bytes[0]); data.push_back(field_bytes[1]); // add 2 byte size - int size = payload.size(); + int size = _payload.size(); uint8_t size_bytes[] = { (uint8_t)(size >> 8 & 0xFF), (uint8_t)(size >> 0 & 0xFF), }; data.push_back(size_bytes[0]); data.push_back(size_bytes[1]); - // add payload - for (auto p : payload) { - data.push_back(p); - } + // add _payload + std::copy(_payload.begin(), _payload.end(), std::back_inserter(data)); // return how many bytes this field is - return 4 + payload.size(); + return 4 + _payload.size(); } - static int add_bt_eir(std::vector &data, BtEir eir_type, std::string_view payload) { + static int add_bt_eir(std::vector &data, BtEir eir_type, std::string_view _payload) { uint8_t num_eir_bytes = 0; switch (eir_type) { case BtEir::UUIDS_16_BIT_PARTIAL: @@ -713,26 +713,26 @@ class Ndef { case BtEir::UUIDS_32_BIT_COMPLETE: case BtEir::UUIDS_128_BIT_PARTIAL: case BtEir::UUIDS_128_BIT_COMPLETE: - num_eir_bytes = payload.size(); + num_eir_bytes = _payload.size(); break; case BtEir::FLAGS: num_eir_bytes = 1; break; case BtEir::SHORT_LOCAL_NAME: case BtEir::LONG_LOCAL_NAME: - num_eir_bytes = payload.size(); + num_eir_bytes = _payload.size(); break; case BtEir::CLASS_OF_DEVICE: num_eir_bytes = 3; // 24 bit class of device structure break; case BtEir::SECURITY_MANAGER_TK: - num_eir_bytes = payload.size(); + num_eir_bytes = _payload.size(); break; case BtEir::APPEARANCE: num_eir_bytes = 2; // 2 byte appearance type break; case BtEir::MAC: - num_eir_bytes = payload.size(); + num_eir_bytes = _payload.size(); break; case BtEir::LE_ROLE: num_eir_bytes = 1; @@ -740,12 +740,12 @@ class Ndef { case BtEir::SP_HASH_C192: case BtEir::LE_SC_CONFIRMATION: // NOTE: should be 16 - num_eir_bytes = payload.size(); + num_eir_bytes = _payload.size(); break; case BtEir::SP_RANDOM_R192: case BtEir::LE_SC_RANDOM: // NOTE: should be 16 - num_eir_bytes = payload.size(); + num_eir_bytes = _payload.size(); break; default: break; @@ -753,14 +753,14 @@ class Ndef { data.push_back(num_eir_bytes + 1); // total size of EIR (including eir data type) data.push_back((uint8_t)eir_type); for (int i = 0; i < num_eir_bytes; i++) { - data.push_back(payload[i]); + data.push_back(_payload[i]); } // return the total number of bytes written return 2 + num_eir_bytes; } TNF tnf_; - Flags flags_; + Flags flags_{0}; int id_{-1}; std::string type_{""}; std::string payload_{""}; diff --git a/components/pid/include/pid.hpp b/components/pid/include/pid.hpp index b42584df8..4fd49c685 100644 --- a/components/pid/include/pid.hpp +++ b/components/pid/include/pid.hpp @@ -41,7 +41,7 @@ class Pid { /** * @brief Create the PID controller. */ - Pid(const Config &config) + explicit Pid(const Config &config) : prev_ts_(std::chrono::high_resolution_clock::now()), logger_({.tag = "PID", .level = config.log_level}) { change_gains(config); diff --git a/components/qwiicnes/include/qwiicnes.hpp b/components/qwiicnes/include/qwiicnes.hpp index 3e55d2590..afef45267 100644 --- a/components/qwiicnes/include/qwiicnes.hpp +++ b/components/qwiicnes/include/qwiicnes.hpp @@ -194,7 +194,7 @@ class QwiicNes { write_fn write_; write_read_fn write_read_; uint8_t accumulated_states_{0}; - ButtonState button_state_; + ButtonState button_state_{0}; uint8_t address_{DEFAULT_ADDRESS}; espp::Logger logger_; }; diff --git a/components/rmt/include/rmt.hpp b/components/rmt/include/rmt.hpp index e2fb40b32..78c275935 100644 --- a/components/rmt/include/rmt.hpp +++ b/components/rmt/include/rmt.hpp @@ -39,7 +39,9 @@ class Rmt { /// \brief Constructor /// \param config Configuration for this class - Rmt(const Config &config) : logger_({.tag = "RMT", .level = config.log_level}) { init(config); } + explicit Rmt(const Config &config) : logger_({.tag = "RMT", .level = config.log_level}) { + init(config); + } /// \brief Destructor /// \details This function disables the RMT peripheral and frees the diff --git a/components/rmt/include/rmt_encoder.hpp b/components/rmt/include/rmt_encoder.hpp index 3e16697a5..cc164b78a 100644 --- a/components/rmt/include/rmt_encoder.hpp +++ b/components/rmt/include/rmt_encoder.hpp @@ -114,7 +114,7 @@ class RmtEncoder { /// \brief Constructor /// \param config Configuration for this class - RmtEncoder(const Config &config) { init(config); } + explicit RmtEncoder(const Config &config) { init(config); } /// \brief Destructor ~RmtEncoder() { diff --git a/components/rtsp/include/jpeg_header.hpp b/components/rtsp/include/jpeg_header.hpp index 2d4658bb3..4f0a97b6b 100644 --- a/components/rtsp/include/jpeg_header.hpp +++ b/components/rtsp/include/jpeg_header.hpp @@ -590,7 +590,7 @@ class JpegHeader { // add the SOS marker memcpy(data_.data() + offset, SOS, sizeof(SOS)); - offset += sizeof(SOS); + // offset += sizeof(SOS); } void parse() { diff --git a/components/rtsp/include/rtcp_packet.hpp b/components/rtsp/include/rtcp_packet.hpp index de35f1880..61c4e3aca 100644 --- a/components/rtsp/include/rtcp_packet.hpp +++ b/components/rtsp/include/rtcp_packet.hpp @@ -19,7 +19,7 @@ class RtcpPacket { void serialize() {} protected: - uint8_t *m_buffer; - uint32_t m_bufferSize; + uint8_t *m_buffer{nullptr}; + uint32_t m_bufferSize{0}; }; } // namespace espp diff --git a/components/rtsp/include/rtp_jpeg_packet.hpp b/components/rtsp/include/rtp_jpeg_packet.hpp index fbe0c2d76..c234ad353 100644 --- a/components/rtsp/include/rtp_jpeg_packet.hpp +++ b/components/rtsp/include/rtp_jpeg_packet.hpp @@ -87,7 +87,7 @@ class RtpJpegPacket : public RtpPacket { /// Get the mjepg header. /// @return The mjepg header. - std::string_view get_mjpeg_header() { + std::string_view get_mjpeg_header() const { return std::string_view((char *)get_payload().data(), MJPEG_HEADER_SIZE); } @@ -97,7 +97,7 @@ class RtpJpegPacket : public RtpPacket { /// @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; } + bool has_q_tables() const { return q_ >= 128; } /// Get the number of quantization tables. /// @note The quantization tables are optional. If they are present, the @@ -198,7 +198,7 @@ class RtpJpegPacket : public RtpPacket { memcpy(packet.data() + offset, q1.data(), Q_TABLE_SIZE); q_tables_[1] = std::string_view((char *)packet.data() + offset, Q_TABLE_SIZE); - offset += Q_TABLE_SIZE; + // offset += Q_TABLE_SIZE; } uint8_t type_specific_{0}; diff --git a/components/rtsp/include/rtsp_client.hpp b/components/rtsp/include/rtsp_client.hpp index 1daf059a1..2d8fb5c6d 100644 --- a/components/rtsp/include/rtsp_client.hpp +++ b/components/rtsp/include/rtsp_client.hpp @@ -245,8 +245,8 @@ class RtspClient { 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); + // send the setup request (no response is expected) + send_request("SETUP", path_, {{"Transport", transport_header}}, ec); if (ec) { return; } @@ -315,7 +315,7 @@ class RtspClient { // 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) { + if (response_data.starts_with("RTSP/1.0") != 0) { ec = std::make_error_code(std::errc::protocol_error); logger_.error("Invalid response"); return false; @@ -460,7 +460,7 @@ class RtspClient { 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()); + [[maybe_unused]] 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 {}; diff --git a/components/rtsp/include/rtsp_server.hpp b/components/rtsp/include/rtsp_server.hpp index cc5f0a52e..15d40eec5 100644 --- a/components/rtsp/include/rtsp_server.hpp +++ b/components/rtsp/include/rtsp_server.hpp @@ -191,8 +191,8 @@ class RtspServer { // set the ssrc packet->set_ssrc(ssrc_); - auto mjpeg_header = packet->get_mjpeg_header(); - std::vector mjpeg_vec(mjpeg_header.begin(), mjpeg_header.end()); + // 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) { diff --git a/components/socket/example/main/socket_example.cpp b/components/socket/example/main/socket_example.cpp index e2956ec99..49efa5d56 100644 --- a/components/socket/example/main/socket_example.cpp +++ b/components/socket/example/main/socket_example.cpp @@ -69,9 +69,8 @@ espp::UdpSocket client_socket({}); auto client_task_fn = [&server_address, &client_socket, &port](auto &, auto &) { static size_t iterations = 0; std::vector data{0, 1, 2, 3, 4}; - for (auto &d : data) { - d += iterations; - } + std::transform(data.begin(), data.end(), data.begin(), + [](const auto &d) { return d + iterations; }); auto send_config = espp::UdpSocket::SendConfig{.ip_address = server_address, .port = port}; client_socket.send(data, send_config); iterations++; @@ -123,9 +122,8 @@ espp::UdpSocket client_socket({.log_level = espp::Logger::Verbosity::WARN}); auto client_task_fn = [&server_address, &client_socket, &port](auto &, auto &) { static size_t iterations = 0; std::vector data{0, 1, 2, 3, 4}; - for (auto &d : data) { - d += iterations; - } + std::transform(data.begin(), data.end(), data.begin(), + [](const auto &d) { return d + iterations; }); auto send_config = espp::UdpSocket::SendConfig{ .ip_address = server_address, .port = port, @@ -189,9 +187,8 @@ espp::UdpSocket client_socket({}); auto client_task_fn = [&client_socket, &port, &multicast_group](auto &, auto &) { static size_t iterations = 0; std::vector data{0, 1, 2, 3, 4}; - for (auto &d : data) { - d += iterations; - } + std::transform(data.begin(), data.end(), data.begin(), + [](const auto &d) { return d + iterations; }); auto send_config = espp::UdpSocket::SendConfig{.ip_address = multicast_group, .port = port, .is_multicast_endpoint = true, @@ -268,9 +265,8 @@ fmt::print(fg(fmt::terminal_color::yellow) | fmt::emphasis::bold, "Staring Basic auto client_task_fn = [&server_address, &client_socket, &port](auto &, auto &) { static size_t iterations = 0; std::vector data{0, 1, 2, 3, 4}; - for (auto &d : data) { - d += iterations; - } + std::transform(data.begin(), data.end(), data.begin(), + [](const auto &d) { return d + iterations; }); client_socket.transmit(data); iterations++; std::this_thread::sleep_for(1s); @@ -346,9 +342,8 @@ fmt::print(fg(fmt::terminal_color::yellow) | fmt::emphasis::bold, auto client_task_fn = [&server_address, &client_socket, &port](auto &, auto &) { static size_t iterations = 0; std::vector data{0, 1, 2, 3, 4}; - for (auto &d : data) { - d += iterations; - } + std::transform(data.begin(), data.end(), data.begin(), + [](const auto &d) { return d + iterations; }); auto transmit_config = espp::detail::TcpTransmitConfig{ .wait_for_response = true, .response_size = 128, diff --git a/components/socket/include/socket.hpp b/components/socket/include/socket.hpp index c3dad5f8a..bfde73e1f 100644 --- a/components/socket/include/socket.hpp +++ b/components/socket/include/socket.hpp @@ -246,7 +246,7 @@ class Socket { #if !CONFIG_LWIP_SO_REUSE && defined(ESP_PLATFORM) fmt::print(fg(fmt::color::red), "CONFIG_LWIP_SO_REUSE not defined!\n"); return false; -#endif +#else // CONFIG_LWIP_SO_REUSE || !defined(ESP_PLATFORM) int err = 0; int enabled = 1; err = setsockopt(socket_, SOL_SOCKET, SO_REUSEADDR, &enabled, sizeof(enabled)); @@ -260,8 +260,9 @@ class Socket { fmt::print(fg(fmt::color::red), "Couldn't set SO_REUSEPORT\n"); return false; } -#endif +#endif // !defined(ESP_PLATFORM) return true; +#endif // !CONFIG_LWIP_SO_REUSE && defined(ESP_PLATFORM) } /** @@ -391,6 +392,7 @@ class Socket { logger_.error("Cannot create socket: {} - '{}'", errno, strerror(errno)); return false; } + // cppcheck-suppress knownConditionTrueFalse if (!enable_reuse()) { logger_.error("Cannot enable reuse: {} - '{}'", errno, strerror(errno)); return false; diff --git a/components/socket/include/tcp_socket.hpp b/components/socket/include/tcp_socket.hpp index 8b70d93bb..5390d0f3c 100644 --- a/components/socket/include/tcp_socket.hpp +++ b/components/socket/include/tcp_socket.hpp @@ -69,7 +69,7 @@ class TcpSocket : public Socket { * @note Enables keepalive on the socket. * @param config Config for the socket. */ - TcpSocket(const Config &config) + explicit TcpSocket(const Config &config) : Socket(Type::STREAM, Logger::Config{.tag = "TcpSocket", .level = config.log_level}) { set_keepalive(); } @@ -244,7 +244,8 @@ class TcpSocket : public Socket { int num_bytes_received = receive(receive_buffer.get(), max_num_bytes); if (num_bytes_received > 0) { logger_.info("Received {} bytes", num_bytes_received); - data.assign(receive_buffer.get(), receive_buffer.get() + num_bytes_received); + uint8_t *data_ptr = (uint8_t *)receive_buffer.get(); + data.assign(data_ptr, data_ptr + num_bytes_received); return true; } return false; @@ -274,8 +275,9 @@ class TcpSocket : public Socket { int num_bytes_received = ::recv(socket_, data, max_num_bytes, 0); // if we didn't receive anything return false and don't do anything else if (num_bytes_received < 0) { - // if we got an error, log it and return false + // if we got an error, log it and return 0 logger_.debug("Receive failed: {} - '{}'", errno, strerror(errno)); + return 0; } else if (num_bytes_received == 0) { logger_.warn("Remote socket closed!"); // update our connection state here since remote end was closed... @@ -370,7 +372,7 @@ class TcpSocket : public Socket { * @param socket_fd The socket file descriptor for the connection. * @param remote_info The remote endpoint info. */ - TcpSocket(int socket_fd, const Socket::Info &remote_info) + explicit TcpSocket(int socket_fd, const Socket::Info &remote_info) : Socket(socket_fd, Logger::Config{.tag = "TcpSocket", .level = Logger::Verbosity::WARN}), remote_info_(remote_info) { connected_ = true; @@ -390,18 +392,19 @@ class TcpSocket : public Socket { logger_.error("Unable to set keepalive: {} - '{}'", errno, strerror(errno)); return false; } - // set the idle time - optval = idle_time.count(); #if defined(__APPLE__) -// TODO: figure out how to set keepidle on macos + // TODO: figure out how to set keepidle on macos #else + // set the idle time + optval = idle_time.count(); err = setsockopt(socket_, IPPROTO_TCP, TCP_KEEPIDLE, &optval, sizeof(optval)); -#endif if (err < 0) { logger_.error("Unable to set keepalive idle time: {} - '{}'", errno, strerror(errno)); return false; } +#endif + // set the interval optval = interval.count(); err = setsockopt(socket_, IPPROTO_TCP, TCP_KEEPINTVL, &optval, sizeof(optval)); @@ -420,6 +423,6 @@ class TcpSocket : public Socket { } bool connected_{false}; - Socket::Info remote_info_; + Socket::Info remote_info_{}; }; } // namespace espp diff --git a/components/socket/include/udp_socket.hpp b/components/socket/include/udp_socket.hpp index 9638b6335..83a25cf42 100644 --- a/components/socket/include/udp_socket.hpp +++ b/components/socket/include/udp_socket.hpp @@ -71,7 +71,7 @@ class UdpSocket : public Socket { * @brief Initialize the socket and associated resources. * @param config Config for the socket. */ - UdpSocket(const Config &config) + explicit UdpSocket(const Config &config) : Socket(Type::DGRAM, Logger::Config{.tag = "UdpSocket", .level = config.log_level}) {} /** @@ -205,7 +205,8 @@ class UdpSocket : public Socket { return false; } // we received data, so call the callback function if one was provided. - data.assign(receive_buffer.get(), receive_buffer.get() + num_bytes_received); + uint8_t *data_ptr = (uint8_t *)receive_buffer.get(); + data.assign(data_ptr, data_ptr + num_bytes_received); remote_info.update(); logger_.debug("Received {} bytes from {}", num_bytes_received, remote_info); return true; diff --git a/components/st25dv/include/st25dv.hpp b/components/st25dv/include/st25dv.hpp index 88372f5f2..918bcadf2 100644 --- a/components/st25dv/include/st25dv.hpp +++ b/components/st25dv/include/st25dv.hpp @@ -88,7 +88,7 @@ class St25dv { /** * @brief Construct the St25dv and start the update task. */ - St25dv(const Config &config) + explicit St25dv(const Config &config) : write_(config.write), read_(config.read), logger_({.tag = "St25dv", .level = config.log_level}) { if (config.auto_init) { @@ -330,7 +330,9 @@ class St25dv { * @param length Number of bytes to write. * @param &ec Error code to be filled with any errors that occur during */ - void transfer(uint8_t *data, uint8_t length, std::error_code &ec) { write_ftm(data, length, ec); } + void transfer(const uint8_t *data, uint8_t length, std::error_code &ec) { + write_ftm(data, length, ec); + } /** * @brief Read data from the FTM message box. @@ -370,7 +372,7 @@ class St25dv { logger_.info("Memory size (B): {}", memory_size_bytes_); } - void write_ftm(uint8_t *data, uint8_t length, std::error_code &ec) { + void write_ftm(const uint8_t *data, uint8_t length, std::error_code &ec) { // must start from FTM_START_ADDR uint8_t all_data[2 + length]; all_data[0] = (uint8_t)(FTM_START_ADDR >> 8); @@ -430,13 +432,13 @@ class St25dv { } uint64_t read_password(std::error_code &ec) { - uint8_t pswd[8]; - bool success = read_(SYST_ADDRESS, (uint16_t)Registers::I2C_PWD, pswd, sizeof(pswd)); + uint8_t pswds[8]; + bool success = read_(SYST_ADDRESS, (uint16_t)Registers::I2C_PWD, pswds, sizeof(pswds)); if (!success) { ec = std::make_error_code(std::errc::io_error); return 0; } - memcpy(&password_, pswd, sizeof(pswd)); + memcpy(&password_, pswds, sizeof(pswds)); logger_.debug("Got pswd: 0x{:016X}", password_); return password_; } @@ -446,7 +448,7 @@ class St25dv { uint8_t data[2 + 17] = {0}; data[0] = (uint16_t)Registers::I2C_PWD >> 8; data[1] = (uint16_t)Registers::I2C_PWD & 0xFF; - uint8_t *pswd_data = (uint8_t *)&password_; + const uint8_t *pswd_data = (uint8_t *)&password_; // validation code in the middle data[8 + 2] = 0x09; for (int i = 0; i < 4; i++) { @@ -518,7 +520,7 @@ class St25dv { * @return Number of bytes of raw that should be written to represent the * TLV. */ - int size() { return length < 255 ? 2 : 4; } + int size() const { return length < 255 ? 2 : 4; } /** * @brief Append the TLV into a vector of bytes. @@ -540,7 +542,7 @@ class St25dv { * @param data The vector to serialize the TLV into. * @param offset The offset into the vector to start writing at. */ - void serialize(std::vector &data, int offset) { + void serialize(std::vector &data, int offset) const { data[offset] = (uint8_t)type; if (length < 255) { data[offset + 1] = length; diff --git a/components/state_machine/example/main/Complex_generated_states.cpp b/components/state_machine/example/main/Complex_generated_states.cpp index 7e8f40c2e..48b26ea96 100644 --- a/components/state_machine/example/main/Complex_generated_states.cpp +++ b/components/state_machine/example/main/Complex_generated_states.cpp @@ -52,7 +52,7 @@ void Root::restart(void) { bool Root::has_stopped(void) { bool reachedEnd = false; // Get the currently active leaf state - StateBase *activeLeaf = getActiveLeaf(); + const StateBase *activeLeaf = getActiveLeaf(); if (activeLeaf != nullptr && activeLeaf != this && activeLeaf == static_cast(&_root->COMPLEX_OBJ__END_STATE_OBJ)) { reachedEnd = true; @@ -89,7 +89,7 @@ void Root::State_1::entry(void) { _root->log("\033[36mENTRY::State_1::/c/Y\033[0m"); // Entry action for this state //::::/c/Y::::Entry:::: - int a = 2; + [[maybe_unused]] int a = 2; printf("SerialTask :: initializing State 1\n"); } diff --git a/components/state_machine/example/main/hfsm_example.cpp b/components/state_machine/example/main/hfsm_example.cpp index 7e5197fec..a70d0165a 100644 --- a/components/state_machine/example/main/hfsm_example.cpp +++ b/components/state_machine/example/main/hfsm_example.cpp @@ -25,7 +25,7 @@ extern "C" void app_main(void) { { fmt::print("Starting hfsm example!\n"); //! [hfsm example] - espp::state_machine::Complex::GeneratedEventBase *e = nullptr; + const espp::state_machine::Complex::GeneratedEventBase *e = nullptr; bool handled = false; // create the HFSM @@ -87,7 +87,7 @@ extern "C" void app_main(void) { // get_user_selection() function. espp::Cli::configure_stdin_stdout(); - espp::state_machine::Complex::GeneratedEventBase *e = nullptr; + const espp::state_machine::Complex::GeneratedEventBase *e = nullptr; // create the HFSM espp::state_machine::Complex::Root complex_root; diff --git a/components/state_machine/include/deep_history_state.hpp b/components/state_machine/include/deep_history_state.hpp index 892a2a6b8..c766f4cf0 100644 --- a/components/state_machine/include/deep_history_state.hpp +++ b/components/state_machine/include/deep_history_state.hpp @@ -12,12 +12,12 @@ namespace espp::state_machine { class DeepHistoryState : public StateBase { public: DeepHistoryState() : StateBase() {} - DeepHistoryState(StateBase *_parent) : StateBase(_parent) {} + explicit DeepHistoryState(StateBase *_parent) : StateBase(_parent) {} /** * @brief Calls _parentState->setDeepHistory() */ - void makeActive() { + virtual void makeActive() override { if (_parentState) { _parentState->setDeepHistory(); } diff --git a/components/state_machine/include/magic_enum.hpp b/components/state_machine/include/magic_enum.hpp index 3feb38929..46496dce4 100644 --- a/components/state_machine/include/magic_enum.hpp +++ b/components/state_machine/include/magic_enum.hpp @@ -46,10 +46,6 @@ #include #include -#if defined(MAGIC_ENUM_CONFIG_FILE) -#include MAGIC_ENUM_CONFIG_FILE -#endif - #if !defined(MAGIC_ENUM_USING_ALIAS_OPTIONAL) #include #endif @@ -256,7 +252,7 @@ constexpr string_view pretty_name(string_view name) noexcept { } class case_insensitive { - static constexpr char to_lower(char c) noexcept { + [[maybe_unused]] static constexpr char to_lower(char c) noexcept { return (c >= 'A' && c <= 'Z') ? static_cast(c + ('a' - 'A')) : c; } @@ -513,14 +509,14 @@ constexpr auto values(std::index_sequence) noexcept { constexpr std::size_t count = values_count(valid); if constexpr (count > 0) { - E values[count] = {}; + E _values[count] = {}; for (std::size_t i = 0, v = 0; v < count; ++i) { if (valid[i]) { - values[v++] = value(i); + _values[v++] = value(i); } } - return to_array(values, std::make_index_sequence{}); + return to_array(_values, std::make_index_sequence{}); } else { return std::array{}; } @@ -544,6 +540,7 @@ constexpr bool is_flags_enum() noexcept { if constexpr (has_is_flags::value) { return customize::enum_range::is_flags; + // cppcheck-suppress duplicateBranch } else if constexpr (std::is_same_v) { // bool special case return false; } else { @@ -729,6 +726,7 @@ struct constexpr_hash_t(0xffffffffL); + // cppcheck-suppress useStlAlgorithm for (const auto c : value) { crc = (crc >> 8) ^ crc_table[(crc ^ static_cast(c)) & 0xff]; } @@ -738,6 +736,7 @@ struct constexpr_hash_t(2166136261ULL); + // cppcheck-suppress useStlAlgorithm for (const auto c : value) { acc = ((acc ^ static_cast(c)) * static_cast(16777619ULL)) & (std::numeric_limits::max)(); } @@ -751,16 +750,16 @@ constexpr static Hash hash_v{}; template constexpr auto calculate_cases(std::size_t Page) noexcept { - constexpr std::array values = *GlobValues; - constexpr std::size_t size = values.size(); + constexpr std::array _values = *GlobValues; + constexpr std::size_t size = _values.size(); - using switch_t = std::invoke_result_t; + using switch_t = std::invoke_result_t; static_assert(std::is_integral_v && !std::is_same_v); const std::size_t values_to = (std::min)(static_cast(256), size - Page); std::array result{}; auto fill = result.begin(); - for (auto first = values.begin() + Page, last = values.begin() + Page + values_to; first != last; ) { + for (auto first = _values.begin() + Page, last = _values.begin() + Page + values_to; first != last; ) { *fill++ = hash_v(*first++); } @@ -864,8 +863,8 @@ constexpr std::invoke_result_t constexpr_switch( BinaryPredicate&& pred = {}) { using result_t = std::invoke_result_t; using hash_t = std::conditional_t(), Hash, typename Hash::secondary_hash>; - constexpr std::array values = *GlobValues; - constexpr std::size_t size = values.size(); + constexpr std::array _values = *GlobValues; + constexpr std::size_t size = _values.size(); constexpr std::array cases = calculate_cases(Page); switch (hash_v(searched)) { diff --git a/components/state_machine/include/shallow_history_state.hpp b/components/state_machine/include/shallow_history_state.hpp index 48f480640..f40145ac2 100644 --- a/components/state_machine/include/shallow_history_state.hpp +++ b/components/state_machine/include/shallow_history_state.hpp @@ -12,12 +12,12 @@ namespace espp::state_machine { class ShallowHistoryState : public StateBase { public: ShallowHistoryState() : StateBase() {} - ShallowHistoryState(StateBase *_parent) : StateBase(_parent) {} + explicit ShallowHistoryState(StateBase *_parent) : StateBase(_parent) {} /** * @brief Calls _parentState->setShallowHistory(). */ - void makeActive() { + virtual void makeActive() override { if (_parentState) { _parentState->setShallowHistory(); } diff --git a/components/state_machine/include/state_base.hpp b/components/state_machine/include/state_base.hpp index d111f278b..1d81b9469 100644 --- a/components/state_machine/include/state_base.hpp +++ b/components/state_machine/include/state_base.hpp @@ -27,8 +27,8 @@ class EventBase { class StateBase { public: StateBase() : _activeState(this), _parentState(nullptr) {} - StateBase(StateBase *parent) : _activeState(this), _parentState(parent) {} - ~StateBase(void) {} + explicit StateBase(StateBase *parent) : _activeState(this), _parentState(parent) {} + virtual ~StateBase(void) {} /** * @brief Will be generated to call entry() then handle any child @@ -118,7 +118,7 @@ class StateBase { * * *Should only be called on leaf nodes!* */ - void makeActive(void) { + virtual void makeActive(void) { if (_parentState != nullptr) { _parentState->setActiveChild(this); _parentState->makeActive(); diff --git a/components/t_keyboard/include/t_keyboard.hpp b/components/t_keyboard/include/t_keyboard.hpp index f4a475373..126154be0 100644 --- a/components/t_keyboard/include/t_keyboard.hpp +++ b/components/t_keyboard/include/t_keyboard.hpp @@ -89,7 +89,7 @@ class TKeyboard { /// \details This function returns the currently pressed key. /// \return The currently pressed key. /// \note This function will return 0 if no key has been pressed. - uint8_t get_key() { return pressed_key_; } + uint8_t get_key() const { return pressed_key_; } /// \brief Read a key from the keyboard. /// \details This function reads a key from the keyboard. @@ -125,7 +125,7 @@ class TKeyboard { protected: bool key_task(std::mutex &m, std::condition_variable &cv) { std::error_code ec; - auto start = std::chrono::steady_clock::now(); + auto start_time = std::chrono::steady_clock::now(); auto key = read_char(ec); if (!ec) { pressed_key_ = key; @@ -138,7 +138,7 @@ class TKeyboard { } { std::unique_lock lock(m); - cv.wait_until(lock, start + polling_interval_); + cv.wait_until(lock, start_time + polling_interval_); } return false; } diff --git a/components/task/example/main/task_example.cpp b/components/task/example/main/task_example.cpp index 4841a5eac..cdc799ab4 100644 --- a/components/task/example/main/task_example.cpp +++ b/components/task/example/main/task_example.cpp @@ -36,9 +36,6 @@ extern "C" void app_main(void) { * Set up some variables we'll re-use to control and measure our tests. */ size_t num_seconds_to_run = 2; - auto test_start = std::chrono::high_resolution_clock::now(); - auto test_end = std::chrono::high_resolution_clock::now(); - auto test_duration = std::chrono::duration(test_end - test_start).count(); /** * Show a simple task running for a short period and then stopping. Enable @@ -47,7 +44,7 @@ extern "C" void app_main(void) { * which is called at the end of this scope block when the pointer leaves * scope. */ - test_start = std::chrono::high_resolution_clock::now(); + auto test_start = std::chrono::high_resolution_clock::now(); { fmt::print("Spawning 1 task for {} seconds!\n", num_seconds_to_run); //! [Task example] @@ -73,8 +70,8 @@ extern "C" void app_main(void) { task.stop(); //! [Task example] } - test_end = std::chrono::high_resolution_clock::now(); - test_duration = std::chrono::duration(test_end - test_start).count(); + auto test_end = std::chrono::high_resolution_clock::now(); + auto test_duration = std::chrono::duration(test_end - test_start).count(); fmt::print("Test ran for {:.03f} seconds\n", test_duration); /** diff --git a/components/task/include/task.hpp b/components/task/include/task.hpp index efda288dd..785b0ccc4 100644 --- a/components/task/include/task.hpp +++ b/components/task/include/task.hpp @@ -229,14 +229,14 @@ class Task { * * @return true if the task is started / running, false otherwise. */ - bool is_started() { return started_; } + bool is_started() const { return started_; } /** * @brief Is the task running? * * @return true if the task is running, false otherwise. */ - bool is_running() { return is_started(); } + bool is_running() const { return is_started(); } #if defined(ESP_PLATFORM) /** diff --git a/components/timer/include/timer.hpp b/components/timer/include/timer.hpp index 19da55950..31c9b0ef3 100644 --- a/components/timer/include/timer.hpp +++ b/components/timer/include/timer.hpp @@ -160,10 +160,10 @@ class Timer { // initial delay, if any - this is only used the first time the timer // runs if (delay_float > 0) { - auto start = std::chrono::steady_clock::now(); + auto start_time = std::chrono::steady_clock::now(); logger_.debug("waiting for delay {:.3f} s", delay_float); std::unique_lock lock(m); - cv.wait_until(lock, start + delay_); + cv.wait_until(lock, start_time + delay_); if (!running_) { logger_.debug("delay canceled, stopping"); return true; @@ -173,7 +173,7 @@ class Timer { delay_float = 0; } // now run the callback - auto start = std::chrono::steady_clock::now(); + auto start_time = std::chrono::steady_clock::now(); logger_.debug("running callback"); bool requested_stop = callback_(); if (requested_stop || period_float <= 0) { @@ -183,7 +183,7 @@ class Timer { return true; } auto end = std::chrono::steady_clock::now(); - float elapsed = std::chrono::duration(end - start).count(); + float elapsed = std::chrono::duration(end - start_time).count(); if (elapsed > period_float) { // if the callback took longer than the period, then we should just // return and run the callback again immediately @@ -195,7 +195,7 @@ class Timer { // the callback) { std::unique_lock lock(m); - cv.wait_until(lock, start + period_); + cv.wait_until(lock, start_time + period_); // Note: we don't care about cv_retval here because we are going to // return from the function anyway. If the timer was canceled, then // the task will be stopped and the callback will not be called again. diff --git a/components/tla2528/include/tla2528.hpp b/components/tla2528/include/tla2528.hpp index 93f080009..d9450d78b 100644 --- a/components/tla2528/include/tla2528.hpp +++ b/components/tla2528/include/tla2528.hpp @@ -4,6 +4,7 @@ #include #include #include +#include #include #include @@ -155,7 +156,7 @@ class Tla2528 { * @brief Construct Tla2528 * @param config Configuration structure. */ - Tla2528(const Config &config) + explicit Tla2528(const Config &config) : config_(config), mode_(config.mode), avdd_mv_(config.avdd_volts * 1000.0f) // Convert to mV , data_format_(config.oversampling_ratio == OversamplingRatio::NONE ? DataFormat::RAW @@ -586,16 +587,16 @@ class Tla2528 { write_one_(Register::OSR_CFG, data, ec); } + static uint8_t bit_pred(uint8_t value, Channel channel) { + return value | (1 << static_cast(channel)); + }; + void set_pin_configuration(std::error_code &ec) { logger_.info("Setting digital mode for outputs {} and inputs {}", digital_outputs_, digital_inputs_); uint8_t data = 0; - for (auto channel : digital_inputs_) { - data |= 1 << static_cast(channel); - } - for (auto channel : digital_outputs_) { - data |= 1 << static_cast(channel); - } + std::accumulate(digital_inputs_.begin(), digital_inputs_.end(), data, bit_pred); + std::accumulate(digital_outputs_.begin(), digital_outputs_.end(), data, bit_pred); // don't have to do anything for analog inputs since they are the default // state (0) write_one_(Register::PIN_CFG, data, ec); @@ -605,9 +606,7 @@ class Tla2528 { logger_.info("Setting digital output for pins {}", digital_outputs_); // default direction is input (0) uint8_t data = 0; - for (auto channel : digital_outputs_) { - data |= 1 << static_cast(channel); - } + std::accumulate(digital_outputs_.begin(), digital_outputs_.end(), data, bit_pred); write_one_(Register::GPIO_CFG, data, ec); } @@ -617,9 +616,7 @@ class Tla2528 { logger_.info("Setting analog inputs for autonomous mode"); // configure the analog inputs for autonomous conversion sequence uint8_t data = 0; - for (auto channel : analog_inputs_) { - data |= 1 << static_cast(channel); - } + std::accumulate(analog_inputs_.begin(), analog_inputs_.end(), data, bit_pred); write_one_(Register::AUTO_SEQ_CH_SEL, data, ec); } } @@ -708,7 +705,7 @@ class Tla2528 { return values; } - uint16_t parse_frame(uint8_t *frame_ptr) { + uint16_t parse_frame(const uint8_t *frame_ptr) { uint8_t msb = frame_ptr[0]; uint8_t lsb = frame_ptr[1]; uint8_t channel_id = (append_ == Append::CHANNEL_ID) ? (lsb & 0x0F) : 0; @@ -758,7 +755,7 @@ class Tla2528 { * @param raw Raw ADC value. * @return Voltage in mV. */ - float raw_to_mv(uint16_t raw) { + float raw_to_mv(uint16_t raw) const { if (data_format_ == DataFormat::AVERAGED) { // we have a 16-bit ADC, so we can represent 2^16 = 65536 values // we were configured with avdd_mv_ as the reference voltage, so we @@ -781,7 +778,7 @@ class Tla2528 { * @param mv Voltage in mV. * @return Raw ADC value. */ - uint16_t mv_to_raw(float mv) { + uint16_t mv_to_raw(float mv) const { // we have a 16-bit ADC, so we can represent 2^16 = 65536 values // we were configured with avdd_mv_ as the reference voltage, so we // can represent avdd_mv_ volts with 65536 values @@ -935,7 +932,7 @@ class Tla2528 { write_many_(reg, (uint8_t *)&value, 2, ec); } - void write_many_(Register reg, uint8_t *data, uint8_t len, std::error_code &ec) { + void write_many_(Register reg, const uint8_t *data, uint8_t len, std::error_code &ec) { std::lock_guard lock(mutex_); uint8_t total_len = len + 2; uint8_t data_with_header[total_len]; diff --git a/components/tt21100/include/tt21100.hpp b/components/tt21100/include/tt21100.hpp index 6dbcede1f..1c822ffe0 100644 --- a/components/tt21100/include/tt21100.hpp +++ b/components/tt21100/include/tt21100.hpp @@ -75,8 +75,8 @@ class Tt21100 { case 17: case 27: { // touch event - NOTE: this only gets the first touch record - auto report_data = (TouchReport *)data; - auto touch_data = (TouchRecord *)(&report_data->touch_record[0]); + const auto report_data = (const TouchReport *)data; + const auto touch_data = (const TouchRecord *)(&report_data->touch_record[0]); x_ = touch_data->x; y_ = touch_data->y; num_touch_points_ = (data_len - sizeof(TouchReport)) / sizeof(TouchRecord); @@ -86,7 +86,7 @@ class Tt21100 { } case 14: { // button event - auto button_data = (ButtonRecord *)data; + const auto button_data = (const ButtonRecord *)data; home_button_pressed_ = button_data->btn_val; auto btn_signal = button_data->btn_signal[0]; logger_.debug("Button event({}): {}, {}", (int)(button_data->length), home_button_pressed_, diff --git a/components/wifi/include/wifi_ap.hpp b/components/wifi/include/wifi_ap.hpp index 4c197acf8..de4fa3302 100644 --- a/components/wifi/include/wifi_ap.hpp +++ b/components/wifi/include/wifi_ap.hpp @@ -38,7 +38,7 @@ class WifiAp { * @brief Initialize the WiFi Access Point (AP) * @param config WifiAp::Config structure with initialization information. */ - WifiAp(const Config &config) : logger_({.tag = "WifiAp", .level = config.log_level}) { + explicit WifiAp(const Config &config) : logger_({.tag = "WifiAp", .level = config.log_level}) { // Code below is modified from: // https://github.com/espressif/esp-idf/blob/master/examples/wifi/getting_started/softAP/main/softap_example_main.c // NOTE: Init phase diff --git a/components/wifi/include/wifi_sta.hpp b/components/wifi/include/wifi_sta.hpp index f06016040..a60f1e7d4 100644 --- a/components/wifi/include/wifi_sta.hpp +++ b/components/wifi/include/wifi_sta.hpp @@ -65,7 +65,7 @@ class WifiSta { * @brief Initialize the WiFi Station (STA) * @param config WifiSta::Config structure with initialization information. */ - WifiSta(const Config &config) + explicit WifiSta(const Config &config) : num_retries_(config.num_connect_retries), connect_callback_(config.on_connected), disconnect_callback_(config.on_disconnected), ip_callback_(config.on_got_ip), logger_({.tag = "WifiSta", .level = config.log_level}) { @@ -168,7 +168,7 @@ class WifiSta { * @brief Whether the station is connected to an access point. * @return true if it is currently connected, false otherwise. */ - bool is_connected() { return connected_; } + bool is_connected() const { return connected_; } protected: static void event_handler(void *arg, esp_event_base_t event_base, int32_t event_id, diff --git a/docs/adc/adc_types.html b/docs/adc/adc_types.html index 426e2be54..98a49b607 100644 --- a/docs/adc/adc_types.html +++ b/docs/adc/adc_types.html @@ -145,7 +145,7 @@
  • ADC APIs »
  • ADC Types
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    diff --git a/docs/adc/ads1x15.html b/docs/adc/ads1x15.html index 0066a4407..a21a3fc74 100644 --- a/docs/adc/ads1x15.html +++ b/docs/adc/ads1x15.html @@ -146,7 +146,7 @@
  • ADC APIs »
  • ADS1x15 I2C ADC
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,7 +163,7 @@

    API Reference

    Header File

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

    ADS1X15 ExamplePublic Functions

    -inline Ads1x15(const Ads1015Config &config)
    +inline explicit Ads1x15(const Ads1015Config &config)

    Construct Ads1x15 specficially for ADS1015.

    Parameters
    @@ -445,7 +445,7 @@

    ADS1X15 Example
    -inline Ads1x15(const Ads1115Config &config)
    +inline explicit Ads1x15(const Ads1115Config &config)

    Construct Ads1x15 specficially for ADS1115.

    Parameters
    diff --git a/docs/adc/ads7138.html b/docs/adc/ads7138.html index 9eb3ec38f..fd7d8e159 100644 --- a/docs/adc/ads7138.html +++ b/docs/adc/ads7138.html @@ -146,7 +146,7 @@
  • ADC APIs »
  • ADS7138 I2C ADC
  • - Edit on GitHub + Edit on GitHub

  • @@ -168,7 +168,7 @@

    API Reference

    Header File

    @@ -703,7 +703,7 @@

    ADS7138 ExamplePublic Functions

    -inline Ads7138(const Config &config)
    +inline explicit Ads7138(const Config &config)

    Construct Ads7138.

    Parameters
    diff --git a/docs/adc/continuous_adc.html b/docs/adc/continuous_adc.html index 3ce4c059b..c382083b9 100644 --- a/docs/adc/continuous_adc.html +++ b/docs/adc/continuous_adc.html @@ -146,7 +146,7 @@
  • ADC APIs »
  • Continuous ADC
  • - Edit on GitHub + Edit on GitHub

  • @@ -168,7 +168,7 @@

    API Reference

    Header File

    @@ -238,7 +238,7 @@

    Continuous ADC ExamplePublic Functions

    -inline ContinuousAdc(const Config &config)
    +inline explicit ContinuousAdc(const Config &config)

    Initialize and start the continuous adc reader.

    Parameters
    diff --git a/docs/adc/index.html b/docs/adc/index.html index 68f339e65..bfff6cd5e 100644 --- a/docs/adc/index.html +++ b/docs/adc/index.html @@ -138,7 +138,7 @@
  • »
  • ADC APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/adc/oneshot_adc.html b/docs/adc/oneshot_adc.html index 898ab7836..5875069b3 100644 --- a/docs/adc/oneshot_adc.html +++ b/docs/adc/oneshot_adc.html @@ -146,7 +146,7 @@
  • ADC APIs »
  • Oneshot ADC
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -214,7 +214,7 @@

    Oneshot ADC ExamplePublic Functions

    -inline OneshotAdc(const Config &config)
    +inline explicit OneshotAdc(const Config &config)

    Initialize the oneshot adc reader.

    Parameters
    diff --git a/docs/adc/tla2528.html b/docs/adc/tla2528.html index a1afc8eb5..c982c665d 100644 --- a/docs/adc/tla2528.html +++ b/docs/adc/tla2528.html @@ -146,7 +146,7 @@
  • ADC APIs »
  • TLA2528 I2C ADC
  • - Edit on GitHub + Edit on GitHub

  • @@ -168,7 +168,7 @@

    API Reference

    Header File

    @@ -566,7 +566,7 @@

    TLA2528 ExamplePublic Functions

    -inline Tla2528(const Config &config)
    +inline explicit Tla2528(const Config &config)

    Construct Tla2528.

    Parameters
    diff --git a/docs/bldc/bldc_driver.html b/docs/bldc/bldc_driver.html index e8323c386..27eb7d9d0 100644 --- a/docs/bldc/bldc_driver.html +++ b/docs/bldc/bldc_driver.html @@ -142,7 +142,7 @@
  • BLDC APIs »
  • BLDC Driver
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

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

    ClassesPublic Functions

    -inline BldcDriver(const Config &config)
    +inline explicit BldcDriver(const Config &config)

    Initialize the bldc driver.

    Note

    diff --git a/docs/bldc/bldc_motor.html b/docs/bldc/bldc_motor.html index be328cda7..96dddfab6 100644 --- a/docs/bldc/bldc_motor.html +++ b/docs/bldc/bldc_motor.html @@ -144,7 +144,7 @@
  • BLDC APIs »
  • BLDC Motor
  • - Edit on GitHub + Edit on GitHub

  • @@ -175,7 +175,7 @@

    API Reference

    Header File

    @@ -321,7 +321,7 @@

    Example UsagePublic Functions

    -inline BldcMotor(const Config &config)
    +inline explicit BldcMotor(const Config &config)

    Create and initialize the BLDC motor, running through any necessary sensor calibration.

    @@ -568,13 +568,13 @@

    Example Usage

    Header File

    Header File

    diff --git a/docs/bldc/index.html b/docs/bldc/index.html index 9860c0cbf..cb97337d0 100644 --- a/docs/bldc/index.html +++ b/docs/bldc/index.html @@ -134,7 +134,7 @@
  • »
  • BLDC APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/button.html b/docs/button.html index 3083488a0..67be08c29 100644 --- a/docs/button.html +++ b/docs/button.html @@ -137,7 +137,7 @@
  • »
  • Button APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,7 +163,7 @@

    API Reference

    Header File

    diff --git a/docs/cli.html b/docs/cli.html index 22bfdfd40..e1c674f8f 100644 --- a/docs/cli.html +++ b/docs/cli.html @@ -140,7 +140,7 @@
  • »
  • Command Line Interface (CLI) APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -183,7 +183,7 @@

    API Reference

    Header File

    @@ -347,7 +347,7 @@

    Oneshot CLI Example

    Header File

    diff --git a/docs/color.html b/docs/color.html index f633c4d1f..e4ee0a0a8 100644 --- a/docs/color.html +++ b/docs/color.html @@ -137,7 +137,7 @@
  • »
  • Color APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -160,7 +160,7 @@

    API Reference

    Header File

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

    ClassesPublic Functions

    -Rgb(const float &r, const float &g, const float &b)
    +explicit Rgb(const float &r, const float &g, const float &b)

    Construct an Rgb object from the provided rgb values.

    Note

    @@ -207,7 +207,7 @@

    Classes
    -Rgb(const Hsv &hsv)
    +explicit Rgb(const Hsv &hsv)

    Construct an Rgb object from the provided Hsv object.

    Note

    @@ -288,7 +288,7 @@

    ClassesPublic Functions

    -Hsv(const float &h, const float &s, const float &v)
    +explicit Hsv(const float &h, const float &s, const float &v)

    Construct a Hsv object from the provided values.

    Parameters
    @@ -314,7 +314,7 @@

    Classes
    -Hsv(const Rgb &rgb)
    +explicit Hsv(const Rgb &rgb)

    Construct Hsv object from Rgb object. Calls rgb.hsv() to perform the conversion.

    Parameters
    diff --git a/docs/controller.html b/docs/controller.html index 450549140..1d82638c9 100644 --- a/docs/controller.html +++ b/docs/controller.html @@ -137,7 +137,7 @@
  • »
  • Controller APIs
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -512,19 +512,19 @@

    I2C Analog Controller ExamplePublic Functions

    -inline Controller(const DigitalConfig &config)
    +inline explicit Controller(const DigitalConfig &config)

    Create a Digital controller.

    -inline Controller(const AnalogJoystickConfig &config)
    +inline explicit Controller(const AnalogJoystickConfig &config)

    Create an analog joystick controller.

    -inline Controller(const DualConfig &config)
    +inline explicit Controller(const DualConfig &config)

    Create a dual d-pad + analog joystick controller.

    diff --git a/docs/csv.html b/docs/csv.html index 912cabd83..f8db856d0 100644 --- a/docs/csv.html +++ b/docs/csv.html @@ -138,7 +138,7 @@
  • »
  • CSV APIs
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    diff --git a/docs/display/display.html b/docs/display/display.html index 577a6c0dc..92cbfe031 100644 --- a/docs/display/display.html +++ b/docs/display/display.html @@ -142,7 +142,7 @@
  • Display APIs »
  • Display
  • - Edit on GitHub + Edit on GitHub

  • @@ -160,7 +160,7 @@

    API Reference

    Header File

    @@ -239,7 +239,7 @@

    ClassesPublic Functions

    -inline Display(const AllocatingConfig &config)
    +inline explicit Display(const AllocatingConfig &config)

    Allocate the dsiplay buffers, initialize LVGL, then start the update task.

    Parameters
    @@ -250,7 +250,7 @@

    Classes
    -inline Display(const NonAllocatingConfig &config)
    +inline explicit Display(const NonAllocatingConfig &config)

    Initialize LVGL then start the update task.

    Parameters
    @@ -322,8 +322,8 @@

    Classes -
    -inline void force_refresh()
    +
    +inline void force_refresh() const

    Force a redraw / refresh of the display.

    Note

    @@ -354,8 +354,8 @@

    Classes -
    -inline size_t vram_size_px()
    +
    +inline size_t vram_size_px() const

    Return the number of pixels that vram() can hold.

    Returns
    @@ -365,8 +365,8 @@

    Classes -
    -inline size_t vram_size_bytes()
    +
    +inline size_t vram_size_bytes() const

    Return the number of bytes that vram() can hold.

    Returns
    diff --git a/docs/display/display_drivers.html b/docs/display/display_drivers.html index fae48ed4d..c0af0572d 100644 --- a/docs/display/display_drivers.html +++ b/docs/display/display_drivers.html @@ -144,7 +144,7 @@
  • Display APIs »
  • Display Drivers
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -190,7 +190,11 @@

    WROVER-KIT ILI9341 Config bool backlight_on_value = false; bool reset_value = false; bool invert_colors = false; - auto flush_cb = espp::Ili9341::flush; + int offset_x = 0; + int offset_y = 0; + bool mirror_x = false; + bool mirror_y = false; + using DisplayDriver = espp::Ili9341; auto rotation = espp::Display::Rotation::LANDSCAPE; @@ -225,50 +229,30 @@

    ili9341 Example ret = spi_bus_add_device(spi_num, &devcfg, &spi); ESP_ERROR_CHECK(ret); -#if CONFIG_HARDWARE_WROVER_KIT // initialize the controller - espp::Ili9341::initialize(espp::display_drivers::Config{.lcd_write = lcd_write, - .lcd_send_lines = lcd_send_lines, - .reset_pin = reset, - .data_command_pin = dc_pin, - .reset_value = reset_value, - .invert_colors = invert_colors}); -#endif -#if CONFIG_HARDWARE_TTGO - // initialize the controller - espp::St7789::initialize(espp::display_drivers::Config{ - .lcd_write = lcd_write, - .lcd_send_lines = lcd_send_lines, - .reset_pin = reset, - .data_command_pin = dc_pin, - .invert_colors = invert_colors, - .offset_x = 40, - .offset_y = 53, - }); -#endif -#if CONFIG_HARDWARE_BOX - // initialize the controller - espp::St7789::initialize(espp::display_drivers::Config{ + DisplayDriver::initialize(espp::display_drivers::Config{ .lcd_write = lcd_write, .lcd_send_lines = lcd_send_lines, .reset_pin = reset, .data_command_pin = dc_pin, + .reset_value = reset_value, .invert_colors = invert_colors, - .mirror_x = true, - .mirror_y = true, + .offset_x = offset_x, + .offset_y = offset_y, + .mirror_x = mirror_x, + .mirror_y = mirror_y, }); -#endif - // initialize the display / lvgl auto display = std::make_shared<espp::Display>( espp::Display::AllocatingConfig{.width = width, .height = height, .pixel_buffer_size = pixel_buffer_size, - .flush_callback = flush_cb, + .flush_callback = DisplayDriver::flush, .backlight_pin = backlight, .backlight_on_value = backlight_on_value, .rotation = rotation, .software_rotation_enabled = true}); + // initialize the gui Gui gui({.display = display}); size_t iterations = 0; @@ -440,7 +424,7 @@

    ili9341 Example

    Header File

    @@ -468,7 +452,11 @@

    TTGO St7789 Config bool backlight_on_value = false; bool reset_value = false; bool invert_colors = false; - auto flush_cb = espp::St7789::flush; + int offset_x = 40; + int offset_y = 53; + bool mirror_x = false; + bool mirror_y = false; + using DisplayDriver = espp::St7789; auto rotation = espp::Display::Rotation::PORTRAIT; @@ -491,7 +479,11 @@

    ESP32-S3-BOX St7789 Config bool backlight_on_value = true; bool reset_value = false; bool invert_colors = true; - auto flush_cb = espp::St7789::flush; + int offset_x = 0; + int offset_y = 0; + bool mirror_x = true; + bool mirror_y = true; + using DisplayDriver = espp::St7789; auto rotation = espp::Display::Rotation::LANDSCAPE; @@ -526,50 +518,30 @@

    st7789 Example ret = spi_bus_add_device(spi_num, &devcfg, &spi); ESP_ERROR_CHECK(ret); -#if CONFIG_HARDWARE_WROVER_KIT // initialize the controller - espp::Ili9341::initialize(espp::display_drivers::Config{.lcd_write = lcd_write, - .lcd_send_lines = lcd_send_lines, - .reset_pin = reset, - .data_command_pin = dc_pin, - .reset_value = reset_value, - .invert_colors = invert_colors}); -#endif -#if CONFIG_HARDWARE_TTGO - // initialize the controller - espp::St7789::initialize(espp::display_drivers::Config{ - .lcd_write = lcd_write, - .lcd_send_lines = lcd_send_lines, - .reset_pin = reset, - .data_command_pin = dc_pin, - .invert_colors = invert_colors, - .offset_x = 40, - .offset_y = 53, - }); -#endif -#if CONFIG_HARDWARE_BOX - // initialize the controller - espp::St7789::initialize(espp::display_drivers::Config{ + DisplayDriver::initialize(espp::display_drivers::Config{ .lcd_write = lcd_write, .lcd_send_lines = lcd_send_lines, .reset_pin = reset, .data_command_pin = dc_pin, + .reset_value = reset_value, .invert_colors = invert_colors, - .mirror_x = true, - .mirror_y = true, + .offset_x = offset_x, + .offset_y = offset_y, + .mirror_x = mirror_x, + .mirror_y = mirror_y, }); -#endif - // initialize the display / lvgl auto display = std::make_shared<espp::Display>( espp::Display::AllocatingConfig{.width = width, .height = height, .pixel_buffer_size = pixel_buffer_size, - .flush_callback = flush_cb, + .flush_callback = DisplayDriver::flush, .backlight_pin = backlight, .backlight_on_value = backlight_on_value, .rotation = rotation, .software_rotation_enabled = true}); + // initialize the gui Gui gui({.display = display}); size_t iterations = 0; diff --git a/docs/display/index.html b/docs/display/index.html index b3f9e9bba..ed988c212 100644 --- a/docs/display/index.html +++ b/docs/display/index.html @@ -134,7 +134,7 @@
  • »
  • Display APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/encoder/abi_encoder.html b/docs/encoder/abi_encoder.html index 0d7b5774e..c0d38390e 100644 --- a/docs/encoder/abi_encoder.html +++ b/docs/encoder/abi_encoder.html @@ -144,7 +144,7 @@
  • Encoder APIs »
  • ABI Encoder
  • - Edit on GitHub + Edit on GitHub

  • @@ -166,7 +166,7 @@

    API Reference

    Header File

    @@ -239,7 +239,7 @@

    AbiEncoder (LINEAR) ExamplePublic Functions

    -template<EncoderType type = T>
    inline AbiEncoder(const Config &config)
    +template<EncoderType type = T>
    inline explicit AbiEncoder(const Config &config)

    Initialize the pulse count hardware for the ABI encoder.

    Note

    diff --git a/docs/encoder/as5600.html b/docs/encoder/as5600.html index 405ba847d..4fcce72af 100644 --- a/docs/encoder/as5600.html +++ b/docs/encoder/as5600.html @@ -144,7 +144,7 @@
  • Encoder APIs »
  • AS5600 Magnetic Encoder
  • - Edit on GitHub + Edit on GitHub

  • @@ -177,7 +177,7 @@

    API Reference

    Header File

    @@ -334,7 +334,7 @@

    As5600 ExamplePublic Functions

    -inline As5600(const Config &config)
    +inline explicit As5600(const Config &config)

    Construct the As5600 and start the update task.

    diff --git a/docs/encoder/encoder_types.html b/docs/encoder/encoder_types.html index 54b08f89a..d9f41fa15 100644 --- a/docs/encoder/encoder_types.html +++ b/docs/encoder/encoder_types.html @@ -143,7 +143,7 @@
  • Encoder APIs »
  • Encoder Types
  • - Edit on GitHub + Edit on GitHub

  • @@ -160,7 +160,7 @@

    API Reference

    Header File

    diff --git a/docs/encoder/index.html b/docs/encoder/index.html index 374f0901e..ce6628c68 100644 --- a/docs/encoder/index.html +++ b/docs/encoder/index.html @@ -136,7 +136,7 @@
  • »
  • Encoder APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/encoder/mt6701.html b/docs/encoder/mt6701.html index 19ed71347..9f47cfc4e 100644 --- a/docs/encoder/mt6701.html +++ b/docs/encoder/mt6701.html @@ -144,7 +144,7 @@
  • Encoder APIs »
  • MT6701 Magnetic Encoder
  • - Edit on GitHub + Edit on GitHub

  • @@ -177,7 +177,7 @@

    API Reference

    Header File

    @@ -332,7 +332,7 @@

    Mt6701 ExamplePublic Functions

    -inline Mt6701(const Config &config)
    +inline explicit Mt6701(const Config &config)

    Construct the Mt6701 and start the update task.

    diff --git a/docs/event_manager.html b/docs/event_manager.html index 38d7c0f85..20e2f4312 100644 --- a/docs/event_manager.html +++ b/docs/event_manager.html @@ -137,7 +137,7 @@
  • »
  • Event Manager APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,7 +163,7 @@

    API Reference

    Header File

    diff --git a/docs/file_system.html b/docs/file_system.html index f03a0ae81..5abec5aa1 100644 --- a/docs/file_system.html +++ b/docs/file_system.html @@ -137,7 +137,7 @@
  • »
  • File System APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -160,7 +160,7 @@

    API Reference

    Header File

    @@ -178,25 +178,25 @@

    Classes

    File System Info Example

    -

      auto &fs = espp::FileSystem::get();
    -  // NOTE: partition label is configured by menuconfig and should match the
    -  //       partition label in the partition table (partitions.csv).
    -  // returns a const char*
    -  auto partition_label = fs.get_partition_label();
    -  // returns a std::string
    -  auto mount_point = fs.get_mount_point();
    -  // returns a std::filesystem::path
    -  auto root_path = fs.get_root_path();
    -  logger.info("Partition label: {}", partition_label);
    -  logger.info("Mount point:     {}", mount_point);
    -  logger.info("Root path:       {}", root_path.string());
    -  // human_readable returns a string with the size and unit, e.g. 1.2 MB
    -  auto total_space = fs.human_readable(fs.get_total_space());
    -  auto free_space = fs.human_readable(fs.get_free_space());
    -  auto used_space = fs.human_readable(fs.get_used_space());
    -  logger.info("Total space: {}", total_space);
    -  logger.info("Free space:  {}", free_space);
    -  logger.info("Used space:  {}", used_space);
    +

        auto &fs = espp::FileSystem::get();
    +    // NOTE: partition label is configured by menuconfig and should match the
    +    //       partition label in the partition table (partitions.csv).
    +    // returns a const char*
    +    auto partition_label = fs.get_partition_label();
    +    // returns a std::string
    +    auto mount_point = fs.get_mount_point();
    +    // returns a std::filesystem::path
    +    auto root_path = fs.get_root_path();
    +    logger.info("Partition label: {}", partition_label);
    +    logger.info("Mount point:     {}", mount_point);
    +    logger.info("Root path:       {}", root_path.string());
    +    // human_readable returns a string with the size and unit, e.g. 1.2 MB
    +    auto total_space = fs.human_readable(fs.get_total_space());
    +    auto free_space = fs.human_readable(fs.get_free_space());
    +    auto used_space = fs.human_readable(fs.get_used_space());
    +    logger.info("Total space: {}", total_space);
    +    logger.info("Free space:  {}", free_space);
    +    logger.info("Used space:  {}", used_space);
     

    diff --git a/docs/filters/biquad.html b/docs/filters/biquad.html index 9d2f748de..3b47b79b5 100644 --- a/docs/filters/biquad.html +++ b/docs/filters/biquad.html @@ -146,7 +146,7 @@
  • Filter APIs »
  • Biquad Filter
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,7 +163,7 @@

    API Reference

    Header File

    diff --git a/docs/filters/butterworth.html b/docs/filters/butterworth.html index 0d6007979..3a7244f00 100644 --- a/docs/filters/butterworth.html +++ b/docs/filters/butterworth.html @@ -145,7 +145,7 @@
  • Filter APIs »
  • Butterworth Filter
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,7 +163,7 @@

    API Reference

    Header File

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

    ClassesPublic Functions

    -inline ButterworthFilter(const Config &config)
    +inline explicit ButterworthFilter(const Config &config)

    Construct the butterworth filter for the given config.

    Parameters
    diff --git a/docs/filters/index.html b/docs/filters/index.html index 827976fba..62c3f64c2 100644 --- a/docs/filters/index.html +++ b/docs/filters/index.html @@ -137,7 +137,7 @@
  • »
  • Filter APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/filters/lowpass.html b/docs/filters/lowpass.html index 1018786e1..67fd3952a 100644 --- a/docs/filters/lowpass.html +++ b/docs/filters/lowpass.html @@ -145,7 +145,7 @@
  • Filter APIs »
  • Lowpass Filter
  • - Edit on GitHub + Edit on GitHub

  • @@ -164,7 +164,7 @@

    API Reference

    Header File

    @@ -177,7 +177,7 @@

    ClassesPublic Functions

    -inline LowpassFilter(const Config &config)
    +inline explicit LowpassFilter(const Config &config)

    Initialize the lowpass filter coefficients based on the config.

    Parameters
    diff --git a/docs/filters/sos.html b/docs/filters/sos.html index 833984f0a..93a1cb5d8 100644 --- a/docs/filters/sos.html +++ b/docs/filters/sos.html @@ -145,7 +145,7 @@
  • Filter APIs »
  • Second Order Sections (SoS) Filter
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,7 +163,7 @@

    API Reference

    Header File

    @@ -185,7 +185,7 @@

    ClassesPublic Functions

    -inline SosFilter(const std::array<TransferFunction<3>, N> &config)
    +inline explicit SosFilter(const std::array<TransferFunction<3>, N> &config)

    Construct a second order sections filter.

    Parameters
    diff --git a/docs/filters/transfer_function.html b/docs/filters/transfer_function.html index f772c770b..2dd77cd6b 100644 --- a/docs/filters/transfer_function.html +++ b/docs/filters/transfer_function.html @@ -144,7 +144,7 @@
  • Filter APIs »
  • Transfer Function API
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    diff --git a/docs/ftp/ftp_server.html b/docs/ftp/ftp_server.html index d01ce7e4a..10eb1148e 100644 --- a/docs/ftp/ftp_server.html +++ b/docs/ftp/ftp_server.html @@ -144,7 +144,7 @@
  • FTP APIs »
  • FTP Server
  • - Edit on GitHub + Edit on GitHub

  • @@ -166,7 +166,7 @@

    API Reference

    Header File

    @@ -226,14 +226,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/esp-cpp/esp-box-emu/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/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 c717b05a4..379d84434 100644
    --- a/docs/ftp/index.html
    +++ b/docs/ftp/index.html
    @@ -133,7 +133,7 @@
           
  • »
  • FTP APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/genindex.html b/docs/genindex.html index d6674d905..25f7e3f63 100644 --- a/docs/genindex.html +++ b/docs/genindex.html @@ -127,7 +127,7 @@
  • »
  • Index
  • - Edit on GitHub + Edit on GitHub

  • @@ -804,7 +804,7 @@

    E

  • espp::Bm8563::set_date (C++ function)
  • -
  • espp::Bm8563::set_date_time (C++ function) +
  • espp::Bm8563::set_date_time (C++ function)
  • espp::Bm8563::set_time (C++ function)
  • @@ -1102,7 +1102,7 @@

    E

  • espp::Display::flush_fn (C++ type)
  • -
  • espp::Display::force_refresh (C++ function) +
  • espp::Display::force_refresh (C++ function)
  • espp::Display::get_brightness (C++ function)
  • @@ -1160,9 +1160,9 @@

    E

  • espp::Display::vram1 (C++ function)
  • -
  • espp::Display::vram_size_bytes (C++ function) +
  • espp::Display::vram_size_bytes (C++ function)
  • -
  • espp::Display::vram_size_px (C++ function) +
  • espp::Display::vram_size_px (C++ function)
  • espp::Display::width (C++ function)
  • @@ -2400,7 +2400,7 @@

    E

  • espp::RtpJpegPacket::get_jpeg_data (C++ function)
  • -
  • espp::RtpJpegPacket::get_mjpeg_header (C++ function) +
  • espp::RtpJpegPacket::get_mjpeg_header (C++ function)
  • espp::RtpJpegPacket::get_num_q_tables (C++ function)
  • @@ -2656,7 +2656,7 @@

    E

  • espp::St25dv::SYST_ADDRESS (C++ member)
  • -
  • espp::St25dv::transfer (C++ function) +
  • espp::St25dv::transfer (C++ function)
  • espp::St25dv::write (C++ function)
  • @@ -2798,9 +2798,9 @@

    E

  • espp::Task::Config::stack_size_bytes (C++ member)
  • -
  • espp::Task::is_running (C++ function) +
  • espp::Task::is_running (C++ function)
  • -
  • espp::Task::is_started (C++ function) +
  • espp::Task::is_started (C++ function)
  • espp::Task::make_unique (C++ function), [1]
  • @@ -2982,7 +2982,7 @@

    E

  • espp::TKeyboard::DEFAULT_ADDRESS (C++ member)
  • -
  • espp::TKeyboard::get_key (C++ function) +
  • espp::TKeyboard::get_key (C++ function)
  • espp::TKeyboard::key_cb_fn (C++ type)
  • @@ -3316,7 +3316,7 @@

    E

  • espp::WifiSta::ip_callback (C++ type)
  • -
  • espp::WifiSta::is_connected (C++ function) +
  • espp::WifiSta::is_connected (C++ function)
  • espp::WifiSta::WifiSta (C++ function)
  • diff --git a/docs/haptics/bldc_haptics.html b/docs/haptics/bldc_haptics.html index fa5afb2bd..cd4e68343 100644 --- a/docs/haptics/bldc_haptics.html +++ b/docs/haptics/bldc_haptics.html @@ -144,7 +144,7 @@
  • Haptics APIs »
  • BLDC Haptics
  • - Edit on GitHub + Edit on GitHub

  • @@ -185,19 +185,19 @@

    API Reference

    Header File

    Header File

    Header File

    @@ -297,7 +297,7 @@

    Example 2: Playing a haptic click / buzzPublic Functions

    -inline BldcHaptics(const Config &config)
    +inline explicit BldcHaptics(const Config &config)

    Constructor for the haptic motor.

    Parameters
    diff --git a/docs/haptics/drv2605.html b/docs/haptics/drv2605.html index 616f5d7e2..eb47499ec 100644 --- a/docs/haptics/drv2605.html +++ b/docs/haptics/drv2605.html @@ -142,7 +142,7 @@
  • Haptics APIs »
  • DRV2605 Haptic Motor Driver
  • - Edit on GitHub + Edit on GitHub

  • @@ -164,7 +164,7 @@

    API Reference

    Header File

    @@ -545,7 +545,7 @@

    DRV2605 ExamplePublic Functions

    -inline Drv2605(const Config &config)
    +inline explicit Drv2605(const Config &config)

    Construct and initialize the DRV2605.

    diff --git a/docs/haptics/index.html b/docs/haptics/index.html index f47504824..29d01cd72 100644 --- a/docs/haptics/index.html +++ b/docs/haptics/index.html @@ -134,7 +134,7 @@
  • »
  • Haptics APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/i2c.html b/docs/i2c.html index e2201f6e9..d2be1ab60 100644 --- a/docs/i2c.html +++ b/docs/i2c.html @@ -137,7 +137,7 @@
  • »
  • I2C
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    diff --git a/docs/index.html b/docs/index.html index 64d492652..c04ab3da9 100644 --- a/docs/index.html +++ b/docs/index.html @@ -129,7 +129,7 @@
  • »
  • ESPP Documentation
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/input/encoder_input.html b/docs/input/encoder_input.html index a92859871..0422fbc6c 100644 --- a/docs/input/encoder_input.html +++ b/docs/input/encoder_input.html @@ -147,7 +147,7 @@
  • Input APIs »
  • Encoder Input
  • - Edit on GitHub + Edit on GitHub

  • @@ -165,7 +165,7 @@

    API Reference

    Header File

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

    ClassesPublic Functions

    -inline EncoderInput(const Config &config)
    +inline explicit EncoderInput(const Config &config)

    Initialize and register the input drivers associated with the encoder.

    Parameters
    diff --git a/docs/input/ft5x06.html b/docs/input/ft5x06.html index db10e4430..aae9f6423 100644 --- a/docs/input/ft5x06.html +++ b/docs/input/ft5x06.html @@ -147,7 +147,7 @@
  • Input APIs »
  • FT5x06 Touch Controller
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,7 +163,7 @@

    API Reference

    Header File

    diff --git a/docs/input/gt911.html b/docs/input/gt911.html index 788430af9..6acad5e9f 100644 --- a/docs/input/gt911.html +++ b/docs/input/gt911.html @@ -147,7 +147,7 @@
  • Input APIs »
  • GT911 Touch Controller
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,7 +163,7 @@

    API Reference

    Header File

    diff --git a/docs/input/index.html b/docs/input/index.html index 2b4b71fc4..3744c0818 100644 --- a/docs/input/index.html +++ b/docs/input/index.html @@ -139,7 +139,7 @@
  • »
  • Input APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/input/keypad_input.html b/docs/input/keypad_input.html index dc41da262..b174dc48a 100644 --- a/docs/input/keypad_input.html +++ b/docs/input/keypad_input.html @@ -147,7 +147,7 @@
  • Input APIs »
  • Keypad Input
  • - Edit on GitHub + Edit on GitHub

  • @@ -166,7 +166,7 @@

    API Reference

    Header File

    @@ -179,7 +179,7 @@

    ClassesPublic Functions

    -inline KeypadInput(const Config &config)
    +inline explicit KeypadInput(const Config &config)

    Initialize and register the input drivers associated with the keypad.

    Parameters
    diff --git a/docs/input/t_keyboard.html b/docs/input/t_keyboard.html index 86a3fd843..208399d03 100644 --- a/docs/input/t_keyboard.html +++ b/docs/input/t_keyboard.html @@ -147,7 +147,7 @@
  • Input APIs »
  • LilyGo T-Keyboard
  • - Edit on GitHub + Edit on GitHub

  • @@ -164,7 +164,7 @@

    API Reference

    Header File

    @@ -280,8 +280,8 @@

    Example -
    -inline uint8_t get_key()
    +
    +inline uint8_t get_key() const

    Get the currently pressed key.

    This function returns the currently pressed key.

    diff --git a/docs/input/touchpad_input.html b/docs/input/touchpad_input.html index 4674868c6..805d269e3 100644 --- a/docs/input/touchpad_input.html +++ b/docs/input/touchpad_input.html @@ -147,7 +147,7 @@
  • Input APIs »
  • Touchpad Input
  • - Edit on GitHub + Edit on GitHub

  • @@ -165,7 +165,7 @@

    API Reference

    Header File

    @@ -201,7 +201,7 @@

    ClassesPublic Functions

    -inline TouchpadInput(const Config &config)
    +inline explicit TouchpadInput(const Config &config)

    Initialize and register the input drivers associated with the touchpad.

    Parameters
    diff --git a/docs/input/tt21100.html b/docs/input/tt21100.html index 952e273c8..2c3821c1f 100644 --- a/docs/input/tt21100.html +++ b/docs/input/tt21100.html @@ -147,7 +147,7 @@
  • Input APIs »
  • TT21100 Touch Controller
  • - Edit on GitHub + Edit on GitHub

  • @@ -165,7 +165,7 @@

    API Reference

    Header File

    diff --git a/docs/io_expander/aw9523.html b/docs/io_expander/aw9523.html index 75bb3f5f6..d6e2291e2 100644 --- a/docs/io_expander/aw9523.html +++ b/docs/io_expander/aw9523.html @@ -142,7 +142,7 @@
  • IO Expander APIs »
  • AW9523 I/O Expander
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -419,7 +419,7 @@

    AW9523 ExamplePublic Functions

    -inline Aw9523(const Config &config)
    +inline explicit Aw9523(const Config &config)

    Construct the Aw9523. Will call initialize() if auto_init is true.

    Parameters
    diff --git a/docs/io_expander/index.html b/docs/io_expander/index.html index be0de7897..e18c710ec 100644 --- a/docs/io_expander/index.html +++ b/docs/io_expander/index.html @@ -134,7 +134,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 29d1e8338..ac76581d6 100644 --- a/docs/io_expander/mcp23x17.html +++ b/docs/io_expander/mcp23x17.html @@ -142,7 +142,7 @@
  • IO Expander APIs »
  • MCP23x17 I/O Expander
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -332,7 +332,7 @@

    MCP23x17 ExamplePublic Functions

    -inline Mcp23x17(const Config &config)
    +inline explicit Mcp23x17(const Config &config)

    Construct the Mcp23x17 and configure it.

    Parameters
    diff --git a/docs/joystick.html b/docs/joystick.html index 8638f8486..266ce4f17 100644 --- a/docs/joystick.html +++ b/docs/joystick.html @@ -138,7 +138,7 @@
  • »
  • Joystick APIs
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -283,7 +283,7 @@

    ADC Joystick ExamplePublic Functions

    -inline Joystick(const Config &config)
    +inline explicit Joystick(const Config &config)

    Initalize the joystick using the provided configuration.

    Parameters
    diff --git a/docs/led.html b/docs/led.html index 4b2fc9cd7..3c3c9d02c 100644 --- a/docs/led.html +++ b/docs/led.html @@ -138,7 +138,7 @@
  • »
  • LED APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -160,7 +160,7 @@

    API Reference

    Header File

    @@ -253,7 +253,7 @@

    Breathing LED ExamplePublic Functions

    -inline Led(const Config &config)
    +inline explicit Led(const Config &config)

    Initialize the LEDC subsystem according to the configuration.

    Parameters
    diff --git a/docs/led_strip.html b/docs/led_strip.html index 7fa6fd1c7..a87f019e5 100644 --- a/docs/led_strip.html +++ b/docs/led_strip.html @@ -137,7 +137,7 @@
  • »
  • LED Strip APIs
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -321,7 +321,7 @@

    Example 1: APA102 via SPIPublic Functions

    -inline LedStrip(const Config &config)
    +inline explicit LedStrip(const Config &config)

    Constructor.

    Parameters
    diff --git a/docs/logger.html b/docs/logger.html index 860b93ffe..7a74bdc45 100644 --- a/docs/logger.html +++ b/docs/logger.html @@ -139,7 +139,7 @@
  • »
  • Logging APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -166,7 +166,7 @@

    API Reference

    Header File

    @@ -287,7 +287,7 @@

    Threaded Logging and Verbosity ExamplePublic Functions

    -inline Logger(const Config &config)
    +inline explicit Logger(const Config &config)

    Construct a new Logger object.

    Parameters
    diff --git a/docs/math/bezier.html b/docs/math/bezier.html index 1f68c2efd..a2282f86c 100644 --- a/docs/math/bezier.html +++ b/docs/math/bezier.html @@ -145,7 +145,7 @@
  • Math APIs »
  • Bezier
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,7 +163,7 @@

    API Reference

    Header File

    @@ -184,7 +184,7 @@

    ClassesPublic Functions

    -inline Bezier(const Config &config)
    +inline explicit Bezier(const Config &config)

    Construct an unweighted cubic bezier curve for evaluation.

    Parameters
    @@ -195,7 +195,7 @@

    Classes
    -inline Bezier(const WeightedConfig &config)
    +inline explicit Bezier(const WeightedConfig &config)

    Construct a rational / weighted cubic bezier curve for evaluation.

    Parameters
    diff --git a/docs/math/fast_math.html b/docs/math/fast_math.html index 300287abd..9636e37b8 100644 --- a/docs/math/fast_math.html +++ b/docs/math/fast_math.html @@ -144,7 +144,7 @@
  • Math APIs »
  • Fast Math
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    diff --git a/docs/math/gaussian.html b/docs/math/gaussian.html index 747260d09..6786f293c 100644 --- a/docs/math/gaussian.html +++ b/docs/math/gaussian.html @@ -146,7 +146,7 @@
  • Math APIs »
  • Gaussian
  • - Edit on GitHub + Edit on GitHub

  • @@ -166,7 +166,7 @@

    API Reference

    Header File

    @@ -180,7 +180,7 @@

    ClassesPublic Functions

    -inline Gaussian(const Config &config)
    +inline explicit Gaussian(const Config &config)

    Construct the gaussian object, configuring its parameters.

    Parameters
    diff --git a/docs/math/index.html b/docs/math/index.html index bcd2d8c71..564229583 100644 --- a/docs/math/index.html +++ b/docs/math/index.html @@ -137,7 +137,7 @@
  • »
  • Math APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/math/range_mapper.html b/docs/math/range_mapper.html index a31a4662c..3a7ef66e4 100644 --- a/docs/math/range_mapper.html +++ b/docs/math/range_mapper.html @@ -145,7 +145,7 @@
  • Math APIs »
  • Range Mapper
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -182,7 +182,7 @@

    ClassesPublic Functions

    -inline RangeMapper(const Config &config)
    +inline explicit RangeMapper(const Config &config)

    Initialize the RangeMapper.

    Parameters
    diff --git a/docs/math/vector2d.html b/docs/math/vector2d.html index 105f60500..1abe91a79 100644 --- a/docs/math/vector2d.html +++ b/docs/math/vector2d.html @@ -145,7 +145,7 @@
  • Math APIs »
  • Vector2d
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -176,7 +176,7 @@

    ClassesPublic Functions

    -inline Vector2d(T x = T(0), T y = T(0))
    +inline explicit Vector2d(T x = T(0), T y = T(0))

    Constructor for the vector, defaults to 0,0.

    Parameters
    diff --git a/docs/monitor.html b/docs/monitor.html index c06095b18..c0c2405a4 100644 --- a/docs/monitor.html +++ b/docs/monitor.html @@ -138,7 +138,7 @@
  • »
  • Monitoring APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,7 +163,7 @@

    API Reference

    Header File

    diff --git a/docs/network/index.html b/docs/network/index.html index 4e752434b..1a998defa 100644 --- a/docs/network/index.html +++ b/docs/network/index.html @@ -135,7 +135,7 @@
  • »
  • Network APIs
  • - Edit on GitHub + Edit on GitHub

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

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

    API Reference

    Header File

    diff --git a/docs/network/tcp_socket.html b/docs/network/tcp_socket.html index 54999b63a..3f62a0189 100644 --- a/docs/network/tcp_socket.html +++ b/docs/network/tcp_socket.html @@ -143,7 +143,7 @@
  • Network APIs »
  • TCP Sockets
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -179,9 +179,8 @@

    TCP Client Example auto client_task_fn = [&server_address, &client_socket, &port](auto &, auto &) { static size_t iterations = 0; std::vector<uint8_t> data{0, 1, 2, 3, 4}; - for (auto &d : data) { - d += iterations; - } + std::transform(data.begin(), data.end(), data.begin(), + [](const auto &d) { return d + iterations; }); client_socket.transmit(data); iterations++; std::this_thread::sleep_for(1s); @@ -249,9 +248,8 @@

    TCP Client Response Example auto client_task_fn = [&server_address, &client_socket, &port](auto &, auto &) { static size_t iterations = 0; std::vector<uint8_t> data{0, 1, 2, 3, 4}; - for (auto &d : data) { - d += iterations; - } + std::transform(data.begin(), data.end(), data.begin(), + [](const auto &d) { return d + iterations; }); auto transmit_config = espp::detail::TcpTransmitConfig{ .wait_for_response = true, .response_size = 128, @@ -354,7 +352,7 @@

    TCP Server Response ExamplePublic Functions

    -inline TcpSocket(const Config &config)
    +inline explicit TcpSocket(const Config &config)

    Initialize the socket and associated resources.

    Note

    diff --git a/docs/network/udp_socket.html b/docs/network/udp_socket.html index b670c35cb..190f8a26e 100644 --- a/docs/network/udp_socket.html +++ b/docs/network/udp_socket.html @@ -143,7 +143,7 @@
  • Network APIs »
  • UDP Sockets
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -178,9 +178,8 @@

    UDP Client Exampleauto client_task_fn = [&server_address, &client_socket, &port](auto &, auto &) { static size_t iterations = 0; std::vector<uint8_t> data{0, 1, 2, 3, 4}; - for (auto &d : data) { - d += iterations; - } + std::transform(data.begin(), data.end(), data.begin(), + [](const auto &d) { return d + iterations; }); auto send_config = espp::UdpSocket::SendConfig{.ip_address = server_address, .port = port}; client_socket.send(data, send_config); iterations++; @@ -227,9 +226,8 @@

    UDP Client Response Exampleauto client_task_fn = [&server_address, &client_socket, &port](auto &, auto &) { static size_t iterations = 0; std::vector<uint8_t> data{0, 1, 2, 3, 4}; - for (auto &d : data) { - d += iterations; - } + std::transform(data.begin(), data.end(), data.begin(), + [](const auto &d) { return d + iterations; }); auto send_config = espp::UdpSocket::SendConfig{ .ip_address = server_address, .port = port, @@ -284,9 +282,8 @@

    UDP Multicast Client Exampleauto client_task_fn = [&client_socket, &port, &multicast_group](auto &, auto &) { static size_t iterations = 0; std::vector<uint8_t> data{0, 1, 2, 3, 4}; - for (auto &d : data) { - d += iterations; - } + std::transform(data.begin(), data.end(), data.begin(), + [](const auto &d) { return d + iterations; }); auto send_config = espp::UdpSocket::SendConfig{.ip_address = multicast_group, .port = port, .is_multicast_endpoint = true, @@ -375,7 +372,7 @@

    UDP Multicast Server ExamplePublic Functions

    -inline UdpSocket(const Config &config)
    +inline explicit UdpSocket(const Config &config)

    Initialize the socket and associated resources.

    Parameters
    diff --git a/docs/nfc/index.html b/docs/nfc/index.html index fdee8fc09..d8bb991a2 100644 --- a/docs/nfc/index.html +++ b/docs/nfc/index.html @@ -134,7 +134,7 @@
  • »
  • NFC APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/nfc/ndef.html b/docs/nfc/ndef.html index 6a876730d..214484644 100644 --- a/docs/nfc/ndef.html +++ b/docs/nfc/ndef.html @@ -143,7 +143,7 @@
  • NFC APIs »
  • NDEF
  • - Edit on GitHub + Edit on GitHub

  • @@ -160,7 +160,7 @@

    API Reference

    Header File

    @@ -909,7 +909,7 @@

    ClassesPublic Functions

    -inline Ndef(TNF tnf, std::string_view type, std::string_view payload)
    +inline explicit Ndef(TNF tnf, std::string_view type, std::string_view payload)

    Makes an NDEF record with header and payload.

    Parameters
    diff --git a/docs/nfc/st25dv.html b/docs/nfc/st25dv.html index 6a6b42623..7425513b9 100644 --- a/docs/nfc/st25dv.html +++ b/docs/nfc/st25dv.html @@ -142,7 +142,7 @@
  • NFC APIs »
  • ST25DV
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,7 +163,7 @@

    API Reference

    Header File

    @@ -339,7 +339,7 @@

    St25dv ExamplePublic Functions

    -inline St25dv(const Config &config)
    +inline explicit St25dv(const Config &config)

    Construct the St25dv and start the update task.

    @@ -478,7 +478,7 @@

    St25dv Example
    inline void start_fast_transfer_mode(std::error_code &ec)
    -

    Enable fast transfer mode (using up to 255 bytes at a time) between RF and I2C. After calling this, you can call transfer(), receive(), and get_ftm_length() for fast bi-directional communications between RF and I2C.

    +

    Enable fast transfer mode (using up to 255 bytes at a time) between RF and I2C. After calling this, you can call transfer(), receive(), and get_ftm_length() for fast bi-directional communications between RF and I2C.

    Note

    You must call stop_fast_transfer_mode() before calling any other functions on this class.

    @@ -493,7 +493,7 @@

    St25dv Example
    inline void stop_fast_transfer_mode(std::error_code &ec)
    -

    Disable fast transfer mode (using up to 255 bytes at a time) between RF and I2C. After calling this, you cannot call transfer() or receive() without again calling start_fast_transfer_mode() first.

    +

    Disable fast transfer mode (using up to 255 bytes at a time) between RF and I2C. After calling this, you cannot call transfer() or receive() without again calling start_fast_transfer_mode() first.

    Parameters

    &ec – Error code to be filled with any errors that occur during writing.

    @@ -517,8 +517,8 @@

    St25dv Example

    -
    -inline void transfer(uint8_t *data, uint8_t length, std::error_code &ec)
    +
    +inline void transfer(const uint8_t *data, uint8_t length, std::error_code &ec)

    Write data to the FTM message box to send.

    Note

    diff --git a/docs/objects.inv b/docs/objects.inv index 4a915cf70..36c691d6c 100644 Binary files a/docs/objects.inv and b/docs/objects.inv differ diff --git a/docs/pid.html b/docs/pid.html index c9c4d7146..1de17c45f 100644 --- a/docs/pid.html +++ b/docs/pid.html @@ -138,7 +138,7 @@
  • »
  • PID APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -160,7 +160,7 @@

    API Reference

    Header File

    @@ -232,7 +232,7 @@

    Complex PID ExamplePublic Functions

    -inline Pid(const Config &config)
    +inline explicit Pid(const Config &config)

    Create the PID controller.

    diff --git a/docs/qwiicnes.html b/docs/qwiicnes.html index b267c3620..cee9fe19d 100644 --- a/docs/qwiicnes.html +++ b/docs/qwiicnes.html @@ -139,7 +139,7 @@
  • »
  • QwiicNES
  • - Edit on GitHub + Edit on GitHub

  • @@ -155,14 +155,14 @@

    API Reference

    Header File

    Functions

    Warning

    -

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

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

    - bool operator==(const AdcConfig &lhs, const AdcConfig &rhs)
    diff --git a/docs/rmt.html b/docs/rmt.html
    index 3855492f6..cb10a3e6e 100644
    --- a/docs/rmt.html
    +++ b/docs/rmt.html
    @@ -139,7 +139,7 @@
           
  • »
  • Remote Control Transceiver (RMT)
  • - Edit on GitHub + Edit on GitHub

  • @@ -166,7 +166,7 @@

    API Reference

    Header File

    @@ -235,7 +235,7 @@

    Example 1: Transmitting dataPublic Functions

    -inline Rmt(const Config &config)
    +inline explicit Rmt(const Config &config)

    Constructor.

    Parameters
    @@ -330,7 +330,7 @@

    Example 1: Transmitting data

    Header File

    @@ -500,7 +500,7 @@

    Example 1: WS2812 encoderPublic Functions

    -inline RmtEncoder(const Config &config)
    +inline explicit RmtEncoder(const Config &config)

    Constructor.

    Parameters
    diff --git a/docs/rtc/bm8563.html b/docs/rtc/bm8563.html index 76738b45b..50d87ce3c 100644 --- a/docs/rtc/bm8563.html +++ b/docs/rtc/bm8563.html @@ -142,7 +142,7 @@
  • RTC APIs »
  • BM8563
  • - Edit on GitHub + Edit on GitHub

  • @@ -158,14 +158,14 @@

    API Reference

    Header File

    Functions

    Warning

    -

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

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

    - bool operator==(const AdcConfig &lhs, const AdcConfig &rhs)
    @@ -182,7 +182,7 @@ 

    Functions

    Warning

    -

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

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

    - bool operator==(const AdcConfig &lhs, const AdcConfig &rhs)
    @@ -199,7 +199,7 @@ 

    Functions

    Warning

    -

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

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

    - bool operator==(const AdcConfig &lhs, const AdcConfig &rhs)
    @@ -291,7 +291,7 @@ 

    ExamplePublic Types

    -typedef std::function<bool(uint8_t, uint8_t*, size_t)> write_fn
    +typedef std::function<bool(uint8_t, uint8_t*, size_t)> write_fn

    Function prototype for the I2C write function.

    Param address
    @@ -311,7 +311,7 @@

    Example
    -typedef std::function<bool(uint8_t, uint8_t, uint8_t*, size_t)> read_fn
    +typedef std::function<bool(uint8_t, uint8_t, uint8_t*, size_t)> read_fn

    Function prototype for the I2C read function.

    Param address
    @@ -358,8 +358,8 @@

    Example -
    -inline void set_date_time(DateTime &dt, std::error_code &ec)
    +
    +inline void set_date_time(const DateTime &dt, std::error_code &ec)

    Set the date and time.

    Parameters
    diff --git a/docs/rtc/index.html b/docs/rtc/index.html index 8333e613c..3998d616d 100644 --- a/docs/rtc/index.html +++ b/docs/rtc/index.html @@ -133,7 +133,7 @@
  • »
  • RTC APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/rtsp.html b/docs/rtsp.html index 812a18f72..b7705bc5e 100644 --- a/docs/rtsp.html +++ b/docs/rtsp.html @@ -153,7 +153,7 @@
  • »
  • RTSP APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -193,7 +193,7 @@

    API Reference

    Header File

    @@ -454,7 +454,7 @@

    Example

    Header File

    @@ -612,7 +612,7 @@

    example

    Header File

    @@ -769,7 +769,7 @@

    Classes

    Header File

    @@ -911,7 +911,7 @@

    Classes

    Header File

    @@ -1030,8 +1030,8 @@

    Classes
    -
    -inline std::string_view get_mjpeg_header()
    +
    +inline std::string_view get_mjpeg_header() const

    Get the mjepg header.

    Returns
    @@ -1210,7 +1210,7 @@

    Classes

    Header File

    @@ -1226,7 +1226,7 @@

    Classes

    Header File

    @@ -1313,7 +1313,7 @@

    Classes

    Header File

    diff --git a/docs/searchindex.js b/docs/searchindex.js index 784e2ef3e..fcebc9f20 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","adc/tla2528","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","i2c","index","input/encoder_input","input/ft5x06","input/gt911","input/index","input/keypad_input","input/t_keyboard","input/touchpad_input","input/tt21100","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","qwiicnes","rmt","rtc/bm8563","rtc/index","rtsp","serialization","state_machine","tabulate","task","thermistor","timer","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","adc/tla2528.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","i2c.rst","index.rst","input/encoder_input.rst","input/ft5x06.rst","input/gt911.rst","input/index.rst","input/keypad_input.rst","input/t_keyboard.rst","input/touchpad_input.rst","input/tt21100.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","qwiicnes.rst","rmt.rst","rtc/bm8563.rst","rtc/index.rst","rtsp.rst","serialization.rst","state_machine.rst","tabulate.rst","task.rst","thermistor.rst","timer.rst","wifi/index.rst","wifi/wifi_ap.rst","wifi/wifi_sta.rst"],objects:{"":[[74,0,1,"c.MAGIC_ENUM_NO_CHECK_SUPPORT","MAGIC_ENUM_NO_CHECK_SUPPORT"],[14,0,1,"c.__gnu_linux__","__gnu_linux__"],[73,0,1,"c.__gnu_linux__","__gnu_linux__"],[11,0,1,"c.__linux__","__linux__"],[75,0,1,"c.__unix__","__unix__"],[65,1,1,"_CPPv4N19PhonyNameDueToError3rawE","PhonyNameDueToError::raw"],[68,1,1,"_CPPv4N19PhonyNameDueToError3rawE","PhonyNameDueToError::raw"],[18,2,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoderE","espp::AbiEncoder"],[18,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder10AbiEncoderERK6Config","espp::AbiEncoder::AbiEncoder"],[18,4,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder10AbiEncoderERK6Config","espp::AbiEncoder::AbiEncoder::config"],[18,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder10AbiEncoderERK6Config","espp::AbiEncoder::AbiEncoder::type"],[18,2,1,"_CPPv4N4espp10AbiEncoder6ConfigE","espp::AbiEncoder::Config"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config6a_gpioE","espp::AbiEncoder::Config::a_gpio"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config6b_gpioE","espp::AbiEncoder::Config::b_gpio"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config21counts_per_revolutionE","espp::AbiEncoder::Config::counts_per_revolution"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config10high_limitE","espp::AbiEncoder::Config::high_limit"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config6i_gpioE","espp::AbiEncoder::Config::i_gpio"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config9log_levelE","espp::AbiEncoder::Config::log_level"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config9low_limitE","espp::AbiEncoder::Config::low_limit"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config13max_glitch_nsE","espp::AbiEncoder::Config::max_glitch_ns"],[18,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoderE","espp::AbiEncoder::T"],[18,3,1,"_CPPv4N4espp10AbiEncoder5clearEv","espp::AbiEncoder::clear"],[18,3,1,"_CPPv4N4espp10AbiEncoder9get_countEv","espp::AbiEncoder::get_count"],[18,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_degreesENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_degrees"],[18,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_degreesENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_degrees::type"],[18,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_radiansENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_radians"],[18,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_radiansENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_radians::type"],[18,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder15get_revolutionsENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_revolutions"],[18,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder15get_revolutionsENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_revolutions::type"],[18,3,1,"_CPPv4N4espp10AbiEncoder5startEv","espp::AbiEncoder::start"],[18,3,1,"_CPPv4N4espp10AbiEncoder4stopEv","espp::AbiEncoder::stop"],[18,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_mvEiRNSt10error_codeE","espp::Ads1x15::sample_mv"],[1,4,1,"_CPPv4N4espp7Ads1x159sample_mvEiRNSt10error_codeE","espp::Ads1x15::sample_mv::channel"],[1,4,1,"_CPPv4N4espp7Ads1x159sample_mvEiRNSt10error_codeE","espp::Ads1x15::sample_mv::ec"],[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,"_CPPv4N4espp7Ads71386Config9auto_initE","espp::Ads7138::Config::auto_init"],[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,"_CPPv4N4espp7Ads71386Config20digital_output_modesE","espp::Ads7138::Config::digital_output_modes"],[2,1,1,"_CPPv4N4espp7Ads71386Config21digital_output_valuesE","espp::Ads7138::Config::digital_output_values"],[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_tRNSt10error_codeE","espp::Ads7138::clear_event_high_flag"],[2,4,1,"_CPPv4N4espp7Ads713821clear_event_high_flagE7uint8_tRNSt10error_codeE","espp::Ads7138::clear_event_high_flag::ec"],[2,4,1,"_CPPv4N4espp7Ads713821clear_event_high_flagE7uint8_tRNSt10error_codeE","espp::Ads7138::clear_event_high_flag::flags"],[2,3,1,"_CPPv4N4espp7Ads713820clear_event_low_flagE7uint8_tRNSt10error_codeE","espp::Ads7138::clear_event_low_flag"],[2,4,1,"_CPPv4N4espp7Ads713820clear_event_low_flagE7uint8_tRNSt10error_codeE","espp::Ads7138::clear_event_low_flag::ec"],[2,4,1,"_CPPv4N4espp7Ads713820clear_event_low_flagE7uint8_tRNSt10error_codeE","espp::Ads7138::clear_event_low_flag::flags"],[2,3,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogicRNSt10error_codeE","espp::Ads7138::configure_alert"],[2,4,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogicRNSt10error_codeE","espp::Ads7138::configure_alert::alert_logic"],[2,4,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogicRNSt10error_codeE","espp::Ads7138::configure_alert::ec"],[2,4,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogicRNSt10error_codeE","espp::Ads7138::configure_alert::output_mode"],[2,3,1,"_CPPv4N4espp7Ads713810get_all_mvERNSt10error_codeE","espp::Ads7138::get_all_mv"],[2,4,1,"_CPPv4N4espp7Ads713810get_all_mvERNSt10error_codeE","espp::Ads7138::get_all_mv::ec"],[2,3,1,"_CPPv4N4espp7Ads713814get_all_mv_mapERNSt10error_codeE","espp::Ads7138::get_all_mv_map"],[2,4,1,"_CPPv4N4espp7Ads713814get_all_mv_mapERNSt10error_codeE","espp::Ads7138::get_all_mv_map::ec"],[2,3,1,"_CPPv4N4espp7Ads713823get_digital_input_valueE7ChannelRNSt10error_codeE","espp::Ads7138::get_digital_input_value"],[2,4,1,"_CPPv4N4espp7Ads713823get_digital_input_valueE7ChannelRNSt10error_codeE","espp::Ads7138::get_digital_input_value::channel"],[2,4,1,"_CPPv4N4espp7Ads713823get_digital_input_valueE7ChannelRNSt10error_codeE","espp::Ads7138::get_digital_input_value::ec"],[2,3,1,"_CPPv4N4espp7Ads713824get_digital_input_valuesERNSt10error_codeE","espp::Ads7138::get_digital_input_values"],[2,4,1,"_CPPv4N4espp7Ads713824get_digital_input_valuesERNSt10error_codeE","espp::Ads7138::get_digital_input_values::ec"],[2,3,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_tRNSt10error_codeE","espp::Ads7138::get_event_data"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_tRNSt10error_codeE","espp::Ads7138::get_event_data::ec"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_tRNSt10error_codeE","espp::Ads7138::get_event_data::event_flags"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_tRNSt10error_codeE","espp::Ads7138::get_event_data::event_high_flags"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_tRNSt10error_codeE","espp::Ads7138::get_event_data::event_low_flags"],[2,3,1,"_CPPv4N4espp7Ads713815get_event_flagsERNSt10error_codeE","espp::Ads7138::get_event_flags"],[2,4,1,"_CPPv4N4espp7Ads713815get_event_flagsERNSt10error_codeE","espp::Ads7138::get_event_flags::ec"],[2,3,1,"_CPPv4N4espp7Ads713819get_event_high_flagERNSt10error_codeE","espp::Ads7138::get_event_high_flag"],[2,4,1,"_CPPv4N4espp7Ads713819get_event_high_flagERNSt10error_codeE","espp::Ads7138::get_event_high_flag::ec"],[2,3,1,"_CPPv4N4espp7Ads713818get_event_low_flagERNSt10error_codeE","espp::Ads7138::get_event_low_flag"],[2,4,1,"_CPPv4N4espp7Ads713818get_event_low_flagERNSt10error_codeE","espp::Ads7138::get_event_low_flag::ec"],[2,3,1,"_CPPv4N4espp7Ads71386get_mvE7ChannelRNSt10error_codeE","espp::Ads7138::get_mv"],[2,4,1,"_CPPv4N4espp7Ads71386get_mvE7ChannelRNSt10error_codeE","espp::Ads7138::get_mv::channel"],[2,4,1,"_CPPv4N4espp7Ads71386get_mvE7ChannelRNSt10error_codeE","espp::Ads7138::get_mv::ec"],[2,3,1,"_CPPv4N4espp7Ads713810initializeERNSt10error_codeE","espp::Ads7138::initialize"],[2,4,1,"_CPPv4N4espp7Ads713810initializeERNSt10error_codeE","espp::Ads7138::initialize::ec"],[2,8,1,"_CPPv4N4espp7Ads71387read_fnE","espp::Ads7138::read_fn"],[2,3,1,"_CPPv4N4espp7Ads71385resetERNSt10error_codeE","espp::Ads7138::reset"],[2,4,1,"_CPPv4N4espp7Ads71385resetERNSt10error_codeE","espp::Ads7138::reset::ec"],[2,3,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert::channel"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert::ec"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert::event"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert::event_count"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert::high_threshold_mv"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert::low_threshold_mv"],[2,3,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEventRNSt10error_codeE","espp::Ads7138::set_digital_alert"],[2,4,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEventRNSt10error_codeE","espp::Ads7138::set_digital_alert::channel"],[2,4,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEventRNSt10error_codeE","espp::Ads7138::set_digital_alert::ec"],[2,4,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEventRNSt10error_codeE","espp::Ads7138::set_digital_alert::event"],[2,3,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Ads7138::set_digital_output_mode"],[2,4,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Ads7138::set_digital_output_mode::channel"],[2,4,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Ads7138::set_digital_output_mode::ec"],[2,4,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Ads7138::set_digital_output_mode::output_mode"],[2,3,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Ads7138::set_digital_output_value"],[2,4,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Ads7138::set_digital_output_value::channel"],[2,4,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Ads7138::set_digital_output_value::ec"],[2,4,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Ads7138::set_digital_output_value::value"],[2,8,1,"_CPPv4N4espp7Ads71388write_fnE","espp::Ads7138::write_fn"],[19,2,1,"_CPPv4N4espp6As5600E","espp::As5600"],[19,3,1,"_CPPv4N4espp6As56006As5600ERK6Config","espp::As5600::As5600"],[19,4,1,"_CPPv4N4espp6As56006As5600ERK6Config","espp::As5600::As5600::config"],[19,1,1,"_CPPv4N4espp6As560021COUNTS_PER_REVOLUTIONE","espp::As5600::COUNTS_PER_REVOLUTION"],[19,1,1,"_CPPv4N4espp6As560023COUNTS_PER_REVOLUTION_FE","espp::As5600::COUNTS_PER_REVOLUTION_F"],[19,1,1,"_CPPv4N4espp6As560017COUNTS_TO_DEGREESE","espp::As5600::COUNTS_TO_DEGREES"],[19,1,1,"_CPPv4N4espp6As560017COUNTS_TO_RADIANSE","espp::As5600::COUNTS_TO_RADIANS"],[19,2,1,"_CPPv4N4espp6As56006ConfigE","espp::As5600::Config"],[19,1,1,"_CPPv4N4espp6As56006Config9auto_initE","espp::As5600::Config::auto_init"],[19,1,1,"_CPPv4N4espp6As56006Config14device_addressE","espp::As5600::Config::device_address"],[19,1,1,"_CPPv4N4espp6As56006Config4readE","espp::As5600::Config::read"],[19,1,1,"_CPPv4N4espp6As56006Config13update_periodE","espp::As5600::Config::update_period"],[19,1,1,"_CPPv4N4espp6As56006Config15velocity_filterE","espp::As5600::Config::velocity_filter"],[19,1,1,"_CPPv4N4espp6As56006Config5writeE","espp::As5600::Config::write"],[19,1,1,"_CPPv4N4espp6As560015DEFAULT_ADDRESSE","espp::As5600::DEFAULT_ADDRESS"],[19,1,1,"_CPPv4N4espp6As560018SECONDS_PER_MINUTEE","espp::As5600::SECONDS_PER_MINUTE"],[19,3,1,"_CPPv4NK4espp6As560015get_accumulatorEv","espp::As5600::get_accumulator"],[19,3,1,"_CPPv4NK4espp6As56009get_countEv","espp::As5600::get_count"],[19,3,1,"_CPPv4NK4espp6As560011get_degreesEv","espp::As5600::get_degrees"],[19,3,1,"_CPPv4NK4espp6As560022get_mechanical_degreesEv","espp::As5600::get_mechanical_degrees"],[19,3,1,"_CPPv4NK4espp6As560022get_mechanical_radiansEv","espp::As5600::get_mechanical_radians"],[19,3,1,"_CPPv4NK4espp6As560011get_radiansEv","espp::As5600::get_radians"],[19,3,1,"_CPPv4NK4espp6As56007get_rpmEv","espp::As5600::get_rpm"],[19,3,1,"_CPPv4N4espp6As560010initializeERNSt10error_codeE","espp::As5600::initialize"],[19,4,1,"_CPPv4N4espp6As560010initializeERNSt10error_codeE","espp::As5600::initialize::ec"],[19,3,1,"_CPPv4NK4espp6As560017needs_zero_searchEv","espp::As5600::needs_zero_search"],[19,8,1,"_CPPv4N4espp6As56007read_fnE","espp::As5600::read_fn"],[19,8,1,"_CPPv4N4espp6As560018velocity_filter_fnE","espp::As5600::velocity_filter_fn"],[19,8,1,"_CPPv4N4espp6As56008write_fnE","espp::As5600::write_fn"],[46,2,1,"_CPPv4N4espp6Aw9523E","espp::Aw9523"],[46,3,1,"_CPPv4N4espp6Aw95236Aw9523ERK6Config","espp::Aw9523::Aw9523"],[46,4,1,"_CPPv4N4espp6Aw95236Aw9523ERK6Config","espp::Aw9523::Aw9523::config"],[46,2,1,"_CPPv4N4espp6Aw95236ConfigE","espp::Aw9523::Config"],[46,1,1,"_CPPv4N4espp6Aw95236Config9auto_initE","espp::Aw9523::Config::auto_init"],[46,1,1,"_CPPv4N4espp6Aw95236Config14device_addressE","espp::Aw9523::Config::device_address"],[46,1,1,"_CPPv4N4espp6Aw95236Config9log_levelE","espp::Aw9523::Config::log_level"],[46,1,1,"_CPPv4N4espp6Aw95236Config15max_led_currentE","espp::Aw9523::Config::max_led_current"],[46,1,1,"_CPPv4N4espp6Aw95236Config20output_drive_mode_p0E","espp::Aw9523::Config::output_drive_mode_p0"],[46,1,1,"_CPPv4N4espp6Aw95236Config21port_0_direction_maskE","espp::Aw9523::Config::port_0_direction_mask"],[46,1,1,"_CPPv4N4espp6Aw95236Config21port_0_interrupt_maskE","espp::Aw9523::Config::port_0_interrupt_mask"],[46,1,1,"_CPPv4N4espp6Aw95236Config21port_1_direction_maskE","espp::Aw9523::Config::port_1_direction_mask"],[46,1,1,"_CPPv4N4espp6Aw95236Config21port_1_interrupt_maskE","espp::Aw9523::Config::port_1_interrupt_mask"],[46,1,1,"_CPPv4N4espp6Aw95236Config4readE","espp::Aw9523::Config::read"],[46,1,1,"_CPPv4N4espp6Aw95236Config5writeE","espp::Aw9523::Config::write"],[46,1,1,"_CPPv4N4espp6Aw952315DEFAULT_ADDRESSE","espp::Aw9523::DEFAULT_ADDRESS"],[46,6,1,"_CPPv4N4espp6Aw952313MaxLedCurrentE","espp::Aw9523::MaxLedCurrent"],[46,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent4IMAXE","espp::Aw9523::MaxLedCurrent::IMAX"],[46,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent7IMAX_25E","espp::Aw9523::MaxLedCurrent::IMAX_25"],[46,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent7IMAX_50E","espp::Aw9523::MaxLedCurrent::IMAX_50"],[46,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent7IMAX_75E","espp::Aw9523::MaxLedCurrent::IMAX_75"],[46,6,1,"_CPPv4N4espp6Aw952317OutputDriveModeP0E","espp::Aw9523::OutputDriveModeP0"],[46,7,1,"_CPPv4N4espp6Aw952317OutputDriveModeP010OPEN_DRAINE","espp::Aw9523::OutputDriveModeP0::OPEN_DRAIN"],[46,7,1,"_CPPv4N4espp6Aw952317OutputDriveModeP09PUSH_PULLE","espp::Aw9523::OutputDriveModeP0::PUSH_PULL"],[46,6,1,"_CPPv4N4espp6Aw95234PortE","espp::Aw9523::Port"],[46,7,1,"_CPPv4N4espp6Aw95234Port5PORT0E","espp::Aw9523::Port::PORT0"],[46,7,1,"_CPPv4N4espp6Aw95234Port5PORT1E","espp::Aw9523::Port::PORT1"],[46,3,1,"_CPPv4N4espp6Aw952310clear_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins"],[46,3,1,"_CPPv4N4espp6Aw952310clear_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins"],[46,3,1,"_CPPv4N4espp6Aw952310clear_pinsE8uint16_tRNSt10error_codeE","espp::Aw9523::clear_pins"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE8uint16_tRNSt10error_codeE","espp::Aw9523::clear_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins::mask"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE8uint16_tRNSt10error_codeE","espp::Aw9523::clear_pins::mask"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins::p0"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins::p1"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins::port"],[46,3,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrentRNSt10error_codeE","espp::Aw9523::configure_global_control"],[46,4,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrentRNSt10error_codeE","espp::Aw9523::configure_global_control::ec"],[46,4,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrentRNSt10error_codeE","espp::Aw9523::configure_global_control::max_led_current"],[46,4,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrentRNSt10error_codeE","espp::Aw9523::configure_global_control::output_drive_mode_p0"],[46,3,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led"],[46,3,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led"],[46,3,1,"_CPPv4N4espp6Aw952313configure_ledE8uint16_tRNSt10error_codeE","espp::Aw9523::configure_led"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led::ec"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led::ec"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE8uint16_tRNSt10error_codeE","espp::Aw9523::configure_led::ec"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led::mask"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE8uint16_tRNSt10error_codeE","espp::Aw9523::configure_led::mask"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led::p0"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led::p1"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led::port"],[46,3,1,"_CPPv4N4espp6Aw952310get_outputE4PortRNSt10error_codeE","espp::Aw9523::get_output"],[46,3,1,"_CPPv4N4espp6Aw952310get_outputERNSt10error_codeE","espp::Aw9523::get_output"],[46,4,1,"_CPPv4N4espp6Aw952310get_outputE4PortRNSt10error_codeE","espp::Aw9523::get_output::ec"],[46,4,1,"_CPPv4N4espp6Aw952310get_outputERNSt10error_codeE","espp::Aw9523::get_output::ec"],[46,4,1,"_CPPv4N4espp6Aw952310get_outputE4PortRNSt10error_codeE","espp::Aw9523::get_output::port"],[46,3,1,"_CPPv4N4espp6Aw95238get_pinsE4PortRNSt10error_codeE","espp::Aw9523::get_pins"],[46,3,1,"_CPPv4N4espp6Aw95238get_pinsERNSt10error_codeE","espp::Aw9523::get_pins"],[46,4,1,"_CPPv4N4espp6Aw95238get_pinsE4PortRNSt10error_codeE","espp::Aw9523::get_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw95238get_pinsERNSt10error_codeE","espp::Aw9523::get_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw95238get_pinsE4PortRNSt10error_codeE","espp::Aw9523::get_pins::port"],[46,3,1,"_CPPv4N4espp6Aw952310initializeERNSt10error_codeE","espp::Aw9523::initialize"],[46,4,1,"_CPPv4N4espp6Aw952310initializeERNSt10error_codeE","espp::Aw9523::initialize::ec"],[46,3,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_tRNSt10error_codeE","espp::Aw9523::led"],[46,4,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_tRNSt10error_codeE","espp::Aw9523::led::brightness"],[46,4,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_tRNSt10error_codeE","espp::Aw9523::led::ec"],[46,4,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_tRNSt10error_codeE","espp::Aw9523::led::pin"],[46,3,1,"_CPPv4N4espp6Aw95236outputE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::output"],[46,3,1,"_CPPv4N4espp6Aw95236outputE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::output"],[46,3,1,"_CPPv4N4espp6Aw95236outputE8uint16_tRNSt10error_codeE","espp::Aw9523::output"],[46,4,1,"_CPPv4N4espp6Aw95236outputE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::output::ec"],[46,4,1,"_CPPv4N4espp6Aw95236outputE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::output::ec"],[46,4,1,"_CPPv4N4espp6Aw95236outputE8uint16_tRNSt10error_codeE","espp::Aw9523::output::ec"],[46,4,1,"_CPPv4N4espp6Aw95236outputE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::output::p0"],[46,4,1,"_CPPv4N4espp6Aw95236outputE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::output::p1"],[46,4,1,"_CPPv4N4espp6Aw95236outputE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::output::port"],[46,4,1,"_CPPv4N4espp6Aw95236outputE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::output::value"],[46,4,1,"_CPPv4N4espp6Aw95236outputE8uint16_tRNSt10error_codeE","espp::Aw9523::output::value"],[46,8,1,"_CPPv4N4espp6Aw95237read_fnE","espp::Aw9523::read_fn"],[46,3,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction"],[46,3,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction"],[46,4,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction::ec"],[46,4,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction::ec"],[46,4,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction::mask"],[46,4,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction::p0"],[46,4,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction::p1"],[46,4,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction::port"],[46,3,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt"],[46,3,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt"],[46,4,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt::ec"],[46,4,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt::ec"],[46,4,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt::mask"],[46,4,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt::p0"],[46,4,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt::p1"],[46,4,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt::port"],[46,3,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins"],[46,3,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins"],[46,3,1,"_CPPv4N4espp6Aw95238set_pinsE8uint16_tRNSt10error_codeE","espp::Aw9523::set_pins"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE8uint16_tRNSt10error_codeE","espp::Aw9523::set_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins::mask"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE8uint16_tRNSt10error_codeE","espp::Aw9523::set_pins::mask"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins::p0"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins::p1"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins::port"],[46,8,1,"_CPPv4N4espp6Aw95238write_fnE","espp::Aw9523::write_fn"],[53,2,1,"_CPPv4I0EN4espp6BezierE","espp::Bezier"],[53,3,1,"_CPPv4N4espp6Bezier6BezierERK14WeightedConfig","espp::Bezier::Bezier"],[53,3,1,"_CPPv4N4espp6Bezier6BezierERK6Config","espp::Bezier::Bezier"],[53,4,1,"_CPPv4N4espp6Bezier6BezierERK14WeightedConfig","espp::Bezier::Bezier::config"],[53,4,1,"_CPPv4N4espp6Bezier6BezierERK6Config","espp::Bezier::Bezier::config"],[53,2,1,"_CPPv4N4espp6Bezier6ConfigE","espp::Bezier::Config"],[53,1,1,"_CPPv4N4espp6Bezier6Config14control_pointsE","espp::Bezier::Config::control_points"],[53,5,1,"_CPPv4I0EN4espp6BezierE","espp::Bezier::T"],[53,2,1,"_CPPv4N4espp6Bezier14WeightedConfigE","espp::Bezier::WeightedConfig"],[53,1,1,"_CPPv4N4espp6Bezier14WeightedConfig14control_pointsE","espp::Bezier::WeightedConfig::control_points"],[53,1,1,"_CPPv4N4espp6Bezier14WeightedConfig7weightsE","espp::Bezier::WeightedConfig::weights"],[53,3,1,"_CPPv4NK4espp6Bezier2atEf","espp::Bezier::at"],[53,4,1,"_CPPv4NK4espp6Bezier2atEf","espp::Bezier::at::t"],[53,3,1,"_CPPv4NK4espp6BezierclEf","espp::Bezier::operator()"],[53,4,1,"_CPPv4NK4espp6BezierclEf","espp::Bezier::operator()::t"],[25,2,1,"_CPPv4N4espp15BiquadFilterDf1E","espp::BiquadFilterDf1"],[25,3,1,"_CPPv4N4espp15BiquadFilterDf16updateEf","espp::BiquadFilterDf1::update"],[25,4,1,"_CPPv4N4espp15BiquadFilterDf16updateEf","espp::BiquadFilterDf1::update::input"],[25,2,1,"_CPPv4N4espp15BiquadFilterDf2E","espp::BiquadFilterDf2"],[25,3,1,"_CPPv4N4espp15BiquadFilterDf26updateEKf","espp::BiquadFilterDf2::update"],[25,3,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update"],[25,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEKf","espp::BiquadFilterDf2::update::input"],[25,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update::input"],[25,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update::length"],[25,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update::output"],[7,2,1,"_CPPv4N4espp10BldcDriverE","espp::BldcDriver"],[7,3,1,"_CPPv4N4espp10BldcDriver10BldcDriverERK6Config","espp::BldcDriver::BldcDriver"],[7,4,1,"_CPPv4N4espp10BldcDriver10BldcDriverERK6Config","espp::BldcDriver::BldcDriver::config"],[7,2,1,"_CPPv4N4espp10BldcDriver6ConfigE","espp::BldcDriver::Config"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config9dead_zoneE","espp::BldcDriver::Config::dead_zone"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_a_hE","espp::BldcDriver::Config::gpio_a_h"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_a_lE","espp::BldcDriver::Config::gpio_a_l"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_b_hE","espp::BldcDriver::Config::gpio_b_h"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_b_lE","espp::BldcDriver::Config::gpio_b_l"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_c_hE","espp::BldcDriver::Config::gpio_c_h"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_c_lE","espp::BldcDriver::Config::gpio_c_l"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config11gpio_enableE","espp::BldcDriver::Config::gpio_enable"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config10gpio_faultE","espp::BldcDriver::Config::gpio_fault"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config13limit_voltageE","espp::BldcDriver::Config::limit_voltage"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config9log_levelE","espp::BldcDriver::Config::log_level"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config20power_supply_voltageE","espp::BldcDriver::Config::power_supply_voltage"],[7,3,1,"_CPPv4N4espp10BldcDriver15configure_powerEff","espp::BldcDriver::configure_power"],[7,4,1,"_CPPv4N4espp10BldcDriver15configure_powerEff","espp::BldcDriver::configure_power::power_supply_voltage"],[7,4,1,"_CPPv4N4espp10BldcDriver15configure_powerEff","espp::BldcDriver::configure_power::voltage_limit"],[7,3,1,"_CPPv4N4espp10BldcDriver7disableEv","espp::BldcDriver::disable"],[7,3,1,"_CPPv4N4espp10BldcDriver6enableEv","espp::BldcDriver::enable"],[7,3,1,"_CPPv4NK4espp10BldcDriver22get_power_supply_limitEv","espp::BldcDriver::get_power_supply_limit"],[7,3,1,"_CPPv4NK4espp10BldcDriver17get_voltage_limitEv","espp::BldcDriver::get_voltage_limit"],[7,3,1,"_CPPv4NK4espp10BldcDriver10is_enabledEv","espp::BldcDriver::is_enabled"],[7,3,1,"_CPPv4N4espp10BldcDriver10is_faultedEv","espp::BldcDriver::is_faulted"],[7,3,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state"],[7,4,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state::state_a"],[7,4,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state::state_b"],[7,4,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state::state_c"],[7,3,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm"],[7,4,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm::duty_a"],[7,4,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm::duty_b"],[7,4,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm::duty_c"],[7,3,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage"],[7,4,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage::ua"],[7,4,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage::ub"],[7,4,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage::uc"],[7,3,1,"_CPPv4N4espp10BldcDriverD0Ev","espp::BldcDriver::~BldcDriver"],[33,2,1,"_CPPv4I_12MotorConceptEN4espp11BldcHapticsE","espp::BldcHaptics"],[33,3,1,"_CPPv4N4espp11BldcHaptics11BldcHapticsERK6Config","espp::BldcHaptics::BldcHaptics"],[33,4,1,"_CPPv4N4espp11BldcHaptics11BldcHapticsERK6Config","espp::BldcHaptics::BldcHaptics::config"],[33,2,1,"_CPPv4N4espp11BldcHaptics6ConfigE","espp::BldcHaptics::Config"],[33,1,1,"_CPPv4N4espp11BldcHaptics6Config13kd_factor_maxE","espp::BldcHaptics::Config::kd_factor_max"],[33,1,1,"_CPPv4N4espp11BldcHaptics6Config13kd_factor_minE","espp::BldcHaptics::Config::kd_factor_min"],[33,1,1,"_CPPv4N4espp11BldcHaptics6Config9kp_factorE","espp::BldcHaptics::Config::kp_factor"],[33,1,1,"_CPPv4N4espp11BldcHaptics6Config9log_levelE","espp::BldcHaptics::Config::log_level"],[33,1,1,"_CPPv4N4espp11BldcHaptics6Config5motorE","espp::BldcHaptics::Config::motor"],[33,5,1,"_CPPv4I_12MotorConceptEN4espp11BldcHapticsE","espp::BldcHaptics::M"],[33,3,1,"_CPPv4NK4espp11BldcHaptics12get_positionEv","espp::BldcHaptics::get_position"],[33,3,1,"_CPPv4NK4espp11BldcHaptics10is_runningEv","espp::BldcHaptics::is_running"],[33,3,1,"_CPPv4N4espp11BldcHaptics11play_hapticERKN6detail12HapticConfigE","espp::BldcHaptics::play_haptic"],[33,4,1,"_CPPv4N4espp11BldcHaptics11play_hapticERKN6detail12HapticConfigE","espp::BldcHaptics::play_haptic::config"],[33,3,1,"_CPPv4N4espp11BldcHaptics5startEv","espp::BldcHaptics::start"],[33,3,1,"_CPPv4N4espp11BldcHaptics4stopEv","espp::BldcHaptics::stop"],[33,3,1,"_CPPv4N4espp11BldcHaptics20update_detent_configERKN6detail12DetentConfigE","espp::BldcHaptics::update_detent_config"],[33,4,1,"_CPPv4N4espp11BldcHaptics20update_detent_configERKN6detail12DetentConfigE","espp::BldcHaptics::update_detent_config::config"],[33,3,1,"_CPPv4N4espp11BldcHapticsD0Ev","espp::BldcHaptics::~BldcHaptics"],[8,2,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor"],[8,3,1,"_CPPv4N4espp9BldcMotor9BldcMotorERK6Config","espp::BldcMotor::BldcMotor"],[8,4,1,"_CPPv4N4espp9BldcMotor9BldcMotorERK6Config","espp::BldcMotor::BldcMotor::config"],[8,5,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor::CS"],[8,2,1,"_CPPv4N4espp9BldcMotor6ConfigE","espp::BldcMotor::Config"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config12angle_filterE","espp::BldcMotor::Config::angle_filter"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config13current_limitE","espp::BldcMotor::Config::current_limit"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config13current_senseE","espp::BldcMotor::Config::current_sense"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config16d_current_filterE","espp::BldcMotor::Config::d_current_filter"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config6driverE","espp::BldcMotor::Config::driver"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config8foc_typeE","espp::BldcMotor::Config::foc_type"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config9kv_ratingE","espp::BldcMotor::Config::kv_rating"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config9log_levelE","espp::BldcMotor::Config::log_level"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config14num_pole_pairsE","espp::BldcMotor::Config::num_pole_pairs"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config16phase_inductanceE","espp::BldcMotor::Config::phase_inductance"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config16phase_resistanceE","espp::BldcMotor::Config::phase_resistance"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config16q_current_filterE","espp::BldcMotor::Config::q_current_filter"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config6sensorE","espp::BldcMotor::Config::sensor"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config17torque_controllerE","espp::BldcMotor::Config::torque_controller"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config15velocity_filterE","espp::BldcMotor::Config::velocity_filter"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config14velocity_limitE","espp::BldcMotor::Config::velocity_limit"],[8,5,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor::D"],[8,5,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor::S"],[8,3,1,"_CPPv4N4espp9BldcMotor7disableEv","espp::BldcMotor::disable"],[8,3,1,"_CPPv4N4espp9BldcMotor6enableEv","espp::BldcMotor::enable"],[8,8,1,"_CPPv4N4espp9BldcMotor9filter_fnE","espp::BldcMotor::filter_fn"],[8,3,1,"_CPPv4N4espp9BldcMotor20get_electrical_angleEv","espp::BldcMotor::get_electrical_angle"],[8,3,1,"_CPPv4N4espp9BldcMotor15get_shaft_angleEv","espp::BldcMotor::get_shaft_angle"],[8,3,1,"_CPPv4N4espp9BldcMotor18get_shaft_velocityEv","espp::BldcMotor::get_shaft_velocity"],[8,3,1,"_CPPv4NK4espp9BldcMotor10is_enabledEv","espp::BldcMotor::is_enabled"],[8,3,1,"_CPPv4N4espp9BldcMotor8loop_focEv","espp::BldcMotor::loop_foc"],[8,3,1,"_CPPv4N4espp9BldcMotor4moveEf","espp::BldcMotor::move"],[8,4,1,"_CPPv4N4espp9BldcMotor4moveEf","espp::BldcMotor::move::new_target"],[8,3,1,"_CPPv4N4espp9BldcMotor23set_motion_control_typeEN6detail17MotionControlTypeE","espp::BldcMotor::set_motion_control_type"],[8,4,1,"_CPPv4N4espp9BldcMotor23set_motion_control_typeEN6detail17MotionControlTypeE","espp::BldcMotor::set_motion_control_type::motion_control_type"],[8,3,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage"],[8,4,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage::el_angle"],[8,4,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage::ud"],[8,4,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage::uq"],[8,3,1,"_CPPv4N4espp9BldcMotorD0Ev","espp::BldcMotor::~BldcMotor"],[70,2,1,"_CPPv4N4espp6Bm8563E","espp::Bm8563"],[70,3,1,"_CPPv4N4espp6Bm85636Bm8563ERK6Config","espp::Bm8563::Bm8563"],[70,4,1,"_CPPv4N4espp6Bm85636Bm8563ERK6Config","espp::Bm8563::Bm8563::config"],[70,2,1,"_CPPv4N4espp6Bm85636ConfigE","espp::Bm8563::Config"],[70,1,1,"_CPPv4N4espp6Bm85636Config9log_levelE","espp::Bm8563::Config::log_level"],[70,1,1,"_CPPv4N4espp6Bm85636Config4readE","espp::Bm8563::Config::read"],[70,1,1,"_CPPv4N4espp6Bm85636Config5writeE","espp::Bm8563::Config::write"],[70,1,1,"_CPPv4N4espp6Bm856315DEFAULT_ADDRESSE","espp::Bm8563::DEFAULT_ADDRESS"],[70,2,1,"_CPPv4N4espp6Bm85634DateE","espp::Bm8563::Date"],[70,1,1,"_CPPv4N4espp6Bm85634Date3dayE","espp::Bm8563::Date::day"],[70,1,1,"_CPPv4N4espp6Bm85634Date5monthE","espp::Bm8563::Date::month"],[70,1,1,"_CPPv4N4espp6Bm85634Date7weekdayE","espp::Bm8563::Date::weekday"],[70,1,1,"_CPPv4N4espp6Bm85634Date4yearE","espp::Bm8563::Date::year"],[70,2,1,"_CPPv4N4espp6Bm85638DateTimeE","espp::Bm8563::DateTime"],[70,1,1,"_CPPv4N4espp6Bm85638DateTime4dateE","espp::Bm8563::DateTime::date"],[70,1,1,"_CPPv4N4espp6Bm85638DateTime4timeE","espp::Bm8563::DateTime::time"],[70,2,1,"_CPPv4N4espp6Bm85634TimeE","espp::Bm8563::Time"],[70,1,1,"_CPPv4N4espp6Bm85634Time4hourE","espp::Bm8563::Time::hour"],[70,1,1,"_CPPv4N4espp6Bm85634Time6minuteE","espp::Bm8563::Time::minute"],[70,1,1,"_CPPv4N4espp6Bm85634Time6secondE","espp::Bm8563::Time::second"],[70,3,1,"_CPPv4N4espp6Bm85638bcd2byteE7uint8_t","espp::Bm8563::bcd2byte"],[70,4,1,"_CPPv4N4espp6Bm85638bcd2byteE7uint8_t","espp::Bm8563::bcd2byte::value"],[70,3,1,"_CPPv4N4espp6Bm85638byte2bcdE7uint8_t","espp::Bm8563::byte2bcd"],[70,4,1,"_CPPv4N4espp6Bm85638byte2bcdE7uint8_t","espp::Bm8563::byte2bcd::value"],[70,3,1,"_CPPv4N4espp6Bm85638get_dateERNSt10error_codeE","espp::Bm8563::get_date"],[70,4,1,"_CPPv4N4espp6Bm85638get_dateERNSt10error_codeE","espp::Bm8563::get_date::ec"],[70,3,1,"_CPPv4N4espp6Bm856313get_date_timeERNSt10error_codeE","espp::Bm8563::get_date_time"],[70,4,1,"_CPPv4N4espp6Bm856313get_date_timeERNSt10error_codeE","espp::Bm8563::get_date_time::ec"],[70,3,1,"_CPPv4N4espp6Bm85638get_timeERNSt10error_codeE","espp::Bm8563::get_time"],[70,4,1,"_CPPv4N4espp6Bm85638get_timeERNSt10error_codeE","espp::Bm8563::get_time::ec"],[70,8,1,"_CPPv4N4espp6Bm85637read_fnE","espp::Bm8563::read_fn"],[70,3,1,"_CPPv4N4espp6Bm85638set_dateERK4DateRNSt10error_codeE","espp::Bm8563::set_date"],[70,4,1,"_CPPv4N4espp6Bm85638set_dateERK4DateRNSt10error_codeE","espp::Bm8563::set_date::d"],[70,4,1,"_CPPv4N4espp6Bm85638set_dateERK4DateRNSt10error_codeE","espp::Bm8563::set_date::ec"],[70,3,1,"_CPPv4N4espp6Bm856313set_date_timeER8DateTimeRNSt10error_codeE","espp::Bm8563::set_date_time"],[70,4,1,"_CPPv4N4espp6Bm856313set_date_timeER8DateTimeRNSt10error_codeE","espp::Bm8563::set_date_time::dt"],[70,4,1,"_CPPv4N4espp6Bm856313set_date_timeER8DateTimeRNSt10error_codeE","espp::Bm8563::set_date_time::ec"],[70,3,1,"_CPPv4N4espp6Bm85638set_timeERK4TimeRNSt10error_codeE","espp::Bm8563::set_time"],[70,4,1,"_CPPv4N4espp6Bm85638set_timeERK4TimeRNSt10error_codeE","espp::Bm8563::set_time::ec"],[70,4,1,"_CPPv4N4espp6Bm85638set_timeERK4TimeRNSt10error_codeE","espp::Bm8563::set_time::t"],[70,8,1,"_CPPv4N4espp6Bm85638write_fnE","espp::Bm8563::write_fn"],[26,2,1,"_CPPv4I_6size_t0EN4espp17ButterworthFilterE","espp::ButterworthFilter"],[26,3,1,"_CPPv4N4espp17ButterworthFilter17ButterworthFilterERK6Config","espp::ButterworthFilter::ButterworthFilter"],[26,4,1,"_CPPv4N4espp17ButterworthFilter17ButterworthFilterERK6Config","espp::ButterworthFilter::ButterworthFilter::config"],[26,2,1,"_CPPv4N4espp17ButterworthFilter6ConfigE","espp::ButterworthFilter::Config"],[26,1,1,"_CPPv4N4espp17ButterworthFilter6Config27normalized_cutoff_frequencyE","espp::ButterworthFilter::Config::normalized_cutoff_frequency"],[26,5,1,"_CPPv4I_6size_t0EN4espp17ButterworthFilterE","espp::ButterworthFilter::Impl"],[26,5,1,"_CPPv4I_6size_t0EN4espp17ButterworthFilterE","espp::ButterworthFilter::ORDER"],[26,3,1,"_CPPv4N4espp17ButterworthFilterclEf","espp::ButterworthFilter::operator()"],[26,4,1,"_CPPv4N4espp17ButterworthFilterclEf","espp::ButterworthFilter::operator()::input"],[26,3,1,"_CPPv4N4espp17ButterworthFilter6updateEf","espp::ButterworthFilter::update"],[26,4,1,"_CPPv4N4espp17ButterworthFilter6updateEf","espp::ButterworthFilter::update::input"],[10,2,1,"_CPPv4N4espp6ButtonE","espp::Button"],[10,6,1,"_CPPv4N4espp6Button11ActiveLevelE","espp::Button::ActiveLevel"],[10,7,1,"_CPPv4N4espp6Button11ActiveLevel4HIGHE","espp::Button::ActiveLevel::HIGH"],[10,7,1,"_CPPv4N4espp6Button11ActiveLevel3LOWE","espp::Button::ActiveLevel::LOW"],[10,3,1,"_CPPv4N4espp6Button6ButtonERK6Config","espp::Button::Button"],[10,4,1,"_CPPv4N4espp6Button6ButtonERK6Config","espp::Button::Button::config"],[10,2,1,"_CPPv4N4espp6Button6ConfigE","espp::Button::Config"],[10,1,1,"_CPPv4N4espp6Button6Config12active_levelE","espp::Button::Config::active_level"],[10,1,1,"_CPPv4N4espp6Button6Config8callbackE","espp::Button::Config::callback"],[10,1,1,"_CPPv4N4espp6Button6Config7core_idE","espp::Button::Config::core_id"],[10,1,1,"_CPPv4N4espp6Button6Config8gpio_numE","espp::Button::Config::gpio_num"],[10,1,1,"_CPPv4N4espp6Button6Config14interrupt_typeE","espp::Button::Config::interrupt_type"],[10,1,1,"_CPPv4N4espp6Button6Config9log_levelE","espp::Button::Config::log_level"],[10,1,1,"_CPPv4N4espp6Button6Config4nameE","espp::Button::Config::name"],[10,1,1,"_CPPv4N4espp6Button6Config8priorityE","espp::Button::Config::priority"],[10,1,1,"_CPPv4N4espp6Button6Config16pulldown_enabledE","espp::Button::Config::pulldown_enabled"],[10,1,1,"_CPPv4N4espp6Button6Config14pullup_enabledE","espp::Button::Config::pullup_enabled"],[10,1,1,"_CPPv4N4espp6Button6Config21task_stack_size_bytesE","espp::Button::Config::task_stack_size_bytes"],[10,2,1,"_CPPv4N4espp6Button5EventE","espp::Button::Event"],[10,1,1,"_CPPv4N4espp6Button5Event8gpio_numE","espp::Button::Event::gpio_num"],[10,1,1,"_CPPv4N4espp6Button5Event7pressedE","espp::Button::Event::pressed"],[10,6,1,"_CPPv4N4espp6Button13InterruptTypeE","espp::Button::InterruptType"],[10,7,1,"_CPPv4N4espp6Button13InterruptType8ANY_EDGEE","espp::Button::InterruptType::ANY_EDGE"],[10,7,1,"_CPPv4N4espp6Button13InterruptType12FALLING_EDGEE","espp::Button::InterruptType::FALLING_EDGE"],[10,7,1,"_CPPv4N4espp6Button13InterruptType10HIGH_LEVELE","espp::Button::InterruptType::HIGH_LEVEL"],[10,7,1,"_CPPv4N4espp6Button13InterruptType9LOW_LEVELE","espp::Button::InterruptType::LOW_LEVEL"],[10,7,1,"_CPPv4N4espp6Button13InterruptType11RISING_EDGEE","espp::Button::InterruptType::RISING_EDGE"],[10,8,1,"_CPPv4N4espp6Button17event_callback_fnE","espp::Button::event_callback_fn"],[10,3,1,"_CPPv4NK4espp6Button10is_pressedEv","espp::Button::is_pressed"],[10,3,1,"_CPPv4N4espp6ButtonD0Ev","espp::Button::~Button"],[11,2,1,"_CPPv4N4espp3CliE","espp::Cli"],[11,3,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli"],[11,4,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli::_cli"],[11,4,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli::_in"],[11,4,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli::_out"],[11,3,1,"_CPPv4NK4espp3Cli15GetInputHistoryEv","espp::Cli::GetInputHistory"],[11,3,1,"_CPPv4N4espp3Cli15SetHandleResizeEb","espp::Cli::SetHandleResize"],[11,4,1,"_CPPv4N4espp3Cli15SetHandleResizeEb","espp::Cli::SetHandleResize::handle_resize"],[11,3,1,"_CPPv4N4espp3Cli15SetInputHistoryERKN9LineInput7HistoryE","espp::Cli::SetInputHistory"],[11,4,1,"_CPPv4N4espp3Cli15SetInputHistoryERKN9LineInput7HistoryE","espp::Cli::SetInputHistory::history"],[11,3,1,"_CPPv4N4espp3Cli19SetInputHistorySizeE6size_t","espp::Cli::SetInputHistorySize"],[11,4,1,"_CPPv4N4espp3Cli19SetInputHistorySizeE6size_t","espp::Cli::SetInputHistorySize::history_size"],[11,3,1,"_CPPv4N4espp3Cli5StartEv","espp::Cli::Start"],[11,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"],[13,2,1,"_CPPv4N4espp10ControllerE","espp::Controller"],[13,2,1,"_CPPv4N4espp10Controller20AnalogJoystickConfigE","espp::Controller::AnalogJoystickConfig"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig10active_lowE","espp::Controller::AnalogJoystickConfig::active_low"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_aE","espp::Controller::AnalogJoystickConfig::gpio_a"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_bE","espp::Controller::AnalogJoystickConfig::gpio_b"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig20gpio_joystick_selectE","espp::Controller::AnalogJoystickConfig::gpio_joystick_select"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig11gpio_selectE","espp::Controller::AnalogJoystickConfig::gpio_select"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig10gpio_startE","espp::Controller::AnalogJoystickConfig::gpio_start"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_xE","espp::Controller::AnalogJoystickConfig::gpio_x"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_yE","espp::Controller::AnalogJoystickConfig::gpio_y"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig15joystick_configE","espp::Controller::AnalogJoystickConfig::joystick_config"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig9log_levelE","espp::Controller::AnalogJoystickConfig::log_level"],[13,6,1,"_CPPv4N4espp10Controller6ButtonE","espp::Controller::Button"],[13,7,1,"_CPPv4N4espp10Controller6Button1AE","espp::Controller::Button::A"],[13,7,1,"_CPPv4N4espp10Controller6Button1BE","espp::Controller::Button::B"],[13,7,1,"_CPPv4N4espp10Controller6Button4DOWNE","espp::Controller::Button::DOWN"],[13,7,1,"_CPPv4N4espp10Controller6Button15JOYSTICK_SELECTE","espp::Controller::Button::JOYSTICK_SELECT"],[13,7,1,"_CPPv4N4espp10Controller6Button11LAST_UNUSEDE","espp::Controller::Button::LAST_UNUSED"],[13,7,1,"_CPPv4N4espp10Controller6Button4LEFTE","espp::Controller::Button::LEFT"],[13,7,1,"_CPPv4N4espp10Controller6Button5RIGHTE","espp::Controller::Button::RIGHT"],[13,7,1,"_CPPv4N4espp10Controller6Button6SELECTE","espp::Controller::Button::SELECT"],[13,7,1,"_CPPv4N4espp10Controller6Button5STARTE","espp::Controller::Button::START"],[13,7,1,"_CPPv4N4espp10Controller6Button2UPE","espp::Controller::Button::UP"],[13,7,1,"_CPPv4N4espp10Controller6Button1XE","espp::Controller::Button::X"],[13,7,1,"_CPPv4N4espp10Controller6Button1YE","espp::Controller::Button::Y"],[13,3,1,"_CPPv4N4espp10Controller10ControllerERK10DualConfig","espp::Controller::Controller"],[13,3,1,"_CPPv4N4espp10Controller10ControllerERK13DigitalConfig","espp::Controller::Controller"],[13,3,1,"_CPPv4N4espp10Controller10ControllerERK20AnalogJoystickConfig","espp::Controller::Controller"],[13,4,1,"_CPPv4N4espp10Controller10ControllerERK10DualConfig","espp::Controller::Controller::config"],[13,4,1,"_CPPv4N4espp10Controller10ControllerERK13DigitalConfig","espp::Controller::Controller::config"],[13,4,1,"_CPPv4N4espp10Controller10ControllerERK20AnalogJoystickConfig","espp::Controller::Controller::config"],[13,2,1,"_CPPv4N4espp10Controller13DigitalConfigE","espp::Controller::DigitalConfig"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig10active_lowE","espp::Controller::DigitalConfig::active_low"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_aE","espp::Controller::DigitalConfig::gpio_a"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_bE","espp::Controller::DigitalConfig::gpio_b"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig9gpio_downE","espp::Controller::DigitalConfig::gpio_down"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig9gpio_leftE","espp::Controller::DigitalConfig::gpio_left"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig10gpio_rightE","espp::Controller::DigitalConfig::gpio_right"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig11gpio_selectE","espp::Controller::DigitalConfig::gpio_select"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig10gpio_startE","espp::Controller::DigitalConfig::gpio_start"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig7gpio_upE","espp::Controller::DigitalConfig::gpio_up"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_xE","espp::Controller::DigitalConfig::gpio_x"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_yE","espp::Controller::DigitalConfig::gpio_y"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig9log_levelE","espp::Controller::DigitalConfig::log_level"],[13,2,1,"_CPPv4N4espp10Controller10DualConfigE","espp::Controller::DualConfig"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig10active_lowE","espp::Controller::DualConfig::active_low"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_aE","espp::Controller::DualConfig::gpio_a"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_bE","espp::Controller::DualConfig::gpio_b"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig9gpio_downE","espp::Controller::DualConfig::gpio_down"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig20gpio_joystick_selectE","espp::Controller::DualConfig::gpio_joystick_select"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig9gpio_leftE","espp::Controller::DualConfig::gpio_left"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig10gpio_rightE","espp::Controller::DualConfig::gpio_right"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig11gpio_selectE","espp::Controller::DualConfig::gpio_select"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig10gpio_startE","espp::Controller::DualConfig::gpio_start"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig7gpio_upE","espp::Controller::DualConfig::gpio_up"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_xE","espp::Controller::DualConfig::gpio_x"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_yE","espp::Controller::DualConfig::gpio_y"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig9log_levelE","espp::Controller::DualConfig::log_level"],[13,2,1,"_CPPv4N4espp10Controller5StateE","espp::Controller::State"],[13,1,1,"_CPPv4N4espp10Controller5State1aE","espp::Controller::State::a"],[13,1,1,"_CPPv4N4espp10Controller5State1bE","espp::Controller::State::b"],[13,1,1,"_CPPv4N4espp10Controller5State4downE","espp::Controller::State::down"],[13,1,1,"_CPPv4N4espp10Controller5State15joystick_selectE","espp::Controller::State::joystick_select"],[13,1,1,"_CPPv4N4espp10Controller5State4leftE","espp::Controller::State::left"],[13,1,1,"_CPPv4N4espp10Controller5State5rightE","espp::Controller::State::right"],[13,1,1,"_CPPv4N4espp10Controller5State6selectE","espp::Controller::State::select"],[13,1,1,"_CPPv4N4espp10Controller5State5startE","espp::Controller::State::start"],[13,1,1,"_CPPv4N4espp10Controller5State2upE","espp::Controller::State::up"],[13,1,1,"_CPPv4N4espp10Controller5State1xE","espp::Controller::State::x"],[13,1,1,"_CPPv4N4espp10Controller5State1yE","espp::Controller::State::y"],[13,3,1,"_CPPv4N4espp10Controller9get_stateEv","espp::Controller::get_state"],[13,3,1,"_CPPv4N4espp10Controller10is_pressedEK6Button","espp::Controller::is_pressed"],[13,4,1,"_CPPv4N4espp10Controller10is_pressedEK6Button","espp::Controller::is_pressed::input"],[13,3,1,"_CPPv4N4espp10Controller6updateEv","espp::Controller::update"],[13,3,1,"_CPPv4N4espp10ControllerD0Ev","espp::Controller::~Controller"],[15,2,1,"_CPPv4N4espp7DisplayE","espp::Display"],[15,2,1,"_CPPv4N4espp7Display16AllocatingConfigE","espp::Display::AllocatingConfig"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig16allocation_flagsE","espp::Display::AllocatingConfig::allocation_flags"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig18backlight_on_valueE","espp::Display::AllocatingConfig::backlight_on_value"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig13backlight_pinE","espp::Display::AllocatingConfig::backlight_pin"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig15double_bufferedE","espp::Display::AllocatingConfig::double_buffered"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig14flush_callbackE","espp::Display::AllocatingConfig::flush_callback"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig6heightE","espp::Display::AllocatingConfig::height"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig9log_levelE","espp::Display::AllocatingConfig::log_level"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig17pixel_buffer_sizeE","espp::Display::AllocatingConfig::pixel_buffer_size"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig8rotationE","espp::Display::AllocatingConfig::rotation"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig25software_rotation_enabledE","espp::Display::AllocatingConfig::software_rotation_enabled"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig13update_periodE","espp::Display::AllocatingConfig::update_period"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig5widthE","espp::Display::AllocatingConfig::width"],[15,3,1,"_CPPv4N4espp7Display7DisplayERK16AllocatingConfig","espp::Display::Display"],[15,3,1,"_CPPv4N4espp7Display7DisplayERK19NonAllocatingConfig","espp::Display::Display"],[15,4,1,"_CPPv4N4espp7Display7DisplayERK16AllocatingConfig","espp::Display::Display::config"],[15,4,1,"_CPPv4N4espp7Display7DisplayERK19NonAllocatingConfig","espp::Display::Display::config"],[15,2,1,"_CPPv4N4espp7Display19NonAllocatingConfigE","espp::Display::NonAllocatingConfig"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig18backlight_on_valueE","espp::Display::NonAllocatingConfig::backlight_on_value"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig13backlight_pinE","espp::Display::NonAllocatingConfig::backlight_pin"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig14flush_callbackE","espp::Display::NonAllocatingConfig::flush_callback"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig6heightE","espp::Display::NonAllocatingConfig::height"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig9log_levelE","espp::Display::NonAllocatingConfig::log_level"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig17pixel_buffer_sizeE","espp::Display::NonAllocatingConfig::pixel_buffer_size"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig8rotationE","espp::Display::NonAllocatingConfig::rotation"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig25software_rotation_enabledE","espp::Display::NonAllocatingConfig::software_rotation_enabled"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig13update_periodE","espp::Display::NonAllocatingConfig::update_period"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig5vram0E","espp::Display::NonAllocatingConfig::vram0"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig5vram1E","espp::Display::NonAllocatingConfig::vram1"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig5widthE","espp::Display::NonAllocatingConfig::width"],[15,6,1,"_CPPv4N4espp7Display8RotationE","espp::Display::Rotation"],[15,7,1,"_CPPv4N4espp7Display8Rotation9LANDSCAPEE","espp::Display::Rotation::LANDSCAPE"],[15,7,1,"_CPPv4N4espp7Display8Rotation18LANDSCAPE_INVERTEDE","espp::Display::Rotation::LANDSCAPE_INVERTED"],[15,7,1,"_CPPv4N4espp7Display8Rotation8PORTRAITE","espp::Display::Rotation::PORTRAIT"],[15,7,1,"_CPPv4N4espp7Display8Rotation17PORTRAIT_INVERTEDE","espp::Display::Rotation::PORTRAIT_INVERTED"],[15,6,1,"_CPPv4N4espp7Display6SignalE","espp::Display::Signal"],[15,7,1,"_CPPv4N4espp7Display6Signal5FLUSHE","espp::Display::Signal::FLUSH"],[15,7,1,"_CPPv4N4espp7Display6Signal4NONEE","espp::Display::Signal::NONE"],[15,8,1,"_CPPv4N4espp7Display8flush_fnE","espp::Display::flush_fn"],[15,3,1,"_CPPv4N4espp7Display13force_refreshEv","espp::Display::force_refresh"],[15,3,1,"_CPPv4NK4espp7Display14get_brightnessEv","espp::Display::get_brightness"],[15,3,1,"_CPPv4NK4espp7Display6heightEv","espp::Display::height"],[15,3,1,"_CPPv4N4espp7Display5pauseEv","espp::Display::pause"],[15,3,1,"_CPPv4N4espp7Display6resumeEv","espp::Display::resume"],[15,3,1,"_CPPv4N4espp7Display14set_brightnessEf","espp::Display::set_brightness"],[15,4,1,"_CPPv4N4espp7Display14set_brightnessEf","espp::Display::set_brightness::brightness"],[15,3,1,"_CPPv4N4espp7Display5vram0Ev","espp::Display::vram0"],[15,3,1,"_CPPv4N4espp7Display5vram1Ev","espp::Display::vram1"],[15,3,1,"_CPPv4N4espp7Display15vram_size_bytesEv","espp::Display::vram_size_bytes"],[15,3,1,"_CPPv4N4espp7Display12vram_size_pxEv","espp::Display::vram_size_px"],[15,3,1,"_CPPv4NK4espp7Display5widthEv","espp::Display::width"],[15,3,1,"_CPPv4N4espp7DisplayD0Ev","espp::Display::~Display"],[34,2,1,"_CPPv4N4espp7Drv2605E","espp::Drv2605"],[34,2,1,"_CPPv4N4espp7Drv26056ConfigE","espp::Drv2605::Config"],[34,1,1,"_CPPv4N4espp7Drv26056Config9auto_initE","espp::Drv2605::Config::auto_init"],[34,1,1,"_CPPv4N4espp7Drv26056Config14device_addressE","espp::Drv2605::Config::device_address"],[34,1,1,"_CPPv4N4espp7Drv26056Config9log_levelE","espp::Drv2605::Config::log_level"],[34,1,1,"_CPPv4N4espp7Drv26056Config10motor_typeE","espp::Drv2605::Config::motor_type"],[34,1,1,"_CPPv4N4espp7Drv26056Config4readE","espp::Drv2605::Config::read"],[34,1,1,"_CPPv4N4espp7Drv26056Config5writeE","espp::Drv2605::Config::write"],[34,3,1,"_CPPv4N4espp7Drv26057Drv2605ERK6Config","espp::Drv2605::Drv2605"],[34,4,1,"_CPPv4N4espp7Drv26057Drv2605ERK6Config","espp::Drv2605::Drv2605::config"],[34,6,1,"_CPPv4N4espp7Drv26057LibraryE","espp::Drv2605::Library"],[34,7,1,"_CPPv4N4espp7Drv26057Library5EMPTYE","espp::Drv2605::Library::EMPTY"],[34,7,1,"_CPPv4N4espp7Drv26057Library5ERM_0E","espp::Drv2605::Library::ERM_0"],[34,7,1,"_CPPv4N4espp7Drv26057Library5ERM_1E","espp::Drv2605::Library::ERM_1"],[34,7,1,"_CPPv4N4espp7Drv26057Library5ERM_2E","espp::Drv2605::Library::ERM_2"],[34,7,1,"_CPPv4N4espp7Drv26057Library5ERM_3E","espp::Drv2605::Library::ERM_3"],[34,7,1,"_CPPv4N4espp7Drv26057Library5ERM_4E","espp::Drv2605::Library::ERM_4"],[34,7,1,"_CPPv4N4espp7Drv26057Library3LRAE","espp::Drv2605::Library::LRA"],[34,6,1,"_CPPv4N4espp7Drv26054ModeE","espp::Drv2605::Mode"],[34,7,1,"_CPPv4N4espp7Drv26054Mode9AUDIOVIBEE","espp::Drv2605::Mode::AUDIOVIBE"],[34,7,1,"_CPPv4N4espp7Drv26054Mode7AUTOCALE","espp::Drv2605::Mode::AUTOCAL"],[34,7,1,"_CPPv4N4espp7Drv26054Mode7DIAGNOSE","espp::Drv2605::Mode::DIAGNOS"],[34,7,1,"_CPPv4N4espp7Drv26054Mode11EXTTRIGEDGEE","espp::Drv2605::Mode::EXTTRIGEDGE"],[34,7,1,"_CPPv4N4espp7Drv26054Mode10EXTTRIGLVLE","espp::Drv2605::Mode::EXTTRIGLVL"],[34,7,1,"_CPPv4N4espp7Drv26054Mode7INTTRIGE","espp::Drv2605::Mode::INTTRIG"],[34,7,1,"_CPPv4N4espp7Drv26054Mode9PWMANALOGE","espp::Drv2605::Mode::PWMANALOG"],[34,7,1,"_CPPv4N4espp7Drv26054Mode8REALTIMEE","espp::Drv2605::Mode::REALTIME"],[34,6,1,"_CPPv4N4espp7Drv26059MotorTypeE","espp::Drv2605::MotorType"],[34,7,1,"_CPPv4N4espp7Drv26059MotorType3ERME","espp::Drv2605::MotorType::ERM"],[34,7,1,"_CPPv4N4espp7Drv26059MotorType3LRAE","espp::Drv2605::MotorType::LRA"],[34,6,1,"_CPPv4N4espp7Drv26058WaveformE","espp::Drv2605::Waveform"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform12ALERT_1000MSE","espp::Drv2605::Waveform::ALERT_1000MS"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform11ALERT_750MSE","espp::Drv2605::Waveform::ALERT_750MS"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ1E","espp::Drv2605::Waveform::BUZZ1"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ2E","espp::Drv2605::Waveform::BUZZ2"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ3E","espp::Drv2605::Waveform::BUZZ3"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ4E","espp::Drv2605::Waveform::BUZZ4"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ5E","espp::Drv2605::Waveform::BUZZ5"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform12DOUBLE_CLICKE","espp::Drv2605::Waveform::DOUBLE_CLICK"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform3ENDE","espp::Drv2605::Waveform::END"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform3MAXE","espp::Drv2605::Waveform::MAX"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform16PULSING_STRONG_1E","espp::Drv2605::Waveform::PULSING_STRONG_1"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform16PULSING_STRONG_2E","espp::Drv2605::Waveform::PULSING_STRONG_2"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform11SHARP_CLICKE","espp::Drv2605::Waveform::SHARP_CLICK"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform9SOFT_BUMPE","espp::Drv2605::Waveform::SOFT_BUMP"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform9SOFT_FUZZE","espp::Drv2605::Waveform::SOFT_FUZZ"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform11STRONG_BUZZE","espp::Drv2605::Waveform::STRONG_BUZZ"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform12STRONG_CLICKE","espp::Drv2605::Waveform::STRONG_CLICK"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform18TRANSITION_CLICK_1E","espp::Drv2605::Waveform::TRANSITION_CLICK_1"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform16TRANSITION_HUM_1E","espp::Drv2605::Waveform::TRANSITION_HUM_1"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform12TRIPLE_CLICKE","espp::Drv2605::Waveform::TRIPLE_CLICK"],[34,3,1,"_CPPv4N4espp7Drv26059initalizeERNSt10error_codeE","espp::Drv2605::initalize"],[34,4,1,"_CPPv4N4espp7Drv26059initalizeERNSt10error_codeE","espp::Drv2605::initalize::ec"],[34,8,1,"_CPPv4N4espp7Drv26057read_fnE","espp::Drv2605::read_fn"],[34,3,1,"_CPPv4N4espp7Drv260514select_libraryE7LibraryRNSt10error_codeE","espp::Drv2605::select_library"],[34,4,1,"_CPPv4N4espp7Drv260514select_libraryE7LibraryRNSt10error_codeE","espp::Drv2605::select_library::ec"],[34,4,1,"_CPPv4N4espp7Drv260514select_libraryE7LibraryRNSt10error_codeE","espp::Drv2605::select_library::lib"],[34,3,1,"_CPPv4N4espp7Drv26058set_modeE4ModeRNSt10error_codeE","espp::Drv2605::set_mode"],[34,4,1,"_CPPv4N4espp7Drv26058set_modeE4ModeRNSt10error_codeE","espp::Drv2605::set_mode::ec"],[34,4,1,"_CPPv4N4espp7Drv26058set_modeE4ModeRNSt10error_codeE","espp::Drv2605::set_mode::mode"],[34,3,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8WaveformRNSt10error_codeE","espp::Drv2605::set_waveform"],[34,4,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8WaveformRNSt10error_codeE","espp::Drv2605::set_waveform::ec"],[34,4,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8WaveformRNSt10error_codeE","espp::Drv2605::set_waveform::slot"],[34,4,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8WaveformRNSt10error_codeE","espp::Drv2605::set_waveform::w"],[34,3,1,"_CPPv4N4espp7Drv26055startERNSt10error_codeE","espp::Drv2605::start"],[34,4,1,"_CPPv4N4espp7Drv26055startERNSt10error_codeE","espp::Drv2605::start::ec"],[34,3,1,"_CPPv4N4espp7Drv26054stopERNSt10error_codeE","espp::Drv2605::stop"],[34,4,1,"_CPPv4N4espp7Drv26054stopERNSt10error_codeE","espp::Drv2605::stop::ec"],[34,8,1,"_CPPv4N4espp7Drv26058write_fnE","espp::Drv2605::write_fn"],[38,2,1,"_CPPv4N4espp12EncoderInputE","espp::EncoderInput"],[38,2,1,"_CPPv4N4espp12EncoderInput6ConfigE","espp::EncoderInput::Config"],[38,1,1,"_CPPv4N4espp12EncoderInput6Config9log_levelE","espp::EncoderInput::Config::log_level"],[38,1,1,"_CPPv4N4espp12EncoderInput6Config4readE","espp::EncoderInput::Config::read"],[38,3,1,"_CPPv4N4espp12EncoderInput12EncoderInputERK6Config","espp::EncoderInput::EncoderInput"],[38,4,1,"_CPPv4N4espp12EncoderInput12EncoderInputERK6Config","espp::EncoderInput::EncoderInput::config"],[38,3,1,"_CPPv4N4espp12EncoderInput23get_button_input_deviceEv","espp::EncoderInput::get_button_input_device"],[38,3,1,"_CPPv4N4espp12EncoderInput24get_encoder_input_deviceEv","espp::EncoderInput::get_encoder_input_device"],[38,3,1,"_CPPv4N4espp12EncoderInputD0Ev","espp::EncoderInput::~EncoderInput"],[23,2,1,"_CPPv4N4espp12EventManagerE","espp::EventManager"],[23,3,1,"_CPPv4N4espp12EventManager13add_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::add_publisher"],[23,4,1,"_CPPv4N4espp12EventManager13add_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::add_publisher::component"],[23,4,1,"_CPPv4N4espp12EventManager13add_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::add_publisher::topic"],[23,3,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fnK6size_t","espp::EventManager::add_subscriber"],[23,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fnK6size_t","espp::EventManager::add_subscriber::callback"],[23,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fnK6size_t","espp::EventManager::add_subscriber::component"],[23,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fnK6size_t","espp::EventManager::add_subscriber::stack_size_bytes"],[23,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fnK6size_t","espp::EventManager::add_subscriber::topic"],[23,8,1,"_CPPv4N4espp12EventManager17event_callback_fnE","espp::EventManager::event_callback_fn"],[23,3,1,"_CPPv4N4espp12EventManager3getEv","espp::EventManager::get"],[23,3,1,"_CPPv4N4espp12EventManager7publishERKNSt6stringERKNSt6vectorI7uint8_tEE","espp::EventManager::publish"],[23,4,1,"_CPPv4N4espp12EventManager7publishERKNSt6stringERKNSt6vectorI7uint8_tEE","espp::EventManager::publish::data"],[23,4,1,"_CPPv4N4espp12EventManager7publishERKNSt6stringERKNSt6vectorI7uint8_tEE","espp::EventManager::publish::topic"],[23,3,1,"_CPPv4N4espp12EventManager16remove_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::remove_publisher"],[23,4,1,"_CPPv4N4espp12EventManager16remove_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::remove_publisher::component"],[23,4,1,"_CPPv4N4espp12EventManager16remove_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::remove_publisher::topic"],[23,3,1,"_CPPv4N4espp12EventManager17remove_subscriberERKNSt6stringERKNSt6stringE","espp::EventManager::remove_subscriber"],[23,4,1,"_CPPv4N4espp12EventManager17remove_subscriberERKNSt6stringERKNSt6stringE","espp::EventManager::remove_subscriber::component"],[23,4,1,"_CPPv4N4espp12EventManager17remove_subscriberERKNSt6stringERKNSt6stringE","espp::EventManager::remove_subscriber::topic"],[23,3,1,"_CPPv4N4espp12EventManager13set_log_levelEN6Logger9VerbosityE","espp::EventManager::set_log_level"],[23,4,1,"_CPPv4N4espp12EventManager13set_log_levelEN6Logger9VerbosityE","espp::EventManager::set_log_level::level"],[24,2,1,"_CPPv4N4espp10FileSystemE","espp::FileSystem"],[24,2,1,"_CPPv4N4espp10FileSystem10ListConfigE","espp::FileSystem::ListConfig"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig9date_timeE","espp::FileSystem::ListConfig::date_time"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig5groupE","espp::FileSystem::ListConfig::group"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig15number_of_linksE","espp::FileSystem::ListConfig::number_of_links"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig5ownerE","espp::FileSystem::ListConfig::owner"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig11permissionsE","espp::FileSystem::ListConfig::permissions"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig9recursiveE","espp::FileSystem::ListConfig::recursive"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig4sizeE","espp::FileSystem::ListConfig::size"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig4typeE","espp::FileSystem::ListConfig::type"],[24,3,1,"_CPPv4N4espp10FileSystem3getEv","espp::FileSystem::get"],[24,3,1,"_CPPv4N4espp10FileSystem14get_free_spaceEv","espp::FileSystem::get_free_space"],[24,3,1,"_CPPv4N4espp10FileSystem15get_mount_pointEv","espp::FileSystem::get_mount_point"],[24,3,1,"_CPPv4N4espp10FileSystem19get_partition_labelEv","espp::FileSystem::get_partition_label"],[24,3,1,"_CPPv4N4espp10FileSystem13get_root_pathEv","espp::FileSystem::get_root_path"],[24,3,1,"_CPPv4N4espp10FileSystem15get_total_spaceEv","espp::FileSystem::get_total_space"],[24,3,1,"_CPPv4N4espp10FileSystem14get_used_spaceEv","espp::FileSystem::get_used_space"],[24,3,1,"_CPPv4N4espp10FileSystem14human_readableE6size_t","espp::FileSystem::human_readable"],[24,4,1,"_CPPv4N4espp10FileSystem14human_readableE6size_t","espp::FileSystem::human_readable::bytes"],[24,3,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory"],[24,3,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory"],[24,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::config"],[24,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::config"],[24,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::path"],[24,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::path"],[24,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::prefix"],[24,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::prefix"],[24,3,1,"_CPPv4I0EN4espp10FileSystem9to_time_tENSt6time_tE2TP","espp::FileSystem::to_time_t"],[24,5,1,"_CPPv4I0EN4espp10FileSystem9to_time_tENSt6time_tE2TP","espp::FileSystem::to_time_t::TP"],[24,4,1,"_CPPv4I0EN4espp10FileSystem9to_time_tENSt6time_tE2TP","espp::FileSystem::to_time_t::tp"],[39,2,1,"_CPPv4N4espp6Ft5x06E","espp::Ft5x06"],[39,2,1,"_CPPv4N4espp6Ft5x066ConfigE","espp::Ft5x06::Config"],[39,1,1,"_CPPv4N4espp6Ft5x066Config9log_levelE","espp::Ft5x06::Config::log_level"],[39,1,1,"_CPPv4N4espp6Ft5x066Config16read_at_registerE","espp::Ft5x06::Config::read_at_register"],[39,1,1,"_CPPv4N4espp6Ft5x066Config5writeE","espp::Ft5x06::Config::write"],[39,1,1,"_CPPv4N4espp6Ft5x0615DEFAULT_ADDRESSE","espp::Ft5x06::DEFAULT_ADDRESS"],[39,3,1,"_CPPv4N4espp6Ft5x066Ft5x06ERK6Config","espp::Ft5x06::Ft5x06"],[39,4,1,"_CPPv4N4espp6Ft5x066Ft5x06ERK6Config","espp::Ft5x06::Ft5x06::config"],[39,6,1,"_CPPv4N4espp6Ft5x067GestureE","espp::Ft5x06::Gesture"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture9MOVE_DOWNE","espp::Ft5x06::Gesture::MOVE_DOWN"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture9MOVE_LEFTE","espp::Ft5x06::Gesture::MOVE_LEFT"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture10MOVE_RIGHTE","espp::Ft5x06::Gesture::MOVE_RIGHT"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture7MOVE_UPE","espp::Ft5x06::Gesture::MOVE_UP"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture4NONEE","espp::Ft5x06::Gesture::NONE"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture7ZOOM_INE","espp::Ft5x06::Gesture::ZOOM_IN"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture8ZOOM_OUTE","espp::Ft5x06::Gesture::ZOOM_OUT"],[39,3,1,"_CPPv4N4espp6Ft5x0620get_num_touch_pointsERNSt10error_codeE","espp::Ft5x06::get_num_touch_points"],[39,4,1,"_CPPv4N4espp6Ft5x0620get_num_touch_pointsERNSt10error_codeE","espp::Ft5x06::get_num_touch_points::ec"],[39,3,1,"_CPPv4N4espp6Ft5x0615get_touch_pointEP7uint8_tP8uint16_tP8uint16_tRNSt10error_codeE","espp::Ft5x06::get_touch_point"],[39,4,1,"_CPPv4N4espp6Ft5x0615get_touch_pointEP7uint8_tP8uint16_tP8uint16_tRNSt10error_codeE","espp::Ft5x06::get_touch_point::ec"],[39,4,1,"_CPPv4N4espp6Ft5x0615get_touch_pointEP7uint8_tP8uint16_tP8uint16_tRNSt10error_codeE","espp::Ft5x06::get_touch_point::num_touch_points"],[39,4,1,"_CPPv4N4espp6Ft5x0615get_touch_pointEP7uint8_tP8uint16_tP8uint16_tRNSt10error_codeE","espp::Ft5x06::get_touch_point::x"],[39,4,1,"_CPPv4N4espp6Ft5x0615get_touch_pointEP7uint8_tP8uint16_tP8uint16_tRNSt10error_codeE","espp::Ft5x06::get_touch_point::y"],[39,8,1,"_CPPv4N4espp6Ft5x0619read_at_register_fnE","espp::Ft5x06::read_at_register_fn"],[39,3,1,"_CPPv4N4espp6Ft5x0612read_gestureERNSt10error_codeE","espp::Ft5x06::read_gesture"],[39,4,1,"_CPPv4N4espp6Ft5x0612read_gestureERNSt10error_codeE","espp::Ft5x06::read_gesture::ec"],[39,8,1,"_CPPv4N4espp6Ft5x068write_fnE","espp::Ft5x06::write_fn"],[31,2,1,"_CPPv4N4espp16FtpClientSessionE","espp::FtpClientSession"],[31,3,1,"_CPPv4NK4espp16FtpClientSession17current_directoryEv","espp::FtpClientSession::current_directory"],[31,3,1,"_CPPv4NK4espp16FtpClientSession2idEv","espp::FtpClientSession::id"],[31,3,1,"_CPPv4NK4espp16FtpClientSession8is_aliveEv","espp::FtpClientSession::is_alive"],[31,3,1,"_CPPv4NK4espp16FtpClientSession12is_connectedEv","espp::FtpClientSession::is_connected"],[31,3,1,"_CPPv4NK4espp16FtpClientSession26is_passive_data_connectionEv","espp::FtpClientSession::is_passive_data_connection"],[31,2,1,"_CPPv4N4espp9FtpServerE","espp::FtpServer"],[31,3,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer"],[31,4,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer::ip_address"],[31,4,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer::port"],[31,4,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer::root"],[31,3,1,"_CPPv4N4espp9FtpServer5startEv","espp::FtpServer::start"],[31,3,1,"_CPPv4N4espp9FtpServer4stopEv","espp::FtpServer::stop"],[31,3,1,"_CPPv4N4espp9FtpServerD0Ev","espp::FtpServer::~FtpServer"],[55,2,1,"_CPPv4N4espp8GaussianE","espp::Gaussian"],[55,2,1,"_CPPv4N4espp8Gaussian6ConfigE","espp::Gaussian::Config"],[55,1,1,"_CPPv4N4espp8Gaussian6Config5alphaE","espp::Gaussian::Config::alpha"],[55,1,1,"_CPPv4N4espp8Gaussian6Config4betaE","espp::Gaussian::Config::beta"],[55,1,1,"_CPPv4N4espp8Gaussian6Config5gammaE","espp::Gaussian::Config::gamma"],[55,3,1,"_CPPv4N4espp8Gaussian8GaussianERK6Config","espp::Gaussian::Gaussian"],[55,4,1,"_CPPv4N4espp8Gaussian8GaussianERK6Config","espp::Gaussian::Gaussian::config"],[55,3,1,"_CPPv4N4espp8Gaussian5alphaEf","espp::Gaussian::alpha"],[55,3,1,"_CPPv4NK4espp8Gaussian5alphaEv","espp::Gaussian::alpha"],[55,4,1,"_CPPv4N4espp8Gaussian5alphaEf","espp::Gaussian::alpha::a"],[55,3,1,"_CPPv4NK4espp8Gaussian2atEf","espp::Gaussian::at"],[55,4,1,"_CPPv4NK4espp8Gaussian2atEf","espp::Gaussian::at::t"],[55,3,1,"_CPPv4N4espp8Gaussian4betaEf","espp::Gaussian::beta"],[55,3,1,"_CPPv4NK4espp8Gaussian4betaEv","espp::Gaussian::beta"],[55,4,1,"_CPPv4N4espp8Gaussian4betaEf","espp::Gaussian::beta::b"],[55,3,1,"_CPPv4N4espp8Gaussian5gammaEf","espp::Gaussian::gamma"],[55,3,1,"_CPPv4NK4espp8Gaussian5gammaEv","espp::Gaussian::gamma"],[55,4,1,"_CPPv4N4espp8Gaussian5gammaEf","espp::Gaussian::gamma::g"],[55,3,1,"_CPPv4NK4espp8GaussianclEf","espp::Gaussian::operator()"],[55,4,1,"_CPPv4NK4espp8GaussianclEf","espp::Gaussian::operator()::t"],[40,2,1,"_CPPv4N4espp5Gt911E","espp::Gt911"],[40,2,1,"_CPPv4N4espp5Gt9116ConfigE","espp::Gt911::Config"],[40,1,1,"_CPPv4N4espp5Gt9116Config7addressE","espp::Gt911::Config::address"],[40,1,1,"_CPPv4N4espp5Gt9116Config9log_levelE","espp::Gt911::Config::log_level"],[40,1,1,"_CPPv4N4espp5Gt9116Config5writeE","espp::Gt911::Config::write"],[40,1,1,"_CPPv4N4espp5Gt9116Config10write_readE","espp::Gt911::Config::write_read"],[40,1,1,"_CPPv4N4espp5Gt91117DEFAULT_ADDRESS_1E","espp::Gt911::DEFAULT_ADDRESS_1"],[40,1,1,"_CPPv4N4espp5Gt91117DEFAULT_ADDRESS_2E","espp::Gt911::DEFAULT_ADDRESS_2"],[40,3,1,"_CPPv4N4espp5Gt9115Gt911ERK6Config","espp::Gt911::Gt911"],[40,4,1,"_CPPv4N4espp5Gt9115Gt911ERK6Config","espp::Gt911::Gt911::config"],[40,3,1,"_CPPv4NK4espp5Gt91121get_home_button_stateEv","espp::Gt911::get_home_button_state"],[40,3,1,"_CPPv4NK4espp5Gt91120get_num_touch_pointsEv","espp::Gt911::get_num_touch_points"],[40,3,1,"_CPPv4NK4espp5Gt91115get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Gt911::get_touch_point"],[40,4,1,"_CPPv4NK4espp5Gt91115get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Gt911::get_touch_point::num_touch_points"],[40,4,1,"_CPPv4NK4espp5Gt91115get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Gt911::get_touch_point::x"],[40,4,1,"_CPPv4NK4espp5Gt91115get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Gt911::get_touch_point::y"],[40,3,1,"_CPPv4N4espp5Gt9116updateERNSt10error_codeE","espp::Gt911::update"],[40,4,1,"_CPPv4N4espp5Gt9116updateERNSt10error_codeE","espp::Gt911::update::ec"],[40,8,1,"_CPPv4N4espp5Gt9118write_fnE","espp::Gt911::write_fn"],[40,8,1,"_CPPv4N4espp5Gt91113write_read_fnE","espp::Gt911::write_read_fn"],[12,2,1,"_CPPv4N4espp3HsvE","espp::Hsv"],[12,3,1,"_CPPv4N4espp3Hsv3HsvERK3Hsv","espp::Hsv::Hsv"],[12,3,1,"_CPPv4N4espp3Hsv3HsvERK3Rgb","espp::Hsv::Hsv"],[12,3,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv"],[12,4,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv::h"],[12,4,1,"_CPPv4N4espp3Hsv3HsvERK3Hsv","espp::Hsv::Hsv::hsv"],[12,4,1,"_CPPv4N4espp3Hsv3HsvERK3Rgb","espp::Hsv::Hsv::rgb"],[12,4,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv::s"],[12,4,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv::v"],[12,1,1,"_CPPv4N4espp3Hsv1hE","espp::Hsv::h"],[12,3,1,"_CPPv4NK4espp3Hsv3rgbEv","espp::Hsv::rgb"],[12,1,1,"_CPPv4N4espp3Hsv1sE","espp::Hsv::s"],[12,1,1,"_CPPv4N4espp3Hsv1vE","espp::Hsv::v"],[36,2,1,"_CPPv4N4espp3I2cE","espp::I2c"],[36,2,1,"_CPPv4N4espp3I2c6ConfigE","espp::I2c::Config"],[36,1,1,"_CPPv4N4espp3I2c6Config9auto_initE","espp::I2c::Config::auto_init"],[36,1,1,"_CPPv4N4espp3I2c6Config9clk_speedE","espp::I2c::Config::clk_speed"],[36,1,1,"_CPPv4N4espp3I2c6Config9log_levelE","espp::I2c::Config::log_level"],[36,1,1,"_CPPv4N4espp3I2c6Config4portE","espp::I2c::Config::port"],[36,1,1,"_CPPv4N4espp3I2c6Config10scl_io_numE","espp::I2c::Config::scl_io_num"],[36,1,1,"_CPPv4N4espp3I2c6Config13scl_pullup_enE","espp::I2c::Config::scl_pullup_en"],[36,1,1,"_CPPv4N4espp3I2c6Config10sda_io_numE","espp::I2c::Config::sda_io_num"],[36,1,1,"_CPPv4N4espp3I2c6Config13sda_pullup_enE","espp::I2c::Config::sda_pullup_en"],[36,1,1,"_CPPv4N4espp3I2c6Config10timeout_msE","espp::I2c::Config::timeout_ms"],[36,3,1,"_CPPv4N4espp3I2c3I2cERK6Config","espp::I2c::I2c"],[36,4,1,"_CPPv4N4espp3I2c3I2cERK6Config","espp::I2c::I2c::config"],[36,3,1,"_CPPv4N4espp3I2c6deinitERNSt10error_codeE","espp::I2c::deinit"],[36,4,1,"_CPPv4N4espp3I2c6deinitERNSt10error_codeE","espp::I2c::deinit::ec"],[36,3,1,"_CPPv4N4espp3I2c4initERNSt10error_codeE","espp::I2c::init"],[36,4,1,"_CPPv4N4espp3I2c4initERNSt10error_codeE","espp::I2c::init::ec"],[36,3,1,"_CPPv4N4espp3I2c12probe_deviceE7uint8_t","espp::I2c::probe_device"],[36,4,1,"_CPPv4N4espp3I2c12probe_deviceE7uint8_t","espp::I2c::probe_device::dev_addr"],[36,3,1,"_CPPv4N4espp3I2c4readE7uint8_tP7uint8_t6size_t","espp::I2c::read"],[36,4,1,"_CPPv4N4espp3I2c4readE7uint8_tP7uint8_t6size_t","espp::I2c::read::data"],[36,4,1,"_CPPv4N4espp3I2c4readE7uint8_tP7uint8_t6size_t","espp::I2c::read::data_len"],[36,4,1,"_CPPv4N4espp3I2c4readE7uint8_tP7uint8_t6size_t","espp::I2c::read::dev_addr"],[36,3,1,"_CPPv4N4espp3I2c16read_at_registerE7uint8_t7uint8_tP7uint8_t6size_t","espp::I2c::read_at_register"],[36,4,1,"_CPPv4N4espp3I2c16read_at_registerE7uint8_t7uint8_tP7uint8_t6size_t","espp::I2c::read_at_register::data"],[36,4,1,"_CPPv4N4espp3I2c16read_at_registerE7uint8_t7uint8_tP7uint8_t6size_t","espp::I2c::read_at_register::data_len"],[36,4,1,"_CPPv4N4espp3I2c16read_at_registerE7uint8_t7uint8_tP7uint8_t6size_t","espp::I2c::read_at_register::dev_addr"],[36,4,1,"_CPPv4N4espp3I2c16read_at_registerE7uint8_t7uint8_tP7uint8_t6size_t","espp::I2c::read_at_register::reg_addr"],[36,3,1,"_CPPv4N4espp3I2c5writeE7uint8_tP7uint8_t6size_t","espp::I2c::write"],[36,4,1,"_CPPv4N4espp3I2c5writeE7uint8_tP7uint8_t6size_t","espp::I2c::write::data"],[36,4,1,"_CPPv4N4espp3I2c5writeE7uint8_tP7uint8_t6size_t","espp::I2c::write::data_len"],[36,4,1,"_CPPv4N4espp3I2c5writeE7uint8_tP7uint8_t6size_t","espp::I2c::write::dev_addr"],[36,3,1,"_CPPv4N4espp3I2c10write_readE7uint8_tP7uint8_t6size_tP7uint8_t6size_t","espp::I2c::write_read"],[36,4,1,"_CPPv4N4espp3I2c10write_readE7uint8_tP7uint8_t6size_tP7uint8_t6size_t","espp::I2c::write_read::dev_addr"],[36,4,1,"_CPPv4N4espp3I2c10write_readE7uint8_tP7uint8_t6size_tP7uint8_t6size_t","espp::I2c::write_read::read_data"],[36,4,1,"_CPPv4N4espp3I2c10write_readE7uint8_tP7uint8_t6size_tP7uint8_t6size_t","espp::I2c::write_read::read_size"],[36,4,1,"_CPPv4N4espp3I2c10write_readE7uint8_tP7uint8_t6size_tP7uint8_t6size_t","espp::I2c::write_read::write_data"],[36,4,1,"_CPPv4N4espp3I2c10write_readE7uint8_tP7uint8_t6size_tP7uint8_t6size_t","espp::I2c::write_read::write_size"],[16,2,1,"_CPPv4N4espp7Ili9341E","espp::Ili9341"],[16,3,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear"],[16,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::color"],[16,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::height"],[16,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::width"],[16,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::x"],[16,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::y"],[16,3,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill"],[16,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::area"],[16,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::color_map"],[16,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::drv"],[16,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::flags"],[16,3,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush"],[16,4,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush::area"],[16,4,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush::color_map"],[16,4,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush::drv"],[16,3,1,"_CPPv4N4espp7Ili934110get_offsetERiRi","espp::Ili9341::get_offset"],[16,4,1,"_CPPv4N4espp7Ili934110get_offsetERiRi","espp::Ili9341::get_offset::x"],[16,4,1,"_CPPv4N4espp7Ili934110get_offsetERiRi","espp::Ili9341::get_offset::y"],[16,3,1,"_CPPv4N4espp7Ili934110initializeERKN15display_drivers6ConfigE","espp::Ili9341::initialize"],[16,4,1,"_CPPv4N4espp7Ili934110initializeERKN15display_drivers6ConfigE","espp::Ili9341::initialize::config"],[16,3,1,"_CPPv4N4espp7Ili934112send_commandE7uint8_t","espp::Ili9341::send_command"],[16,4,1,"_CPPv4N4espp7Ili934112send_commandE7uint8_t","espp::Ili9341::send_command::command"],[16,3,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data"],[16,4,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data::data"],[16,4,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data::flags"],[16,4,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data::length"],[16,3,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area"],[16,3,1,"_CPPv4N4espp7Ili934116set_drawing_areaEPK9lv_area_t","espp::Ili9341::set_drawing_area"],[16,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaEPK9lv_area_t","espp::Ili9341::set_drawing_area::area"],[16,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::xe"],[16,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::xs"],[16,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::ye"],[16,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::ys"],[16,3,1,"_CPPv4N4espp7Ili934110set_offsetEii","espp::Ili9341::set_offset"],[16,4,1,"_CPPv4N4espp7Ili934110set_offsetEii","espp::Ili9341::set_offset::x"],[16,4,1,"_CPPv4N4espp7Ili934110set_offsetEii","espp::Ili9341::set_offset::y"],[49,2,1,"_CPPv4N4espp8JoystickE","espp::Joystick"],[49,2,1,"_CPPv4N4espp8Joystick6ConfigE","espp::Joystick::Config"],[49,1,1,"_CPPv4N4espp8Joystick6Config8deadzoneE","espp::Joystick::Config::deadzone"],[49,1,1,"_CPPv4N4espp8Joystick6Config15deadzone_radiusE","espp::Joystick::Config::deadzone_radius"],[49,1,1,"_CPPv4N4espp8Joystick6Config10get_valuesE","espp::Joystick::Config::get_values"],[49,1,1,"_CPPv4N4espp8Joystick6Config9log_levelE","espp::Joystick::Config::log_level"],[49,1,1,"_CPPv4N4espp8Joystick6Config13x_calibrationE","espp::Joystick::Config::x_calibration"],[49,1,1,"_CPPv4N4espp8Joystick6Config13y_calibrationE","espp::Joystick::Config::y_calibration"],[49,6,1,"_CPPv4N4espp8Joystick8DeadzoneE","espp::Joystick::Deadzone"],[49,7,1,"_CPPv4N4espp8Joystick8Deadzone8CIRCULARE","espp::Joystick::Deadzone::CIRCULAR"],[49,7,1,"_CPPv4N4espp8Joystick8Deadzone11RECTANGULARE","espp::Joystick::Deadzone::RECTANGULAR"],[49,3,1,"_CPPv4N4espp8Joystick8JoystickERK6Config","espp::Joystick::Joystick"],[49,4,1,"_CPPv4N4espp8Joystick8JoystickERK6Config","espp::Joystick::Joystick::config"],[49,8,1,"_CPPv4N4espp8Joystick13get_values_fnE","espp::Joystick::get_values_fn"],[49,3,1,"_CPPv4NK4espp8Joystick8positionEv","espp::Joystick::position"],[49,3,1,"_CPPv4NK4espp8Joystick3rawEv","espp::Joystick::raw"],[49,3,1,"_CPPv4N4espp8Joystick15set_calibrationERKN16FloatRangeMapper6ConfigERKN16FloatRangeMapper6ConfigE","espp::Joystick::set_calibration"],[49,4,1,"_CPPv4N4espp8Joystick15set_calibrationERKN16FloatRangeMapper6ConfigERKN16FloatRangeMapper6ConfigE","espp::Joystick::set_calibration::x_calibration"],[49,4,1,"_CPPv4N4espp8Joystick15set_calibrationERKN16FloatRangeMapper6ConfigERKN16FloatRangeMapper6ConfigE","espp::Joystick::set_calibration::y_calibration"],[49,3,1,"_CPPv4N4espp8Joystick12set_deadzoneE8Deadzonef","espp::Joystick::set_deadzone"],[49,4,1,"_CPPv4N4espp8Joystick12set_deadzoneE8Deadzonef","espp::Joystick::set_deadzone::deadzone"],[49,4,1,"_CPPv4N4espp8Joystick12set_deadzoneE8Deadzonef","espp::Joystick::set_deadzone::radius"],[49,3,1,"_CPPv4N4espp8Joystick6updateEv","espp::Joystick::update"],[49,3,1,"_CPPv4NK4espp8Joystick1xEv","espp::Joystick::x"],[49,3,1,"_CPPv4NK4espp8Joystick1yEv","espp::Joystick::y"],[72,2,1,"_CPPv4N4espp9JpegFrameE","espp::JpegFrame"],[72,3,1,"_CPPv4N4espp9JpegFrame9JpegFrameEPKc6size_t","espp::JpegFrame::JpegFrame"],[72,3,1,"_CPPv4N4espp9JpegFrame9JpegFrameERK13RtpJpegPacket","espp::JpegFrame::JpegFrame"],[72,4,1,"_CPPv4N4espp9JpegFrame9JpegFrameEPKc6size_t","espp::JpegFrame::JpegFrame::data"],[72,4,1,"_CPPv4N4espp9JpegFrame9JpegFrameERK13RtpJpegPacket","espp::JpegFrame::JpegFrame::packet"],[72,4,1,"_CPPv4N4espp9JpegFrame9JpegFrameEPKc6size_t","espp::JpegFrame::JpegFrame::size"],[72,3,1,"_CPPv4N4espp9JpegFrame8add_scanERK13RtpJpegPacket","espp::JpegFrame::add_scan"],[72,4,1,"_CPPv4N4espp9JpegFrame8add_scanERK13RtpJpegPacket","espp::JpegFrame::add_scan::packet"],[72,3,1,"_CPPv4N4espp9JpegFrame6appendERK13RtpJpegPacket","espp::JpegFrame::append"],[72,4,1,"_CPPv4N4espp9JpegFrame6appendERK13RtpJpegPacket","espp::JpegFrame::append::packet"],[72,3,1,"_CPPv4NK4espp9JpegFrame8get_dataEv","espp::JpegFrame::get_data"],[72,3,1,"_CPPv4NK4espp9JpegFrame10get_headerEv","espp::JpegFrame::get_header"],[72,3,1,"_CPPv4NK4espp9JpegFrame10get_heightEv","espp::JpegFrame::get_height"],[72,3,1,"_CPPv4NK4espp9JpegFrame13get_scan_dataEv","espp::JpegFrame::get_scan_data"],[72,3,1,"_CPPv4NK4espp9JpegFrame9get_widthEv","espp::JpegFrame::get_width"],[72,3,1,"_CPPv4NK4espp9JpegFrame11is_completeEv","espp::JpegFrame::is_complete"],[72,2,1,"_CPPv4N4espp10JpegHeaderE","espp::JpegHeader"],[72,3,1,"_CPPv4N4espp10JpegHeader10JpegHeaderENSt11string_viewE","espp::JpegHeader::JpegHeader"],[72,3,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader"],[72,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderENSt11string_viewE","espp::JpegHeader::JpegHeader::data"],[72,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::height"],[72,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::q0_table"],[72,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::q1_table"],[72,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::width"],[72,3,1,"_CPPv4NK4espp10JpegHeader8get_dataEv","espp::JpegHeader::get_data"],[72,3,1,"_CPPv4NK4espp10JpegHeader10get_heightEv","espp::JpegHeader::get_height"],[72,3,1,"_CPPv4NK4espp10JpegHeader22get_quantization_tableEi","espp::JpegHeader::get_quantization_table"],[72,4,1,"_CPPv4NK4espp10JpegHeader22get_quantization_tableEi","espp::JpegHeader::get_quantization_table::index"],[72,3,1,"_CPPv4NK4espp10JpegHeader9get_widthEv","espp::JpegHeader::get_width"],[42,2,1,"_CPPv4N4espp11KeypadInputE","espp::KeypadInput"],[42,2,1,"_CPPv4N4espp11KeypadInput6ConfigE","espp::KeypadInput::Config"],[42,1,1,"_CPPv4N4espp11KeypadInput6Config9log_levelE","espp::KeypadInput::Config::log_level"],[42,1,1,"_CPPv4N4espp11KeypadInput6Config4readE","espp::KeypadInput::Config::read"],[42,3,1,"_CPPv4N4espp11KeypadInput11KeypadInputERK6Config","espp::KeypadInput::KeypadInput"],[42,4,1,"_CPPv4N4espp11KeypadInput11KeypadInputERK6Config","espp::KeypadInput::KeypadInput::config"],[42,3,1,"_CPPv4N4espp11KeypadInput16get_input_deviceEv","espp::KeypadInput::get_input_device"],[42,3,1,"_CPPv4N4espp11KeypadInputD0Ev","espp::KeypadInput::~KeypadInput"],[50,2,1,"_CPPv4N4espp3LedE","espp::Led"],[50,2,1,"_CPPv4N4espp3Led13ChannelConfigE","espp::Led::ChannelConfig"],[50,1,1,"_CPPv4N4espp3Led13ChannelConfig7channelE","espp::Led::ChannelConfig::channel"],[50,1,1,"_CPPv4N4espp3Led13ChannelConfig4dutyE","espp::Led::ChannelConfig::duty"],[50,1,1,"_CPPv4N4espp3Led13ChannelConfig4gpioE","espp::Led::ChannelConfig::gpio"],[50,1,1,"_CPPv4N4espp3Led13ChannelConfig13output_invertE","espp::Led::ChannelConfig::output_invert"],[50,1,1,"_CPPv4N4espp3Led13ChannelConfig10speed_modeE","espp::Led::ChannelConfig::speed_mode"],[50,1,1,"_CPPv4N4espp3Led13ChannelConfig5timerE","espp::Led::ChannelConfig::timer"],[50,2,1,"_CPPv4N4espp3Led6ConfigE","espp::Led::Config"],[50,1,1,"_CPPv4N4espp3Led6Config8channelsE","espp::Led::Config::channels"],[50,1,1,"_CPPv4N4espp3Led6Config15duty_resolutionE","espp::Led::Config::duty_resolution"],[50,1,1,"_CPPv4N4espp3Led6Config12frequency_hzE","espp::Led::Config::frequency_hz"],[50,1,1,"_CPPv4N4espp3Led6Config9log_levelE","espp::Led::Config::log_level"],[50,1,1,"_CPPv4N4espp3Led6Config10speed_modeE","espp::Led::Config::speed_mode"],[50,1,1,"_CPPv4N4espp3Led6Config5timerE","espp::Led::Config::timer"],[50,3,1,"_CPPv4N4espp3Led3LedERK6Config","espp::Led::Led"],[50,4,1,"_CPPv4N4espp3Led3LedERK6Config","espp::Led::Led::config"],[50,3,1,"_CPPv4N4espp3Led10can_changeE14ledc_channel_t","espp::Led::can_change"],[50,4,1,"_CPPv4N4espp3Led10can_changeE14ledc_channel_t","espp::Led::can_change::channel"],[50,3,1,"_CPPv4NK4espp3Led8get_dutyE14ledc_channel_t","espp::Led::get_duty"],[50,4,1,"_CPPv4NK4espp3Led8get_dutyE14ledc_channel_t","espp::Led::get_duty::channel"],[50,3,1,"_CPPv4N4espp3Led8set_dutyE14ledc_channel_tf","espp::Led::set_duty"],[50,4,1,"_CPPv4N4espp3Led8set_dutyE14ledc_channel_tf","espp::Led::set_duty::channel"],[50,4,1,"_CPPv4N4espp3Led8set_dutyE14ledc_channel_tf","espp::Led::set_duty::duty_percent"],[50,3,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time"],[50,4,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time::channel"],[50,4,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time::duty_percent"],[50,4,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time::fade_time_ms"],[50,3,1,"_CPPv4N4espp3LedD0Ev","espp::Led::~Led"],[51,2,1,"_CPPv4N4espp8LedStripE","espp::LedStrip"],[51,1,1,"_CPPv4N4espp8LedStrip18APA102_START_FRAMEE","espp::LedStrip::APA102_START_FRAME"],[51,6,1,"_CPPv4N4espp8LedStrip9ByteOrderE","espp::LedStrip::ByteOrder"],[51,7,1,"_CPPv4N4espp8LedStrip9ByteOrder3BGRE","espp::LedStrip::ByteOrder::BGR"],[51,7,1,"_CPPv4N4espp8LedStrip9ByteOrder3GRBE","espp::LedStrip::ByteOrder::GRB"],[51,7,1,"_CPPv4N4espp8LedStrip9ByteOrder3RGBE","espp::LedStrip::ByteOrder::RGB"],[51,2,1,"_CPPv4N4espp8LedStrip6ConfigE","espp::LedStrip::Config"],[51,1,1,"_CPPv4N4espp8LedStrip6Config10byte_orderE","espp::LedStrip::Config::byte_order"],[51,1,1,"_CPPv4N4espp8LedStrip6Config9end_frameE","espp::LedStrip::Config::end_frame"],[51,1,1,"_CPPv4N4espp8LedStrip6Config9log_levelE","espp::LedStrip::Config::log_level"],[51,1,1,"_CPPv4N4espp8LedStrip6Config8num_ledsE","espp::LedStrip::Config::num_leds"],[51,1,1,"_CPPv4N4espp8LedStrip6Config15send_brightnessE","espp::LedStrip::Config::send_brightness"],[51,1,1,"_CPPv4N4espp8LedStrip6Config11start_frameE","espp::LedStrip::Config::start_frame"],[51,1,1,"_CPPv4N4espp8LedStrip6Config5writeE","espp::LedStrip::Config::write"],[51,3,1,"_CPPv4N4espp8LedStrip8LedStripERK6Config","espp::LedStrip::LedStrip"],[51,4,1,"_CPPv4N4espp8LedStrip8LedStripERK6Config","espp::LedStrip::LedStrip::config"],[51,3,1,"_CPPv4NK4espp8LedStrip10byte_orderEv","espp::LedStrip::byte_order"],[51,3,1,"_CPPv4NK4espp8LedStrip8num_ledsEv","espp::LedStrip::num_leds"],[51,3,1,"_CPPv4N4espp8LedStrip7set_allE3Hsvf","espp::LedStrip::set_all"],[51,3,1,"_CPPv4N4espp8LedStrip7set_allE3Rgbf","espp::LedStrip::set_all"],[51,3,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::b"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE3Hsvf","espp::LedStrip::set_all::brightness"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE3Rgbf","espp::LedStrip::set_all::brightness"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::brightness"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::g"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE3Hsvf","espp::LedStrip::set_all::hsv"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::r"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE3Rgbf","espp::LedStrip::set_all::rgb"],[51,3,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel"],[51,3,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel"],[51,3,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::b"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel::brightness"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel::brightness"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::brightness"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::g"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel::hsv"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel::index"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel::index"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::index"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::r"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel::rgb"],[51,3,1,"_CPPv4N4espp8LedStrip10shift_leftEi","espp::LedStrip::shift_left"],[51,4,1,"_CPPv4N4espp8LedStrip10shift_leftEi","espp::LedStrip::shift_left::shift_by"],[51,3,1,"_CPPv4N4espp8LedStrip11shift_rightEi","espp::LedStrip::shift_right"],[51,4,1,"_CPPv4N4espp8LedStrip11shift_rightEi","espp::LedStrip::shift_right::shift_by"],[51,3,1,"_CPPv4N4espp8LedStrip4showEv","espp::LedStrip::show"],[51,8,1,"_CPPv4N4espp8LedStrip8write_fnE","espp::LedStrip::write_fn"],[11,2,1,"_CPPv4N4espp9LineInputE","espp::LineInput"],[11,8,1,"_CPPv4N4espp9LineInput7HistoryE","espp::LineInput::History"],[11,3,1,"_CPPv4N4espp9LineInput9LineInputEv","espp::LineInput::LineInput"],[11,3,1,"_CPPv4N4espp9LineInput10clear_lineEv","espp::LineInput::clear_line"],[11,3,1,"_CPPv4N4espp9LineInput12clear_screenEv","espp::LineInput::clear_screen"],[11,3,1,"_CPPv4N4espp9LineInput20clear_to_end_of_lineEv","espp::LineInput::clear_to_end_of_line"],[11,3,1,"_CPPv4N4espp9LineInput22clear_to_start_of_lineEv","espp::LineInput::clear_to_start_of_line"],[11,3,1,"_CPPv4NK4espp9LineInput11get_historyEv","espp::LineInput::get_history"],[11,3,1,"_CPPv4N4espp9LineInput17get_terminal_sizeERiRi","espp::LineInput::get_terminal_size"],[11,4,1,"_CPPv4N4espp9LineInput17get_terminal_sizeERiRi","espp::LineInput::get_terminal_size::height"],[11,4,1,"_CPPv4N4espp9LineInput17get_terminal_sizeERiRi","espp::LineInput::get_terminal_size::width"],[11,3,1,"_CPPv4N4espp9LineInput14get_user_inputERNSt7istreamE9prompt_fn","espp::LineInput::get_user_input"],[11,4,1,"_CPPv4N4espp9LineInput14get_user_inputERNSt7istreamE9prompt_fn","espp::LineInput::get_user_input::is"],[11,4,1,"_CPPv4N4espp9LineInput14get_user_inputERNSt7istreamE9prompt_fn","espp::LineInput::get_user_input::prompt"],[11,8,1,"_CPPv4N4espp9LineInput9prompt_fnE","espp::LineInput::prompt_fn"],[11,3,1,"_CPPv4N4espp9LineInput17set_handle_resizeEb","espp::LineInput::set_handle_resize"],[11,4,1,"_CPPv4N4espp9LineInput17set_handle_resizeEb","espp::LineInput::set_handle_resize::handle_resize"],[11,3,1,"_CPPv4N4espp9LineInput11set_historyERK7History","espp::LineInput::set_history"],[11,4,1,"_CPPv4N4espp9LineInput11set_historyERK7History","espp::LineInput::set_history::history"],[11,3,1,"_CPPv4N4espp9LineInput16set_history_sizeE6size_t","espp::LineInput::set_history_size"],[11,4,1,"_CPPv4N4espp9LineInput16set_history_sizeE6size_t","espp::LineInput::set_history_size::new_size"],[11,3,1,"_CPPv4N4espp9LineInputD0Ev","espp::LineInput::~LineInput"],[52,2,1,"_CPPv4N4espp6LoggerE","espp::Logger"],[52,2,1,"_CPPv4N4espp6Logger6ConfigE","espp::Logger::Config"],[52,1,1,"_CPPv4N4espp6Logger6Config5levelE","espp::Logger::Config::level"],[52,1,1,"_CPPv4N4espp6Logger6Config10rate_limitE","espp::Logger::Config::rate_limit"],[52,1,1,"_CPPv4N4espp6Logger6Config3tagE","espp::Logger::Config::tag"],[52,3,1,"_CPPv4N4espp6Logger6LoggerERK6Config","espp::Logger::Logger"],[52,4,1,"_CPPv4N4espp6Logger6LoggerERK6Config","espp::Logger::Logger::config"],[52,6,1,"_CPPv4N4espp6Logger9VerbosityE","espp::Logger::Verbosity"],[52,7,1,"_CPPv4N4espp6Logger9Verbosity5DEBUGE","espp::Logger::Verbosity::DEBUG"],[52,7,1,"_CPPv4N4espp6Logger9Verbosity5ERRORE","espp::Logger::Verbosity::ERROR"],[52,7,1,"_CPPv4N4espp6Logger9Verbosity4INFOE","espp::Logger::Verbosity::INFO"],[52,7,1,"_CPPv4N4espp6Logger9Verbosity4NONEE","espp::Logger::Verbosity::NONE"],[52,7,1,"_CPPv4N4espp6Logger9Verbosity4WARNE","espp::Logger::Verbosity::WARN"],[52,3,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug"],[52,5,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited"],[52,5,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error"],[52,5,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited"],[52,5,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format"],[52,5,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info"],[52,5,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited"],[52,5,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited::rt_fmt_str"],[52,3,1,"_CPPv4N4espp6Logger7set_tagEKNSt11string_viewE","espp::Logger::set_tag"],[52,4,1,"_CPPv4N4espp6Logger7set_tagEKNSt11string_viewE","espp::Logger::set_tag::tag"],[52,3,1,"_CPPv4N4espp6Logger13set_verbosityEK9Verbosity","espp::Logger::set_verbosity"],[52,4,1,"_CPPv4N4espp6Logger13set_verbosityEK9Verbosity","espp::Logger::set_verbosity::level"],[52,3,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn"],[52,5,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited"],[52,5,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited::rt_fmt_str"],[28,2,1,"_CPPv4N4espp13LowpassFilterE","espp::LowpassFilter"],[28,2,1,"_CPPv4N4espp13LowpassFilter6ConfigE","espp::LowpassFilter::Config"],[28,1,1,"_CPPv4N4espp13LowpassFilter6Config27normalized_cutoff_frequencyE","espp::LowpassFilter::Config::normalized_cutoff_frequency"],[28,1,1,"_CPPv4N4espp13LowpassFilter6Config8q_factorE","espp::LowpassFilter::Config::q_factor"],[28,3,1,"_CPPv4N4espp13LowpassFilter13LowpassFilterERK6Config","espp::LowpassFilter::LowpassFilter"],[28,4,1,"_CPPv4N4espp13LowpassFilter13LowpassFilterERK6Config","espp::LowpassFilter::LowpassFilter::config"],[28,3,1,"_CPPv4N4espp13LowpassFilterclEf","espp::LowpassFilter::operator()"],[28,4,1,"_CPPv4N4espp13LowpassFilterclEf","espp::LowpassFilter::operator()::input"],[28,3,1,"_CPPv4N4espp13LowpassFilter6updateEKf","espp::LowpassFilter::update"],[28,3,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update"],[28,4,1,"_CPPv4N4espp13LowpassFilter6updateEKf","espp::LowpassFilter::update::input"],[28,4,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update::input"],[28,4,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update::length"],[28,4,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update::output"],[48,2,1,"_CPPv4N4espp8Mcp23x17E","espp::Mcp23x17"],[48,2,1,"_CPPv4N4espp8Mcp23x176ConfigE","espp::Mcp23x17::Config"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config9auto_initE","espp::Mcp23x17::Config::auto_init"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config14device_addressE","espp::Mcp23x17::Config::device_address"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config9log_levelE","espp::Mcp23x17::Config::log_level"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config21port_0_direction_maskE","espp::Mcp23x17::Config::port_0_direction_mask"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config21port_0_interrupt_maskE","espp::Mcp23x17::Config::port_0_interrupt_mask"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config21port_1_direction_maskE","espp::Mcp23x17::Config::port_1_direction_mask"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config21port_1_interrupt_maskE","espp::Mcp23x17::Config::port_1_interrupt_mask"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config4readE","espp::Mcp23x17::Config::read"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config5writeE","espp::Mcp23x17::Config::write"],[48,1,1,"_CPPv4N4espp8Mcp23x1715DEFAULT_ADDRESSE","espp::Mcp23x17::DEFAULT_ADDRESS"],[48,3,1,"_CPPv4N4espp8Mcp23x178Mcp23x17ERK6Config","espp::Mcp23x17::Mcp23x17"],[48,4,1,"_CPPv4N4espp8Mcp23x178Mcp23x17ERK6Config","espp::Mcp23x17::Mcp23x17::config"],[48,6,1,"_CPPv4N4espp8Mcp23x174PortE","espp::Mcp23x17::Port"],[48,7,1,"_CPPv4N4espp8Mcp23x174Port5PORT0E","espp::Mcp23x17::Port::PORT0"],[48,7,1,"_CPPv4N4espp8Mcp23x174Port5PORT1E","espp::Mcp23x17::Port::PORT1"],[48,3,1,"_CPPv4N4espp8Mcp23x1721get_interrupt_captureE4PortRNSt10error_codeE","espp::Mcp23x17::get_interrupt_capture"],[48,4,1,"_CPPv4N4espp8Mcp23x1721get_interrupt_captureE4PortRNSt10error_codeE","espp::Mcp23x17::get_interrupt_capture::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1721get_interrupt_captureE4PortRNSt10error_codeE","espp::Mcp23x17::get_interrupt_capture::port"],[48,3,1,"_CPPv4N4espp8Mcp23x178get_pinsE4PortRNSt10error_codeE","espp::Mcp23x17::get_pins"],[48,3,1,"_CPPv4N4espp8Mcp23x178get_pinsERNSt10error_codeE","espp::Mcp23x17::get_pins"],[48,4,1,"_CPPv4N4espp8Mcp23x178get_pinsE4PortRNSt10error_codeE","espp::Mcp23x17::get_pins::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x178get_pinsERNSt10error_codeE","espp::Mcp23x17::get_pins::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x178get_pinsE4PortRNSt10error_codeE","espp::Mcp23x17::get_pins::port"],[48,3,1,"_CPPv4N4espp8Mcp23x1710initializeERNSt10error_codeE","espp::Mcp23x17::initialize"],[48,4,1,"_CPPv4N4espp8Mcp23x1710initializeERNSt10error_codeE","espp::Mcp23x17::initialize::ec"],[48,8,1,"_CPPv4N4espp8Mcp23x177read_fnE","espp::Mcp23x17::read_fn"],[48,3,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_direction"],[48,4,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_direction::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_direction::mask"],[48,4,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_direction::port"],[48,3,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_input_polarity"],[48,4,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_input_polarity::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_input_polarity::mask"],[48,4,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_input_polarity::port"],[48,3,1,"_CPPv4N4espp8Mcp23x1720set_interrupt_mirrorEbRNSt10error_codeE","espp::Mcp23x17::set_interrupt_mirror"],[48,4,1,"_CPPv4N4espp8Mcp23x1720set_interrupt_mirrorEbRNSt10error_codeE","espp::Mcp23x17::set_interrupt_mirror::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1720set_interrupt_mirrorEbRNSt10error_codeE","espp::Mcp23x17::set_interrupt_mirror::mirror"],[48,3,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_change"],[48,4,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_change::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_change::mask"],[48,4,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_change::port"],[48,3,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_value"],[48,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_value::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_value::pin_mask"],[48,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_value::port"],[48,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_value::val_mask"],[48,3,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_polarityEbRNSt10error_codeE","espp::Mcp23x17::set_interrupt_polarity"],[48,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_polarityEbRNSt10error_codeE","espp::Mcp23x17::set_interrupt_polarity::active_high"],[48,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_polarityEbRNSt10error_codeE","espp::Mcp23x17::set_interrupt_polarity::ec"],[48,3,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pins"],[48,4,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pins::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pins::output"],[48,4,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pins::port"],[48,3,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pull_up"],[48,4,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pull_up::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pull_up::mask"],[48,4,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pull_up::port"],[48,8,1,"_CPPv4N4espp8Mcp23x178write_fnE","espp::Mcp23x17::write_fn"],[22,2,1,"_CPPv4N4espp6Mt6701E","espp::Mt6701"],[22,1,1,"_CPPv4N4espp6Mt670121COUNTS_PER_REVOLUTIONE","espp::Mt6701::COUNTS_PER_REVOLUTION"],[22,1,1,"_CPPv4N4espp6Mt670123COUNTS_PER_REVOLUTION_FE","espp::Mt6701::COUNTS_PER_REVOLUTION_F"],[22,1,1,"_CPPv4N4espp6Mt670117COUNTS_TO_DEGREESE","espp::Mt6701::COUNTS_TO_DEGREES"],[22,1,1,"_CPPv4N4espp6Mt670117COUNTS_TO_RADIANSE","espp::Mt6701::COUNTS_TO_RADIANS"],[22,2,1,"_CPPv4N4espp6Mt67016ConfigE","espp::Mt6701::Config"],[22,1,1,"_CPPv4N4espp6Mt67016Config9auto_initE","espp::Mt6701::Config::auto_init"],[22,1,1,"_CPPv4N4espp6Mt67016Config14device_addressE","espp::Mt6701::Config::device_address"],[22,1,1,"_CPPv4N4espp6Mt67016Config4readE","espp::Mt6701::Config::read"],[22,1,1,"_CPPv4N4espp6Mt67016Config13update_periodE","espp::Mt6701::Config::update_period"],[22,1,1,"_CPPv4N4espp6Mt67016Config15velocity_filterE","espp::Mt6701::Config::velocity_filter"],[22,1,1,"_CPPv4N4espp6Mt67016Config5writeE","espp::Mt6701::Config::write"],[22,1,1,"_CPPv4N4espp6Mt670115DEFAULT_ADDRESSE","espp::Mt6701::DEFAULT_ADDRESS"],[22,3,1,"_CPPv4N4espp6Mt67016Mt6701ERK6Config","espp::Mt6701::Mt6701"],[22,4,1,"_CPPv4N4espp6Mt67016Mt6701ERK6Config","espp::Mt6701::Mt6701::config"],[22,1,1,"_CPPv4N4espp6Mt670118SECONDS_PER_MINUTEE","espp::Mt6701::SECONDS_PER_MINUTE"],[22,3,1,"_CPPv4NK4espp6Mt670115get_accumulatorEv","espp::Mt6701::get_accumulator"],[22,3,1,"_CPPv4NK4espp6Mt67019get_countEv","espp::Mt6701::get_count"],[22,3,1,"_CPPv4NK4espp6Mt670111get_degreesEv","espp::Mt6701::get_degrees"],[22,3,1,"_CPPv4NK4espp6Mt670122get_mechanical_degreesEv","espp::Mt6701::get_mechanical_degrees"],[22,3,1,"_CPPv4NK4espp6Mt670122get_mechanical_radiansEv","espp::Mt6701::get_mechanical_radians"],[22,3,1,"_CPPv4NK4espp6Mt670111get_radiansEv","espp::Mt6701::get_radians"],[22,3,1,"_CPPv4NK4espp6Mt67017get_rpmEv","espp::Mt6701::get_rpm"],[22,3,1,"_CPPv4N4espp6Mt670110initializeERNSt10error_codeE","espp::Mt6701::initialize"],[22,4,1,"_CPPv4N4espp6Mt670110initializeERNSt10error_codeE","espp::Mt6701::initialize::ec"],[22,3,1,"_CPPv4NK4espp6Mt670117needs_zero_searchEv","espp::Mt6701::needs_zero_search"],[22,8,1,"_CPPv4N4espp6Mt67017read_fnE","espp::Mt6701::read_fn"],[22,8,1,"_CPPv4N4espp6Mt670118velocity_filter_fnE","espp::Mt6701::velocity_filter_fn"],[22,8,1,"_CPPv4N4espp6Mt67018write_fnE","espp::Mt6701::write_fn"],[65,2,1,"_CPPv4N4espp4NdefE","espp::Ndef"],[65,6,1,"_CPPv4N4espp4Ndef7BleRoleE","espp::Ndef::BleRole"],[65,7,1,"_CPPv4N4espp4Ndef7BleRole12CENTRAL_ONLYE","espp::Ndef::BleRole::CENTRAL_ONLY"],[65,7,1,"_CPPv4N4espp4Ndef7BleRole18CENTRAL_PERIPHERALE","espp::Ndef::BleRole::CENTRAL_PERIPHERAL"],[65,7,1,"_CPPv4N4espp4Ndef7BleRole18PERIPHERAL_CENTRALE","espp::Ndef::BleRole::PERIPHERAL_CENTRAL"],[65,7,1,"_CPPv4N4espp4Ndef7BleRole15PERIPHERAL_ONLYE","espp::Ndef::BleRole::PERIPHERAL_ONLY"],[65,6,1,"_CPPv4N4espp4Ndef12BtAppearanceE","espp::Ndef::BtAppearance"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance5CLOCKE","espp::Ndef::BtAppearance::CLOCK"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance8COMPUTERE","espp::Ndef::BtAppearance::COMPUTER"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance7DISPLAYE","espp::Ndef::BtAppearance::DISPLAY"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance7GAMEPADE","espp::Ndef::BtAppearance::GAMEPAD"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance6GAMINGE","espp::Ndef::BtAppearance::GAMING"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance11GENERIC_HIDE","espp::Ndef::BtAppearance::GENERIC_HID"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance8JOYSTICKE","espp::Ndef::BtAppearance::JOYSTICK"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance8KEYBOARDE","espp::Ndef::BtAppearance::KEYBOARD"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance5MOUSEE","espp::Ndef::BtAppearance::MOUSE"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance5PHONEE","espp::Ndef::BtAppearance::PHONE"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance14REMOTE_CONTROLE","espp::Ndef::BtAppearance::REMOTE_CONTROL"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance8TOUCHPADE","espp::Ndef::BtAppearance::TOUCHPAD"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance7UNKNOWNE","espp::Ndef::BtAppearance::UNKNOWN"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance5WATCHE","espp::Ndef::BtAppearance::WATCH"],[65,6,1,"_CPPv4N4espp4Ndef5BtEirE","espp::Ndef::BtEir"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir10APPEARANCEE","espp::Ndef::BtEir::APPEARANCE"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir15CLASS_OF_DEVICEE","espp::Ndef::BtEir::CLASS_OF_DEVICE"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir5FLAGSE","espp::Ndef::BtEir::FLAGS"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir7LE_ROLEE","espp::Ndef::BtEir::LE_ROLE"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir18LE_SC_CONFIRMATIONE","espp::Ndef::BtEir::LE_SC_CONFIRMATION"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir12LE_SC_RANDOME","espp::Ndef::BtEir::LE_SC_RANDOM"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir15LONG_LOCAL_NAMEE","espp::Ndef::BtEir::LONG_LOCAL_NAME"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir3MACE","espp::Ndef::BtEir::MAC"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir22SECURITY_MANAGER_FLAGSE","espp::Ndef::BtEir::SECURITY_MANAGER_FLAGS"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir19SECURITY_MANAGER_TKE","espp::Ndef::BtEir::SECURITY_MANAGER_TK"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir16SHORT_LOCAL_NAMEE","espp::Ndef::BtEir::SHORT_LOCAL_NAME"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir12SP_HASH_C192E","espp::Ndef::BtEir::SP_HASH_C192"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir12SP_HASH_C256E","espp::Ndef::BtEir::SP_HASH_C256"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir12SP_HASH_R256E","espp::Ndef::BtEir::SP_HASH_R256"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir14SP_RANDOM_R192E","espp::Ndef::BtEir::SP_RANDOM_R192"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir14TX_POWER_LEVELE","espp::Ndef::BtEir::TX_POWER_LEVEL"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir22UUIDS_128_BIT_COMPLETEE","espp::Ndef::BtEir::UUIDS_128_BIT_COMPLETE"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir21UUIDS_128_BIT_PARTIALE","espp::Ndef::BtEir::UUIDS_128_BIT_PARTIAL"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir21UUIDS_16_BIT_COMPLETEE","espp::Ndef::BtEir::UUIDS_16_BIT_COMPLETE"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir20UUIDS_16_BIT_PARTIALE","espp::Ndef::BtEir::UUIDS_16_BIT_PARTIAL"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir21UUIDS_32_BIT_COMPLETEE","espp::Ndef::BtEir::UUIDS_32_BIT_COMPLETE"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir20UUIDS_32_BIT_PARTIALE","espp::Ndef::BtEir::UUIDS_32_BIT_PARTIAL"],[65,6,1,"_CPPv4N4espp4Ndef6BtTypeE","espp::Ndef::BtType"],[65,7,1,"_CPPv4N4espp4Ndef6BtType3BLEE","espp::Ndef::BtType::BLE"],[65,7,1,"_CPPv4N4espp4Ndef6BtType5BREDRE","espp::Ndef::BtType::BREDR"],[65,6,1,"_CPPv4N4espp4Ndef17CarrierPowerStateE","espp::Ndef::CarrierPowerState"],[65,7,1,"_CPPv4N4espp4Ndef17CarrierPowerState10ACTIVATINGE","espp::Ndef::CarrierPowerState::ACTIVATING"],[65,7,1,"_CPPv4N4espp4Ndef17CarrierPowerState6ACTIVEE","espp::Ndef::CarrierPowerState::ACTIVE"],[65,7,1,"_CPPv4N4espp4Ndef17CarrierPowerState8INACTIVEE","espp::Ndef::CarrierPowerState::INACTIVE"],[65,7,1,"_CPPv4N4espp4Ndef17CarrierPowerState7UNKNOWNE","espp::Ndef::CarrierPowerState::UNKNOWN"],[65,1,1,"_CPPv4N4espp4Ndef16HANDOVER_VERSIONE","espp::Ndef::HANDOVER_VERSION"],[65,3,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef"],[65,4,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef::payload"],[65,4,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef::tnf"],[65,4,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef::type"],[65,6,1,"_CPPv4N4espp4Ndef3TNFE","espp::Ndef::TNF"],[65,7,1,"_CPPv4N4espp4Ndef3TNF12ABSOLUTE_URIE","espp::Ndef::TNF::ABSOLUTE_URI"],[65,7,1,"_CPPv4N4espp4Ndef3TNF5EMPTYE","espp::Ndef::TNF::EMPTY"],[65,7,1,"_CPPv4N4espp4Ndef3TNF13EXTERNAL_TYPEE","espp::Ndef::TNF::EXTERNAL_TYPE"],[65,7,1,"_CPPv4N4espp4Ndef3TNF10MIME_MEDIAE","espp::Ndef::TNF::MIME_MEDIA"],[65,7,1,"_CPPv4N4espp4Ndef3TNF8RESERVEDE","espp::Ndef::TNF::RESERVED"],[65,7,1,"_CPPv4N4espp4Ndef3TNF9UNCHANGEDE","espp::Ndef::TNF::UNCHANGED"],[65,7,1,"_CPPv4N4espp4Ndef3TNF7UNKNOWNE","espp::Ndef::TNF::UNKNOWN"],[65,7,1,"_CPPv4N4espp4Ndef3TNF10WELL_KNOWNE","espp::Ndef::TNF::WELL_KNOWN"],[65,6,1,"_CPPv4N4espp4Ndef3UicE","espp::Ndef::Uic"],[65,7,1,"_CPPv4N4espp4Ndef3Uic6BTGOEPE","espp::Ndef::Uic::BTGOEP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic7BTL2CAPE","espp::Ndef::Uic::BTL2CAP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic5BTSPPE","espp::Ndef::Uic::BTSPP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3DAVE","espp::Ndef::Uic::DAV"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4FILEE","espp::Ndef::Uic::FILE"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3FTPE","espp::Ndef::Uic::FTP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4FTPSE","espp::Ndef::Uic::FTPS"],[65,7,1,"_CPPv4N4espp4Ndef3Uic8FTP_ANONE","espp::Ndef::Uic::FTP_ANON"],[65,7,1,"_CPPv4N4espp4Ndef3Uic7FTP_FTPE","espp::Ndef::Uic::FTP_FTP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4HTTPE","espp::Ndef::Uic::HTTP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic5HTTPSE","espp::Ndef::Uic::HTTPS"],[65,7,1,"_CPPv4N4espp4Ndef3Uic9HTTPS_WWWE","espp::Ndef::Uic::HTTPS_WWW"],[65,7,1,"_CPPv4N4espp4Ndef3Uic8HTTP_WWWE","espp::Ndef::Uic::HTTP_WWW"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4IMAPE","espp::Ndef::Uic::IMAP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic8IRDAOBEXE","espp::Ndef::Uic::IRDAOBEX"],[65,7,1,"_CPPv4N4espp4Ndef3Uic6MAILTOE","espp::Ndef::Uic::MAILTO"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4NEWSE","espp::Ndef::Uic::NEWS"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3NFSE","espp::Ndef::Uic::NFS"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4NONEE","espp::Ndef::Uic::NONE"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3POPE","espp::Ndef::Uic::POP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4RSTPE","espp::Ndef::Uic::RSTP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4SFTPE","espp::Ndef::Uic::SFTP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3SIPE","espp::Ndef::Uic::SIP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4SIPSE","espp::Ndef::Uic::SIPS"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3SMBE","espp::Ndef::Uic::SMB"],[65,7,1,"_CPPv4N4espp4Ndef3Uic7TCPOBEXE","espp::Ndef::Uic::TCPOBEX"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3TELE","espp::Ndef::Uic::TEL"],[65,7,1,"_CPPv4N4espp4Ndef3Uic6TELNETE","espp::Ndef::Uic::TELNET"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4TFTPE","espp::Ndef::Uic::TFTP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3URNE","espp::Ndef::Uic::URN"],[65,7,1,"_CPPv4N4espp4Ndef3Uic7URN_EPCE","espp::Ndef::Uic::URN_EPC"],[65,7,1,"_CPPv4N4espp4Ndef3Uic10URN_EPC_IDE","espp::Ndef::Uic::URN_EPC_ID"],[65,7,1,"_CPPv4N4espp4Ndef3Uic11URN_EPC_PATE","espp::Ndef::Uic::URN_EPC_PAT"],[65,7,1,"_CPPv4N4espp4Ndef3Uic11URN_EPC_RAWE","espp::Ndef::Uic::URN_EPC_RAW"],[65,7,1,"_CPPv4N4espp4Ndef3Uic11URN_EPC_TAGE","espp::Ndef::Uic::URN_EPC_TAG"],[65,7,1,"_CPPv4N4espp4Ndef3Uic7URN_NFCE","espp::Ndef::Uic::URN_NFC"],[65,6,1,"_CPPv4N4espp4Ndef22WifiAuthenticationTypeE","espp::Ndef::WifiAuthenticationType"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType4OPENE","espp::Ndef::WifiAuthenticationType::OPEN"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType6SHAREDE","espp::Ndef::WifiAuthenticationType::SHARED"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType15WPA2_ENTERPRISEE","espp::Ndef::WifiAuthenticationType::WPA2_ENTERPRISE"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType13WPA2_PERSONALE","espp::Ndef::WifiAuthenticationType::WPA2_PERSONAL"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType14WPA_ENTERPRISEE","espp::Ndef::WifiAuthenticationType::WPA_ENTERPRISE"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType12WPA_PERSONALE","espp::Ndef::WifiAuthenticationType::WPA_PERSONAL"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType17WPA_WPA2_PERSONALE","espp::Ndef::WifiAuthenticationType::WPA_WPA2_PERSONAL"],[65,2,1,"_CPPv4N4espp4Ndef10WifiConfigE","espp::Ndef::WifiConfig"],[65,1,1,"_CPPv4N4espp4Ndef10WifiConfig14authenticationE","espp::Ndef::WifiConfig::authentication"],[65,1,1,"_CPPv4N4espp4Ndef10WifiConfig10encryptionE","espp::Ndef::WifiConfig::encryption"],[65,1,1,"_CPPv4N4espp4Ndef10WifiConfig3keyE","espp::Ndef::WifiConfig::key"],[65,1,1,"_CPPv4N4espp4Ndef10WifiConfig11mac_addressE","espp::Ndef::WifiConfig::mac_address"],[65,1,1,"_CPPv4N4espp4Ndef10WifiConfig4ssidE","espp::Ndef::WifiConfig::ssid"],[65,6,1,"_CPPv4N4espp4Ndef18WifiEncryptionTypeE","espp::Ndef::WifiEncryptionType"],[65,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType3AESE","espp::Ndef::WifiEncryptionType::AES"],[65,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType4NONEE","espp::Ndef::WifiEncryptionType::NONE"],[65,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType4TKIPE","espp::Ndef::WifiEncryptionType::TKIP"],[65,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType3WEPE","espp::Ndef::WifiEncryptionType::WEP"],[65,3,1,"_CPPv4NK4espp4Ndef6get_idEv","espp::Ndef::get_id"],[65,3,1,"_CPPv4NK4espp4Ndef8get_sizeEv","espp::Ndef::get_size"],[65,3,1,"_CPPv4N4espp4Ndef24make_alternative_carrierERK17CarrierPowerStatei","espp::Ndef::make_alternative_carrier"],[65,4,1,"_CPPv4N4espp4Ndef24make_alternative_carrierERK17CarrierPowerStatei","espp::Ndef::make_alternative_carrier::carrier_data_ref"],[65,4,1,"_CPPv4N4espp4Ndef24make_alternative_carrierERK17CarrierPowerStatei","espp::Ndef::make_alternative_carrier::power_state"],[65,3,1,"_CPPv4N4espp4Ndef21make_android_launcherENSt11string_viewE","espp::Ndef::make_android_launcher"],[65,4,1,"_CPPv4N4espp4Ndef21make_android_launcherENSt11string_viewE","espp::Ndef::make_android_launcher::uri"],[65,3,1,"_CPPv4N4espp4Ndef21make_handover_requestEi","espp::Ndef::make_handover_request"],[65,4,1,"_CPPv4N4espp4Ndef21make_handover_requestEi","espp::Ndef::make_handover_request::carrier_data_ref"],[65,3,1,"_CPPv4N4espp4Ndef20make_handover_selectEi","espp::Ndef::make_handover_select"],[65,4,1,"_CPPv4N4espp4Ndef20make_handover_selectEi","espp::Ndef::make_handover_select::carrier_data_ref"],[65,3,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::appearance"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::confirm_value"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::mac_addr"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::name"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::random_value"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::role"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::tk"],[65,3,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_oob_pairing"],[65,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_oob_pairing::confirm_value"],[65,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_oob_pairing::device_class"],[65,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_oob_pairing::mac_addr"],[65,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_oob_pairing::name"],[65,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_oob_pairing::random_value"],[65,3,1,"_CPPv4N4espp4Ndef9make_textENSt11string_viewE","espp::Ndef::make_text"],[65,4,1,"_CPPv4N4espp4Ndef9make_textENSt11string_viewE","espp::Ndef::make_text::text"],[65,3,1,"_CPPv4N4espp4Ndef8make_uriENSt11string_viewE3Uic","espp::Ndef::make_uri"],[65,4,1,"_CPPv4N4espp4Ndef8make_uriENSt11string_viewE3Uic","espp::Ndef::make_uri::uic"],[65,4,1,"_CPPv4N4espp4Ndef8make_uriENSt11string_viewE3Uic","espp::Ndef::make_uri::uri"],[65,3,1,"_CPPv4N4espp4Ndef16make_wifi_configERK10WifiConfig","espp::Ndef::make_wifi_config"],[65,4,1,"_CPPv4N4espp4Ndef16make_wifi_configERK10WifiConfig","espp::Ndef::make_wifi_config::config"],[65,3,1,"_CPPv4N4espp4Ndef7payloadEv","espp::Ndef::payload"],[65,3,1,"_CPPv4N4espp4Ndef9serializeEbb","espp::Ndef::serialize"],[65,4,1,"_CPPv4N4espp4Ndef9serializeEbb","espp::Ndef::serialize::message_begin"],[65,4,1,"_CPPv4N4espp4Ndef9serializeEbb","espp::Ndef::serialize::message_end"],[65,3,1,"_CPPv4N4espp4Ndef6set_idEi","espp::Ndef::set_id"],[65,4,1,"_CPPv4N4espp4Ndef6set_idEi","espp::Ndef::set_id::id"],[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"],[67,2,1,"_CPPv4N4espp3PidE","espp::Pid"],[67,2,1,"_CPPv4N4espp3Pid6ConfigE","espp::Pid::Config"],[67,1,1,"_CPPv4N4espp3Pid6Config14integrator_maxE","espp::Pid::Config::integrator_max"],[67,1,1,"_CPPv4N4espp3Pid6Config14integrator_minE","espp::Pid::Config::integrator_min"],[67,1,1,"_CPPv4N4espp3Pid6Config2kdE","espp::Pid::Config::kd"],[67,1,1,"_CPPv4N4espp3Pid6Config2kiE","espp::Pid::Config::ki"],[67,1,1,"_CPPv4N4espp3Pid6Config2kpE","espp::Pid::Config::kp"],[67,1,1,"_CPPv4N4espp3Pid6Config9log_levelE","espp::Pid::Config::log_level"],[67,1,1,"_CPPv4N4espp3Pid6Config10output_maxE","espp::Pid::Config::output_max"],[67,1,1,"_CPPv4N4espp3Pid6Config10output_minE","espp::Pid::Config::output_min"],[67,3,1,"_CPPv4N4espp3Pid3PidERK6Config","espp::Pid::Pid"],[67,4,1,"_CPPv4N4espp3Pid3PidERK6Config","espp::Pid::Pid::config"],[67,3,1,"_CPPv4N4espp3Pid12change_gainsERK6Configb","espp::Pid::change_gains"],[67,4,1,"_CPPv4N4espp3Pid12change_gainsERK6Configb","espp::Pid::change_gains::config"],[67,4,1,"_CPPv4N4espp3Pid12change_gainsERK6Configb","espp::Pid::change_gains::reset_state"],[67,3,1,"_CPPv4N4espp3Pid5clearEv","espp::Pid::clear"],[67,3,1,"_CPPv4NK4espp3Pid10get_configEv","espp::Pid::get_config"],[67,3,1,"_CPPv4NK4espp3Pid9get_errorEv","espp::Pid::get_error"],[67,3,1,"_CPPv4NK4espp3Pid14get_integratorEv","espp::Pid::get_integrator"],[67,3,1,"_CPPv4N4espp3PidclEf","espp::Pid::operator()"],[67,4,1,"_CPPv4N4espp3PidclEf","espp::Pid::operator()::error"],[67,3,1,"_CPPv4N4espp3Pid10set_configERK6Configb","espp::Pid::set_config"],[67,4,1,"_CPPv4N4espp3Pid10set_configERK6Configb","espp::Pid::set_config::config"],[67,4,1,"_CPPv4N4espp3Pid10set_configERK6Configb","espp::Pid::set_config::reset_state"],[67,3,1,"_CPPv4N4espp3Pid6updateEf","espp::Pid::update"],[67,4,1,"_CPPv4N4espp3Pid6updateEf","espp::Pid::update::error"],[68,2,1,"_CPPv4N4espp8QwiicNesE","espp::QwiicNes"],[68,6,1,"_CPPv4N4espp8QwiicNes6ButtonE","espp::QwiicNes::Button"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button1AE","espp::QwiicNes::Button::A"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button1BE","espp::QwiicNes::Button::B"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button4DOWNE","espp::QwiicNes::Button::DOWN"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button4LEFTE","espp::QwiicNes::Button::LEFT"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button5RIGHTE","espp::QwiicNes::Button::RIGHT"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button6SELECTE","espp::QwiicNes::Button::SELECT"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button5STARTE","espp::QwiicNes::Button::START"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button2UPE","espp::QwiicNes::Button::UP"],[68,2,1,"_CPPv4N4espp8QwiicNes11ButtonStateE","espp::QwiicNes::ButtonState"],[68,2,1,"_CPPv4N4espp8QwiicNes6ConfigE","espp::QwiicNes::Config"],[68,1,1,"_CPPv4N4espp8QwiicNes6Config9log_levelE","espp::QwiicNes::Config::log_level"],[68,1,1,"_CPPv4N4espp8QwiicNes6Config5writeE","espp::QwiicNes::Config::write"],[68,1,1,"_CPPv4N4espp8QwiicNes6Config10write_readE","espp::QwiicNes::Config::write_read"],[68,1,1,"_CPPv4N4espp8QwiicNes15DEFAULT_ADDRESSE","espp::QwiicNes::DEFAULT_ADDRESS"],[68,3,1,"_CPPv4N4espp8QwiicNes8QwiicNesERK6Config","espp::QwiicNes::QwiicNes"],[68,4,1,"_CPPv4N4espp8QwiicNes8QwiicNesERK6Config","espp::QwiicNes::QwiicNes::config"],[68,3,1,"_CPPv4NK4espp8QwiicNes16get_button_stateEv","espp::QwiicNes::get_button_state"],[68,3,1,"_CPPv4N4espp8QwiicNes10is_pressedE7uint8_t6Button","espp::QwiicNes::is_pressed"],[68,3,1,"_CPPv4NK4espp8QwiicNes10is_pressedE6Button","espp::QwiicNes::is_pressed"],[68,4,1,"_CPPv4N4espp8QwiicNes10is_pressedE7uint8_t6Button","espp::QwiicNes::is_pressed::button"],[68,4,1,"_CPPv4NK4espp8QwiicNes10is_pressedE6Button","espp::QwiicNes::is_pressed::button"],[68,4,1,"_CPPv4N4espp8QwiicNes10is_pressedE7uint8_t6Button","espp::QwiicNes::is_pressed::state"],[68,3,1,"_CPPv4NK4espp8QwiicNes12read_addressERNSt10error_codeE","espp::QwiicNes::read_address"],[68,4,1,"_CPPv4NK4espp8QwiicNes12read_addressERNSt10error_codeE","espp::QwiicNes::read_address::ec"],[68,3,1,"_CPPv4NK4espp8QwiicNes18read_current_stateERNSt10error_codeE","espp::QwiicNes::read_current_state"],[68,4,1,"_CPPv4NK4espp8QwiicNes18read_current_stateERNSt10error_codeE","espp::QwiicNes::read_current_state::ec"],[68,3,1,"_CPPv4N4espp8QwiicNes6updateERNSt10error_codeE","espp::QwiicNes::update"],[68,4,1,"_CPPv4N4espp8QwiicNes6updateERNSt10error_codeE","espp::QwiicNes::update::ec"],[68,3,1,"_CPPv4N4espp8QwiicNes14update_addressE7uint8_tRNSt10error_codeE","espp::QwiicNes::update_address"],[68,4,1,"_CPPv4N4espp8QwiicNes14update_addressE7uint8_tRNSt10error_codeE","espp::QwiicNes::update_address::ec"],[68,4,1,"_CPPv4N4espp8QwiicNes14update_addressE7uint8_tRNSt10error_codeE","espp::QwiicNes::update_address::new_address"],[68,8,1,"_CPPv4N4espp8QwiicNes8write_fnE","espp::QwiicNes::write_fn"],[68,8,1,"_CPPv4N4espp8QwiicNes13write_read_fnE","espp::QwiicNes::write_read_fn"],[57,2,1,"_CPPv4I0EN4espp11RangeMapperE","espp::RangeMapper"],[57,2,1,"_CPPv4N4espp11RangeMapper6ConfigE","espp::RangeMapper::Config"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config6centerE","espp::RangeMapper::Config::center"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config8deadbandE","espp::RangeMapper::Config::deadband"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config12invert_inputE","espp::RangeMapper::Config::invert_input"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config13invert_outputE","espp::RangeMapper::Config::invert_output"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config7maximumE","espp::RangeMapper::Config::maximum"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config7minimumE","espp::RangeMapper::Config::minimum"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config13output_centerE","espp::RangeMapper::Config::output_center"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config12output_rangeE","espp::RangeMapper::Config::output_range"],[57,3,1,"_CPPv4N4espp11RangeMapper11RangeMapperERK6Config","espp::RangeMapper::RangeMapper"],[57,4,1,"_CPPv4N4espp11RangeMapper11RangeMapperERK6Config","espp::RangeMapper::RangeMapper::config"],[57,5,1,"_CPPv4I0EN4espp11RangeMapperE","espp::RangeMapper::T"],[57,3,1,"_CPPv4N4espp11RangeMapper9configureERK6Config","espp::RangeMapper::configure"],[57,4,1,"_CPPv4N4espp11RangeMapper9configureERK6Config","espp::RangeMapper::configure::config"],[57,3,1,"_CPPv4NK4espp11RangeMapper17get_output_centerEv","espp::RangeMapper::get_output_center"],[57,3,1,"_CPPv4NK4espp11RangeMapper14get_output_maxEv","espp::RangeMapper::get_output_max"],[57,3,1,"_CPPv4NK4espp11RangeMapper14get_output_minEv","espp::RangeMapper::get_output_min"],[57,3,1,"_CPPv4NK4espp11RangeMapper16get_output_rangeEv","espp::RangeMapper::get_output_range"],[57,3,1,"_CPPv4N4espp11RangeMapper3mapERK1T","espp::RangeMapper::map"],[57,4,1,"_CPPv4N4espp11RangeMapper3mapERK1T","espp::RangeMapper::map::v"],[12,2,1,"_CPPv4N4espp3RgbE","espp::Rgb"],[12,3,1,"_CPPv4N4espp3Rgb3RgbERK3Hsv","espp::Rgb::Rgb"],[12,3,1,"_CPPv4N4espp3Rgb3RgbERK3Rgb","espp::Rgb::Rgb"],[12,3,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb"],[12,4,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb::b"],[12,4,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb::g"],[12,4,1,"_CPPv4N4espp3Rgb3RgbERK3Hsv","espp::Rgb::Rgb::hsv"],[12,4,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb::r"],[12,4,1,"_CPPv4N4espp3Rgb3RgbERK3Rgb","espp::Rgb::Rgb::rgb"],[12,1,1,"_CPPv4N4espp3Rgb1bE","espp::Rgb::b"],[12,1,1,"_CPPv4N4espp3Rgb1gE","espp::Rgb::g"],[12,3,1,"_CPPv4NK4espp3Rgb3hsvEv","espp::Rgb::hsv"],[12,3,1,"_CPPv4NK4espp3RgbplERK3Rgb","espp::Rgb::operator+"],[12,4,1,"_CPPv4NK4espp3RgbplERK3Rgb","espp::Rgb::operator+::rhs"],[12,3,1,"_CPPv4N4espp3RgbpLERK3Rgb","espp::Rgb::operator+="],[12,4,1,"_CPPv4N4espp3RgbpLERK3Rgb","espp::Rgb::operator+=::rhs"],[12,1,1,"_CPPv4N4espp3Rgb1rE","espp::Rgb::r"],[69,2,1,"_CPPv4N4espp3RmtE","espp::Rmt"],[69,2,1,"_CPPv4N4espp3Rmt6ConfigE","espp::Rmt::Config"],[69,1,1,"_CPPv4N4espp3Rmt6Config10block_sizeE","espp::Rmt::Config::block_size"],[69,1,1,"_CPPv4N4espp3Rmt6Config9clock_srcE","espp::Rmt::Config::clock_src"],[69,1,1,"_CPPv4N4espp3Rmt6Config11dma_enabledE","espp::Rmt::Config::dma_enabled"],[69,1,1,"_CPPv4N4espp3Rmt6Config8gpio_numE","espp::Rmt::Config::gpio_num"],[69,1,1,"_CPPv4N4espp3Rmt6Config9log_levelE","espp::Rmt::Config::log_level"],[69,1,1,"_CPPv4N4espp3Rmt6Config13resolution_hzE","espp::Rmt::Config::resolution_hz"],[69,1,1,"_CPPv4N4espp3Rmt6Config23transaction_queue_depthE","espp::Rmt::Config::transaction_queue_depth"],[69,3,1,"_CPPv4N4espp3Rmt3RmtERK6Config","espp::Rmt::Rmt"],[69,4,1,"_CPPv4N4espp3Rmt3RmtERK6Config","espp::Rmt::Rmt::config"],[69,3,1,"_CPPv4N4espp3Rmt8transmitEPK7uint8_t6size_t","espp::Rmt::transmit"],[69,4,1,"_CPPv4N4espp3Rmt8transmitEPK7uint8_t6size_t","espp::Rmt::transmit::data"],[69,4,1,"_CPPv4N4espp3Rmt8transmitEPK7uint8_t6size_t","espp::Rmt::transmit::length"],[69,3,1,"_CPPv4N4espp3RmtD0Ev","espp::Rmt::~Rmt"],[69,2,1,"_CPPv4N4espp10RmtEncoderE","espp::RmtEncoder"],[69,2,1,"_CPPv4N4espp10RmtEncoder6ConfigE","espp::RmtEncoder::Config"],[69,1,1,"_CPPv4N4espp10RmtEncoder6Config20bytes_encoder_configE","espp::RmtEncoder::Config::bytes_encoder_config"],[69,1,1,"_CPPv4N4espp10RmtEncoder6Config3delE","espp::RmtEncoder::Config::del"],[69,1,1,"_CPPv4N4espp10RmtEncoder6Config6encodeE","espp::RmtEncoder::Config::encode"],[69,1,1,"_CPPv4N4espp10RmtEncoder6Config5resetE","espp::RmtEncoder::Config::reset"],[69,3,1,"_CPPv4N4espp10RmtEncoder10RmtEncoderERK6Config","espp::RmtEncoder::RmtEncoder"],[69,4,1,"_CPPv4N4espp10RmtEncoder10RmtEncoderERK6Config","espp::RmtEncoder::RmtEncoder::config"],[69,8,1,"_CPPv4N4espp10RmtEncoder9delete_fnE","espp::RmtEncoder::delete_fn"],[69,8,1,"_CPPv4N4espp10RmtEncoder9encode_fnE","espp::RmtEncoder::encode_fn"],[69,3,1,"_CPPv4NK4espp10RmtEncoder6handleEv","espp::RmtEncoder::handle"],[69,8,1,"_CPPv4N4espp10RmtEncoder8reset_fnE","espp::RmtEncoder::reset_fn"],[69,3,1,"_CPPv4N4espp10RmtEncoderD0Ev","espp::RmtEncoder::~RmtEncoder"],[72,2,1,"_CPPv4N4espp10RtcpPacketE","espp::RtcpPacket"],[72,2,1,"_CPPv4N4espp13RtpJpegPacketE","espp::RtpJpegPacket"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::data"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::frag_type"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::frag_type"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::height"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::height"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::offset"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q0"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q1"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::scan_data"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::scan_data"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::type_specific"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::type_specific"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::width"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::width"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket8get_dataEv","espp::RtpJpegPacket::get_data"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket10get_heightEv","espp::RtpJpegPacket::get_height"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket13get_jpeg_dataEv","espp::RtpJpegPacket::get_jpeg_data"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket16get_mjpeg_headerEv","espp::RtpJpegPacket::get_mjpeg_header"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket16get_num_q_tablesEv","espp::RtpJpegPacket::get_num_q_tables"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket10get_offsetEv","espp::RtpJpegPacket::get_offset"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket10get_packetEv","espp::RtpJpegPacket::get_packet"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket11get_payloadEv","espp::RtpJpegPacket::get_payload"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket5get_qEv","espp::RtpJpegPacket::get_q"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket11get_q_tableEi","espp::RtpJpegPacket::get_q_table"],[72,4,1,"_CPPv4NK4espp13RtpJpegPacket11get_q_tableEi","espp::RtpJpegPacket::get_q_table::index"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket14get_rpt_headerEv","espp::RtpJpegPacket::get_rpt_header"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket19get_rtp_header_sizeEv","espp::RtpJpegPacket::get_rtp_header_size"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket17get_type_specificEv","espp::RtpJpegPacket::get_type_specific"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket11get_versionEv","espp::RtpJpegPacket::get_version"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket9get_widthEv","espp::RtpJpegPacket::get_width"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket12has_q_tablesEv","espp::RtpJpegPacket::has_q_tables"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket9serializeEv","espp::RtpJpegPacket::serialize"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket11set_payloadENSt11string_viewE","espp::RtpJpegPacket::set_payload"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket11set_payloadENSt11string_viewE","espp::RtpJpegPacket::set_payload::payload"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket11set_versionEi","espp::RtpJpegPacket::set_version"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket11set_versionEi","espp::RtpJpegPacket::set_version::version"],[72,2,1,"_CPPv4N4espp9RtpPacketE","espp::RtpPacket"],[72,3,1,"_CPPv4N4espp9RtpPacket9RtpPacketE6size_t","espp::RtpPacket::RtpPacket"],[72,3,1,"_CPPv4N4espp9RtpPacket9RtpPacketENSt11string_viewE","espp::RtpPacket::RtpPacket"],[72,3,1,"_CPPv4N4espp9RtpPacket9RtpPacketEv","espp::RtpPacket::RtpPacket"],[72,4,1,"_CPPv4N4espp9RtpPacket9RtpPacketENSt11string_viewE","espp::RtpPacket::RtpPacket::data"],[72,4,1,"_CPPv4N4espp9RtpPacket9RtpPacketE6size_t","espp::RtpPacket::RtpPacket::payload_size"],[72,3,1,"_CPPv4NK4espp9RtpPacket8get_dataEv","espp::RtpPacket::get_data"],[72,3,1,"_CPPv4N4espp9RtpPacket10get_packetEv","espp::RtpPacket::get_packet"],[72,3,1,"_CPPv4NK4espp9RtpPacket11get_payloadEv","espp::RtpPacket::get_payload"],[72,3,1,"_CPPv4NK4espp9RtpPacket14get_rpt_headerEv","espp::RtpPacket::get_rpt_header"],[72,3,1,"_CPPv4NK4espp9RtpPacket19get_rtp_header_sizeEv","espp::RtpPacket::get_rtp_header_size"],[72,3,1,"_CPPv4NK4espp9RtpPacket11get_versionEv","espp::RtpPacket::get_version"],[72,3,1,"_CPPv4N4espp9RtpPacket9serializeEv","espp::RtpPacket::serialize"],[72,3,1,"_CPPv4N4espp9RtpPacket11set_payloadENSt11string_viewE","espp::RtpPacket::set_payload"],[72,4,1,"_CPPv4N4espp9RtpPacket11set_payloadENSt11string_viewE","espp::RtpPacket::set_payload::payload"],[72,3,1,"_CPPv4N4espp9RtpPacket11set_versionEi","espp::RtpPacket::set_version"],[72,4,1,"_CPPv4N4espp9RtpPacket11set_versionEi","espp::RtpPacket::set_version::version"],[72,2,1,"_CPPv4N4espp10RtspClientE","espp::RtspClient"],[72,2,1,"_CPPv4N4espp10RtspClient6ConfigE","espp::RtspClient::Config"],[72,1,1,"_CPPv4N4espp10RtspClient6Config9log_levelE","espp::RtspClient::Config::log_level"],[72,1,1,"_CPPv4N4espp10RtspClient6Config13on_jpeg_frameE","espp::RtspClient::Config::on_jpeg_frame"],[72,1,1,"_CPPv4N4espp10RtspClient6Config4pathE","espp::RtspClient::Config::path"],[72,1,1,"_CPPv4N4espp10RtspClient6Config9rtsp_portE","espp::RtspClient::Config::rtsp_port"],[72,1,1,"_CPPv4N4espp10RtspClient6Config14server_addressE","espp::RtspClient::Config::server_address"],[72,3,1,"_CPPv4N4espp10RtspClient10RtspClientERK6Config","espp::RtspClient::RtspClient"],[72,4,1,"_CPPv4N4espp10RtspClient10RtspClientERK6Config","espp::RtspClient::RtspClient::config"],[72,3,1,"_CPPv4N4espp10RtspClient7connectERNSt10error_codeE","espp::RtspClient::connect"],[72,4,1,"_CPPv4N4espp10RtspClient7connectERNSt10error_codeE","espp::RtspClient::connect::ec"],[72,3,1,"_CPPv4N4espp10RtspClient8describeERNSt10error_codeE","espp::RtspClient::describe"],[72,4,1,"_CPPv4N4espp10RtspClient8describeERNSt10error_codeE","espp::RtspClient::describe::ec"],[72,3,1,"_CPPv4N4espp10RtspClient10disconnectERNSt10error_codeE","espp::RtspClient::disconnect"],[72,4,1,"_CPPv4N4espp10RtspClient10disconnectERNSt10error_codeE","espp::RtspClient::disconnect::ec"],[72,8,1,"_CPPv4N4espp10RtspClient21jpeg_frame_callback_tE","espp::RtspClient::jpeg_frame_callback_t"],[72,3,1,"_CPPv4N4espp10RtspClient5pauseERNSt10error_codeE","espp::RtspClient::pause"],[72,4,1,"_CPPv4N4espp10RtspClient5pauseERNSt10error_codeE","espp::RtspClient::pause::ec"],[72,3,1,"_CPPv4N4espp10RtspClient4playERNSt10error_codeE","espp::RtspClient::play"],[72,4,1,"_CPPv4N4espp10RtspClient4playERNSt10error_codeE","espp::RtspClient::play::ec"],[72,3,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request"],[72,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::ec"],[72,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::extra_headers"],[72,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::method"],[72,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::path"],[72,3,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup"],[72,3,1,"_CPPv4N4espp10RtspClient5setupERNSt10error_codeE","espp::RtspClient::setup"],[72,4,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup::ec"],[72,4,1,"_CPPv4N4espp10RtspClient5setupERNSt10error_codeE","espp::RtspClient::setup::ec"],[72,4,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup::rtcp_port"],[72,4,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup::rtp_port"],[72,3,1,"_CPPv4N4espp10RtspClient8teardownERNSt10error_codeE","espp::RtspClient::teardown"],[72,4,1,"_CPPv4N4espp10RtspClient8teardownERNSt10error_codeE","espp::RtspClient::teardown::ec"],[72,3,1,"_CPPv4N4espp10RtspClientD0Ev","espp::RtspClient::~RtspClient"],[72,2,1,"_CPPv4N4espp10RtspServerE","espp::RtspServer"],[72,2,1,"_CPPv4N4espp10RtspServer6ConfigE","espp::RtspServer::Config"],[72,1,1,"_CPPv4N4espp10RtspServer6Config9log_levelE","espp::RtspServer::Config::log_level"],[72,1,1,"_CPPv4N4espp10RtspServer6Config13max_data_sizeE","espp::RtspServer::Config::max_data_size"],[72,1,1,"_CPPv4N4espp10RtspServer6Config4pathE","espp::RtspServer::Config::path"],[72,1,1,"_CPPv4N4espp10RtspServer6Config4portE","espp::RtspServer::Config::port"],[72,1,1,"_CPPv4N4espp10RtspServer6Config14server_addressE","espp::RtspServer::Config::server_address"],[72,3,1,"_CPPv4N4espp10RtspServer10RtspServerERK6Config","espp::RtspServer::RtspServer"],[72,4,1,"_CPPv4N4espp10RtspServer10RtspServerERK6Config","espp::RtspServer::RtspServer::config"],[72,3,1,"_CPPv4N4espp10RtspServer10send_frameERK9JpegFrame","espp::RtspServer::send_frame"],[72,4,1,"_CPPv4N4espp10RtspServer10send_frameERK9JpegFrame","espp::RtspServer::send_frame::frame"],[72,3,1,"_CPPv4N4espp10RtspServer21set_session_log_levelEN6Logger9VerbosityE","espp::RtspServer::set_session_log_level"],[72,4,1,"_CPPv4N4espp10RtspServer21set_session_log_levelEN6Logger9VerbosityE","espp::RtspServer::set_session_log_level::log_level"],[72,3,1,"_CPPv4N4espp10RtspServer5startEv","espp::RtspServer::start"],[72,3,1,"_CPPv4N4espp10RtspServer4stopEv","espp::RtspServer::stop"],[72,3,1,"_CPPv4N4espp10RtspServerD0Ev","espp::RtspServer::~RtspServer"],[72,2,1,"_CPPv4N4espp11RtspSessionE","espp::RtspSession"],[72,2,1,"_CPPv4N4espp11RtspSession6ConfigE","espp::RtspSession::Config"],[72,1,1,"_CPPv4N4espp11RtspSession6Config9log_levelE","espp::RtspSession::Config::log_level"],[72,1,1,"_CPPv4N4espp11RtspSession6Config9rtsp_pathE","espp::RtspSession::Config::rtsp_path"],[72,1,1,"_CPPv4N4espp11RtspSession6Config14server_addressE","espp::RtspSession::Config::server_address"],[72,3,1,"_CPPv4N4espp11RtspSession11RtspSessionENSt10unique_ptrI9TcpSocketEERK6Config","espp::RtspSession::RtspSession"],[72,4,1,"_CPPv4N4espp11RtspSession11RtspSessionENSt10unique_ptrI9TcpSocketEERK6Config","espp::RtspSession::RtspSession::config"],[72,4,1,"_CPPv4N4espp11RtspSession11RtspSessionENSt10unique_ptrI9TcpSocketEERK6Config","espp::RtspSession::RtspSession::control_socket"],[72,3,1,"_CPPv4NK4espp11RtspSession14get_session_idEv","espp::RtspSession::get_session_id"],[72,3,1,"_CPPv4NK4espp11RtspSession9is_activeEv","espp::RtspSession::is_active"],[72,3,1,"_CPPv4NK4espp11RtspSession9is_closedEv","espp::RtspSession::is_closed"],[72,3,1,"_CPPv4NK4espp11RtspSession12is_connectedEv","espp::RtspSession::is_connected"],[72,3,1,"_CPPv4N4espp11RtspSession5pauseEv","espp::RtspSession::pause"],[72,3,1,"_CPPv4N4espp11RtspSession4playEv","espp::RtspSession::play"],[72,3,1,"_CPPv4N4espp11RtspSession16send_rtcp_packetERK10RtcpPacket","espp::RtspSession::send_rtcp_packet"],[72,4,1,"_CPPv4N4espp11RtspSession16send_rtcp_packetERK10RtcpPacket","espp::RtspSession::send_rtcp_packet::packet"],[72,3,1,"_CPPv4N4espp11RtspSession15send_rtp_packetERK9RtpPacket","espp::RtspSession::send_rtp_packet"],[72,4,1,"_CPPv4N4espp11RtspSession15send_rtp_packetERK9RtpPacket","espp::RtspSession::send_rtp_packet::packet"],[72,3,1,"_CPPv4N4espp11RtspSession8teardownEv","espp::RtspSession::teardown"],[61,2,1,"_CPPv4N4espp6SocketE","espp::Socket"],[61,2,1,"_CPPv4N4espp6Socket4InfoE","espp::Socket::Info"],[61,1,1,"_CPPv4N4espp6Socket4Info7addressE","espp::Socket::Info::address"],[61,3,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK11sockaddr_in","espp::Socket::Info::from_sockaddr"],[61,3,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK12sockaddr_in6","espp::Socket::Info::from_sockaddr"],[61,3,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK16sockaddr_storage","espp::Socket::Info::from_sockaddr"],[61,4,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK11sockaddr_in","espp::Socket::Info::from_sockaddr::source_address"],[61,4,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK12sockaddr_in6","espp::Socket::Info::from_sockaddr::source_address"],[61,4,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK16sockaddr_storage","espp::Socket::Info::from_sockaddr::source_address"],[61,3,1,"_CPPv4N4espp6Socket4Info9init_ipv4ERKNSt6stringE6size_t","espp::Socket::Info::init_ipv4"],[61,4,1,"_CPPv4N4espp6Socket4Info9init_ipv4ERKNSt6stringE6size_t","espp::Socket::Info::init_ipv4::addr"],[61,4,1,"_CPPv4N4espp6Socket4Info9init_ipv4ERKNSt6stringE6size_t","espp::Socket::Info::init_ipv4::prt"],[61,3,1,"_CPPv4N4espp6Socket4Info8ipv4_ptrEv","espp::Socket::Info::ipv4_ptr"],[61,3,1,"_CPPv4N4espp6Socket4Info8ipv6_ptrEv","espp::Socket::Info::ipv6_ptr"],[61,1,1,"_CPPv4N4espp6Socket4Info4portE","espp::Socket::Info::port"],[61,3,1,"_CPPv4N4espp6Socket4Info6updateEv","espp::Socket::Info::update"],[61,3,1,"_CPPv4N4espp6Socket6SocketE4TypeRKN6Logger6ConfigE","espp::Socket::Socket"],[61,3,1,"_CPPv4N4espp6Socket6SocketEiRKN6Logger6ConfigE","espp::Socket::Socket"],[61,4,1,"_CPPv4N4espp6Socket6SocketE4TypeRKN6Logger6ConfigE","espp::Socket::Socket::logger_config"],[61,4,1,"_CPPv4N4espp6Socket6SocketEiRKN6Logger6ConfigE","espp::Socket::Socket::logger_config"],[61,4,1,"_CPPv4N4espp6Socket6SocketEiRKN6Logger6ConfigE","espp::Socket::Socket::socket_fd"],[61,4,1,"_CPPv4N4espp6Socket6SocketE4TypeRKN6Logger6ConfigE","espp::Socket::Socket::type"],[61,3,1,"_CPPv4N4espp6Socket19add_multicast_groupERKNSt6stringE","espp::Socket::add_multicast_group"],[61,4,1,"_CPPv4N4espp6Socket19add_multicast_groupERKNSt6stringE","espp::Socket::add_multicast_group::multicast_group"],[61,3,1,"_CPPv4N4espp6Socket12enable_reuseEv","espp::Socket::enable_reuse"],[61,3,1,"_CPPv4N4espp6Socket13get_ipv4_infoEv","espp::Socket::get_ipv4_info"],[61,3,1,"_CPPv4N4espp6Socket8is_validEi","espp::Socket::is_valid"],[61,3,1,"_CPPv4NK4espp6Socket8is_validEv","espp::Socket::is_valid"],[61,4,1,"_CPPv4N4espp6Socket8is_validEi","espp::Socket::is_valid::socket_fd"],[61,3,1,"_CPPv4N4espp6Socket14make_multicastE7uint8_t7uint8_t","espp::Socket::make_multicast"],[61,4,1,"_CPPv4N4espp6Socket14make_multicastE7uint8_t7uint8_t","espp::Socket::make_multicast::loopback_enabled"],[61,4,1,"_CPPv4N4espp6Socket14make_multicastE7uint8_t7uint8_t","espp::Socket::make_multicast::time_to_live"],[61,8,1,"_CPPv4N4espp6Socket19receive_callback_fnE","espp::Socket::receive_callback_fn"],[61,8,1,"_CPPv4N4espp6Socket20response_callback_fnE","espp::Socket::response_callback_fn"],[61,3,1,"_CPPv4N4espp6Socket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::Socket::set_receive_timeout"],[61,4,1,"_CPPv4N4espp6Socket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::Socket::set_receive_timeout::timeout"],[61,3,1,"_CPPv4N4espp6SocketD0Ev","espp::Socket::~Socket"],[29,2,1,"_CPPv4I_6size_t0EN4espp9SosFilterE","espp::SosFilter"],[29,5,1,"_CPPv4I_6size_t0EN4espp9SosFilterE","espp::SosFilter::N"],[29,5,1,"_CPPv4I_6size_t0EN4espp9SosFilterE","espp::SosFilter::SectionImpl"],[29,3,1,"_CPPv4N4espp9SosFilter9SosFilterERKNSt5arrayI16TransferFunctionIXL3EEE1NEE","espp::SosFilter::SosFilter"],[29,4,1,"_CPPv4N4espp9SosFilter9SosFilterERKNSt5arrayI16TransferFunctionIXL3EEE1NEE","espp::SosFilter::SosFilter::config"],[29,3,1,"_CPPv4N4espp9SosFilterclEf","espp::SosFilter::operator()"],[29,4,1,"_CPPv4N4espp9SosFilterclEf","espp::SosFilter::operator()::input"],[29,3,1,"_CPPv4N4espp9SosFilter6updateEf","espp::SosFilter::update"],[29,4,1,"_CPPv4N4espp9SosFilter6updateEf","espp::SosFilter::update::input"],[66,2,1,"_CPPv4N4espp6St25dvE","espp::St25dv"],[66,2,1,"_CPPv4N4espp6St25dv6ConfigE","espp::St25dv::Config"],[66,1,1,"_CPPv4N4espp6St25dv6Config9auto_initE","espp::St25dv::Config::auto_init"],[66,1,1,"_CPPv4N4espp6St25dv6Config9log_levelE","espp::St25dv::Config::log_level"],[66,1,1,"_CPPv4N4espp6St25dv6Config4readE","espp::St25dv::Config::read"],[66,1,1,"_CPPv4N4espp6St25dv6Config5writeE","espp::St25dv::Config::write"],[66,1,1,"_CPPv4N4espp6St25dv12DATA_ADDRESSE","espp::St25dv::DATA_ADDRESS"],[66,2,1,"_CPPv4N4espp6St25dv7EH_CTRLE","espp::St25dv::EH_CTRL"],[66,2,1,"_CPPv4N4espp6St25dv3GPOE","espp::St25dv::GPO"],[66,2,1,"_CPPv4N4espp6St25dv6IT_STSE","espp::St25dv::IT_STS"],[66,2,1,"_CPPv4N4espp6St25dv6IT_STSE","espp::St25dv::IT_STS"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS13FIELD_FALLINGE","espp::St25dv::IT_STS::FIELD_FALLING"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS13FIELD_FALLINGE","espp::St25dv::IT_STS::FIELD_FALLING"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS12FIELD_RISINGE","espp::St25dv::IT_STS::FIELD_RISING"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS12FIELD_RISINGE","espp::St25dv::IT_STS::FIELD_RISING"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS11RF_ACTIVITYE","espp::St25dv::IT_STS::RF_ACTIVITY"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS11RF_ACTIVITYE","espp::St25dv::IT_STS::RF_ACTIVITY"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_GET_MSGE","espp::St25dv::IT_STS::RF_GET_MSG"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_GET_MSGE","espp::St25dv::IT_STS::RF_GET_MSG"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS12RF_INTTERUPTE","espp::St25dv::IT_STS::RF_INTTERUPT"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS12RF_INTTERUPTE","espp::St25dv::IT_STS::RF_INTTERUPT"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_PUT_MSGE","espp::St25dv::IT_STS::RF_PUT_MSG"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_PUT_MSGE","espp::St25dv::IT_STS::RF_PUT_MSG"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS7RF_USERE","espp::St25dv::IT_STS::RF_USER"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS7RF_USERE","espp::St25dv::IT_STS::RF_USER"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS8RF_WRITEE","espp::St25dv::IT_STS::RF_WRITE"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS8RF_WRITEE","espp::St25dv::IT_STS::RF_WRITE"],[66,2,1,"_CPPv4N4espp6St25dv7MB_CTRLE","espp::St25dv::MB_CTRL"],[66,1,1,"_CPPv4N4espp6St25dv12SYST_ADDRESSE","espp::St25dv::SYST_ADDRESS"],[66,3,1,"_CPPv4N4espp6St25dv6St25dvERK6Config","espp::St25dv::St25dv"],[66,4,1,"_CPPv4N4espp6St25dv6St25dvERK6Config","espp::St25dv::St25dv::config"],[66,3,1,"_CPPv4N4espp6St25dv14get_ftm_lengthERNSt10error_codeE","espp::St25dv::get_ftm_length"],[66,4,1,"_CPPv4N4espp6St25dv14get_ftm_lengthERNSt10error_codeE","espp::St25dv::get_ftm_length::ec"],[66,3,1,"_CPPv4N4espp6St25dv20get_interrupt_statusERNSt10error_codeE","espp::St25dv::get_interrupt_status"],[66,4,1,"_CPPv4N4espp6St25dv20get_interrupt_statusERNSt10error_codeE","espp::St25dv::get_interrupt_status::ec"],[66,3,1,"_CPPv4N4espp6St25dv10initializeERNSt10error_codeE","espp::St25dv::initialize"],[66,4,1,"_CPPv4N4espp6St25dv10initializeERNSt10error_codeE","espp::St25dv::initialize::ec"],[66,3,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_tRNSt10error_codeE","espp::St25dv::read"],[66,3,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::read"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_tRNSt10error_codeE","espp::St25dv::read::data"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::read::data"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_tRNSt10error_codeE","espp::St25dv::read::ec"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::read::ec"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_tRNSt10error_codeE","espp::St25dv::read::length"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::read::length"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_tRNSt10error_codeE","espp::St25dv::read::offset"],[66,8,1,"_CPPv4N4espp6St25dv7read_fnE","espp::St25dv::read_fn"],[66,3,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::receive"],[66,4,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::receive::data"],[66,4,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::receive::ec"],[66,4,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::receive::length"],[66,3,1,"_CPPv4N4espp6St25dv10set_recordER4NdefRNSt10error_codeE","espp::St25dv::set_record"],[66,3,1,"_CPPv4N4espp6St25dv10set_recordERKNSt6vectorI7uint8_tEERNSt10error_codeE","espp::St25dv::set_record"],[66,4,1,"_CPPv4N4espp6St25dv10set_recordER4NdefRNSt10error_codeE","espp::St25dv::set_record::ec"],[66,4,1,"_CPPv4N4espp6St25dv10set_recordERKNSt6vectorI7uint8_tEERNSt10error_codeE","espp::St25dv::set_record::ec"],[66,4,1,"_CPPv4N4espp6St25dv10set_recordER4NdefRNSt10error_codeE","espp::St25dv::set_record::record"],[66,4,1,"_CPPv4N4espp6St25dv10set_recordERKNSt6vectorI7uint8_tEERNSt10error_codeE","espp::St25dv::set_record::record_data"],[66,3,1,"_CPPv4N4espp6St25dv11set_recordsERNSt6vectorI4NdefEERNSt10error_codeE","espp::St25dv::set_records"],[66,4,1,"_CPPv4N4espp6St25dv11set_recordsERNSt6vectorI4NdefEERNSt10error_codeE","espp::St25dv::set_records::ec"],[66,4,1,"_CPPv4N4espp6St25dv11set_recordsERNSt6vectorI4NdefEERNSt10error_codeE","espp::St25dv::set_records::records"],[66,3,1,"_CPPv4N4espp6St25dv24start_fast_transfer_modeERNSt10error_codeE","espp::St25dv::start_fast_transfer_mode"],[66,4,1,"_CPPv4N4espp6St25dv24start_fast_transfer_modeERNSt10error_codeE","espp::St25dv::start_fast_transfer_mode::ec"],[66,3,1,"_CPPv4N4espp6St25dv23stop_fast_transfer_modeERNSt10error_codeE","espp::St25dv::stop_fast_transfer_mode"],[66,4,1,"_CPPv4N4espp6St25dv23stop_fast_transfer_modeERNSt10error_codeE","espp::St25dv::stop_fast_transfer_mode::ec"],[66,3,1,"_CPPv4N4espp6St25dv8transferEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::transfer"],[66,4,1,"_CPPv4N4espp6St25dv8transferEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::transfer::data"],[66,4,1,"_CPPv4N4espp6St25dv8transferEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::transfer::ec"],[66,4,1,"_CPPv4N4espp6St25dv8transferEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::transfer::length"],[66,3,1,"_CPPv4N4espp6St25dv5writeENSt11string_viewERNSt10error_codeE","espp::St25dv::write"],[66,4,1,"_CPPv4N4espp6St25dv5writeENSt11string_viewERNSt10error_codeE","espp::St25dv::write::ec"],[66,4,1,"_CPPv4N4espp6St25dv5writeENSt11string_viewERNSt10error_codeE","espp::St25dv::write::payload"],[66,8,1,"_CPPv4N4espp6St25dv8write_fnE","espp::St25dv::write_fn"],[16,2,1,"_CPPv4N4espp6St7789E","espp::St7789"],[16,3,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear"],[16,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::color"],[16,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::height"],[16,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::width"],[16,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::x"],[16,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::y"],[16,3,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill"],[16,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::area"],[16,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::color_map"],[16,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::drv"],[16,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::flags"],[16,3,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush"],[16,4,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush::area"],[16,4,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush::color_map"],[16,4,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush::drv"],[16,3,1,"_CPPv4N4espp6St778910get_offsetERiRi","espp::St7789::get_offset"],[16,4,1,"_CPPv4N4espp6St778910get_offsetERiRi","espp::St7789::get_offset::x"],[16,4,1,"_CPPv4N4espp6St778910get_offsetERiRi","espp::St7789::get_offset::y"],[16,3,1,"_CPPv4N4espp6St778910initializeERKN15display_drivers6ConfigE","espp::St7789::initialize"],[16,4,1,"_CPPv4N4espp6St778910initializeERKN15display_drivers6ConfigE","espp::St7789::initialize::config"],[16,3,1,"_CPPv4N4espp6St778912send_commandE7uint8_t","espp::St7789::send_command"],[16,4,1,"_CPPv4N4espp6St778912send_commandE7uint8_t","espp::St7789::send_command::command"],[16,3,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data"],[16,4,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data::data"],[16,4,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data::flags"],[16,4,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data::length"],[16,3,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area"],[16,3,1,"_CPPv4N4espp6St778916set_drawing_areaEPK9lv_area_t","espp::St7789::set_drawing_area"],[16,4,1,"_CPPv4N4espp6St778916set_drawing_areaEPK9lv_area_t","espp::St7789::set_drawing_area::area"],[16,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::xe"],[16,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::xs"],[16,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::ye"],[16,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::ys"],[16,3,1,"_CPPv4N4espp6St778910set_offsetEii","espp::St7789::set_offset"],[16,4,1,"_CPPv4N4espp6St778910set_offsetEii","espp::St7789::set_offset::x"],[16,4,1,"_CPPv4N4espp6St778910set_offsetEii","espp::St7789::set_offset::y"],[43,2,1,"_CPPv4N4espp9TKeyboardE","espp::TKeyboard"],[43,2,1,"_CPPv4N4espp9TKeyboard6ConfigE","espp::TKeyboard::Config"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config7addressE","espp::TKeyboard::Config::address"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config10auto_startE","espp::TKeyboard::Config::auto_start"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config6key_cbE","espp::TKeyboard::Config::key_cb"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config9log_levelE","espp::TKeyboard::Config::log_level"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config16polling_intervalE","espp::TKeyboard::Config::polling_interval"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config4readE","espp::TKeyboard::Config::read"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config5writeE","espp::TKeyboard::Config::write"],[43,1,1,"_CPPv4N4espp9TKeyboard15DEFAULT_ADDRESSE","espp::TKeyboard::DEFAULT_ADDRESS"],[43,3,1,"_CPPv4N4espp9TKeyboard9TKeyboardERK6Config","espp::TKeyboard::TKeyboard"],[43,4,1,"_CPPv4N4espp9TKeyboard9TKeyboardERK6Config","espp::TKeyboard::TKeyboard::config"],[43,3,1,"_CPPv4N4espp9TKeyboard7get_keyEv","espp::TKeyboard::get_key"],[43,8,1,"_CPPv4N4espp9TKeyboard9key_cb_fnE","espp::TKeyboard::key_cb_fn"],[43,8,1,"_CPPv4N4espp9TKeyboard7read_fnE","espp::TKeyboard::read_fn"],[43,3,1,"_CPPv4N4espp9TKeyboard8read_keyERNSt10error_codeE","espp::TKeyboard::read_key"],[43,4,1,"_CPPv4N4espp9TKeyboard8read_keyERNSt10error_codeE","espp::TKeyboard::read_key::ec"],[43,3,1,"_CPPv4N4espp9TKeyboard5startEv","espp::TKeyboard::start"],[43,3,1,"_CPPv4N4espp9TKeyboard4stopEv","espp::TKeyboard::stop"],[43,8,1,"_CPPv4N4espp9TKeyboard8write_fnE","espp::TKeyboard::write_fn"],[76,2,1,"_CPPv4N4espp4TaskE","espp::Task"],[76,2,1,"_CPPv4N4espp4Task6ConfigE","espp::Task::Config"],[76,1,1,"_CPPv4N4espp4Task6Config8callbackE","espp::Task::Config::callback"],[76,1,1,"_CPPv4N4espp4Task6Config7core_idE","espp::Task::Config::core_id"],[76,1,1,"_CPPv4N4espp4Task6Config9log_levelE","espp::Task::Config::log_level"],[76,1,1,"_CPPv4N4espp4Task6Config4nameE","espp::Task::Config::name"],[76,1,1,"_CPPv4N4espp4Task6Config8priorityE","espp::Task::Config::priority"],[76,1,1,"_CPPv4N4espp4Task6Config16stack_size_bytesE","espp::Task::Config::stack_size_bytes"],[76,2,1,"_CPPv4N4espp4Task12SimpleConfigE","espp::Task::SimpleConfig"],[76,1,1,"_CPPv4N4espp4Task12SimpleConfig8callbackE","espp::Task::SimpleConfig::callback"],[76,1,1,"_CPPv4N4espp4Task12SimpleConfig7core_idE","espp::Task::SimpleConfig::core_id"],[76,1,1,"_CPPv4N4espp4Task12SimpleConfig9log_levelE","espp::Task::SimpleConfig::log_level"],[76,1,1,"_CPPv4N4espp4Task12SimpleConfig4nameE","espp::Task::SimpleConfig::name"],[76,1,1,"_CPPv4N4espp4Task12SimpleConfig8priorityE","espp::Task::SimpleConfig::priority"],[76,1,1,"_CPPv4N4espp4Task12SimpleConfig16stack_size_bytesE","espp::Task::SimpleConfig::stack_size_bytes"],[76,3,1,"_CPPv4N4espp4Task4TaskERK12SimpleConfig","espp::Task::Task"],[76,3,1,"_CPPv4N4espp4Task4TaskERK6Config","espp::Task::Task"],[76,4,1,"_CPPv4N4espp4Task4TaskERK12SimpleConfig","espp::Task::Task::config"],[76,4,1,"_CPPv4N4espp4Task4TaskERK6Config","espp::Task::Task::config"],[76,8,1,"_CPPv4N4espp4Task11callback_fnE","espp::Task::callback_fn"],[76,3,1,"_CPPv4N4espp4Task10is_runningEv","espp::Task::is_running"],[76,3,1,"_CPPv4N4espp4Task10is_startedEv","espp::Task::is_started"],[76,3,1,"_CPPv4N4espp4Task11make_uniqueERK12SimpleConfig","espp::Task::make_unique"],[76,3,1,"_CPPv4N4espp4Task11make_uniqueERK6Config","espp::Task::make_unique"],[76,4,1,"_CPPv4N4espp4Task11make_uniqueERK12SimpleConfig","espp::Task::make_unique::config"],[76,4,1,"_CPPv4N4espp4Task11make_uniqueERK6Config","espp::Task::make_unique::config"],[76,8,1,"_CPPv4N4espp4Task18simple_callback_fnE","espp::Task::simple_callback_fn"],[76,3,1,"_CPPv4N4espp4Task5startEv","espp::Task::start"],[76,3,1,"_CPPv4N4espp4Task4stopEv","espp::Task::stop"],[76,3,1,"_CPPv4N4espp4TaskD0Ev","espp::Task::~Task"],[59,2,1,"_CPPv4N4espp11TaskMonitorE","espp::TaskMonitor"],[59,2,1,"_CPPv4N4espp11TaskMonitor6ConfigE","espp::TaskMonitor::Config"],[59,1,1,"_CPPv4N4espp11TaskMonitor6Config6periodE","espp::TaskMonitor::Config::period"],[59,1,1,"_CPPv4N4espp11TaskMonitor6Config21task_stack_size_bytesE","espp::TaskMonitor::Config::task_stack_size_bytes"],[59,3,1,"_CPPv4N4espp11TaskMonitor15get_latest_infoEv","espp::TaskMonitor::get_latest_info"],[62,2,1,"_CPPv4N4espp9TcpSocketE","espp::TcpSocket"],[62,2,1,"_CPPv4N4espp9TcpSocket6ConfigE","espp::TcpSocket::Config"],[62,1,1,"_CPPv4N4espp9TcpSocket6Config9log_levelE","espp::TcpSocket::Config::log_level"],[62,2,1,"_CPPv4N4espp9TcpSocket13ConnectConfigE","espp::TcpSocket::ConnectConfig"],[62,1,1,"_CPPv4N4espp9TcpSocket13ConnectConfig10ip_addressE","espp::TcpSocket::ConnectConfig::ip_address"],[62,1,1,"_CPPv4N4espp9TcpSocket13ConnectConfig4portE","espp::TcpSocket::ConnectConfig::port"],[62,3,1,"_CPPv4N4espp9TcpSocket9TcpSocketERK6Config","espp::TcpSocket::TcpSocket"],[62,4,1,"_CPPv4N4espp9TcpSocket9TcpSocketERK6Config","espp::TcpSocket::TcpSocket::config"],[62,3,1,"_CPPv4N4espp9TcpSocket6acceptEv","espp::TcpSocket::accept"],[62,3,1,"_CPPv4N4espp9TcpSocket19add_multicast_groupERKNSt6stringE","espp::TcpSocket::add_multicast_group"],[62,4,1,"_CPPv4N4espp9TcpSocket19add_multicast_groupERKNSt6stringE","espp::TcpSocket::add_multicast_group::multicast_group"],[62,3,1,"_CPPv4N4espp9TcpSocket4bindEi","espp::TcpSocket::bind"],[62,4,1,"_CPPv4N4espp9TcpSocket4bindEi","espp::TcpSocket::bind::port"],[62,3,1,"_CPPv4N4espp9TcpSocket5closeEv","espp::TcpSocket::close"],[62,3,1,"_CPPv4N4espp9TcpSocket7connectERK13ConnectConfig","espp::TcpSocket::connect"],[62,4,1,"_CPPv4N4espp9TcpSocket7connectERK13ConnectConfig","espp::TcpSocket::connect::connect_config"],[62,3,1,"_CPPv4N4espp9TcpSocket12enable_reuseEv","espp::TcpSocket::enable_reuse"],[62,3,1,"_CPPv4N4espp9TcpSocket13get_ipv4_infoEv","espp::TcpSocket::get_ipv4_info"],[62,3,1,"_CPPv4NK4espp9TcpSocket15get_remote_infoEv","espp::TcpSocket::get_remote_info"],[62,3,1,"_CPPv4NK4espp9TcpSocket12is_connectedEv","espp::TcpSocket::is_connected"],[62,3,1,"_CPPv4N4espp9TcpSocket8is_validEi","espp::TcpSocket::is_valid"],[62,3,1,"_CPPv4NK4espp9TcpSocket8is_validEv","espp::TcpSocket::is_valid"],[62,4,1,"_CPPv4N4espp9TcpSocket8is_validEi","espp::TcpSocket::is_valid::socket_fd"],[62,3,1,"_CPPv4N4espp9TcpSocket6listenEi","espp::TcpSocket::listen"],[62,4,1,"_CPPv4N4espp9TcpSocket6listenEi","espp::TcpSocket::listen::max_pending_connections"],[62,3,1,"_CPPv4N4espp9TcpSocket14make_multicastE7uint8_t7uint8_t","espp::TcpSocket::make_multicast"],[62,4,1,"_CPPv4N4espp9TcpSocket14make_multicastE7uint8_t7uint8_t","espp::TcpSocket::make_multicast::loopback_enabled"],[62,4,1,"_CPPv4N4espp9TcpSocket14make_multicastE7uint8_t7uint8_t","espp::TcpSocket::make_multicast::time_to_live"],[62,3,1,"_CPPv4N4espp9TcpSocket7receiveEP7uint8_t6size_t","espp::TcpSocket::receive"],[62,3,1,"_CPPv4N4espp9TcpSocket7receiveERNSt6vectorI7uint8_tEE6size_t","espp::TcpSocket::receive"],[62,4,1,"_CPPv4N4espp9TcpSocket7receiveEP7uint8_t6size_t","espp::TcpSocket::receive::data"],[62,4,1,"_CPPv4N4espp9TcpSocket7receiveERNSt6vectorI7uint8_tEE6size_t","espp::TcpSocket::receive::data"],[62,4,1,"_CPPv4N4espp9TcpSocket7receiveEP7uint8_t6size_t","espp::TcpSocket::receive::max_num_bytes"],[62,4,1,"_CPPv4N4espp9TcpSocket7receiveERNSt6vectorI7uint8_tEE6size_t","espp::TcpSocket::receive::max_num_bytes"],[62,8,1,"_CPPv4N4espp9TcpSocket19receive_callback_fnE","espp::TcpSocket::receive_callback_fn"],[62,3,1,"_CPPv4N4espp9TcpSocket6reinitEv","espp::TcpSocket::reinit"],[62,8,1,"_CPPv4N4espp9TcpSocket20response_callback_fnE","espp::TcpSocket::response_callback_fn"],[62,3,1,"_CPPv4N4espp9TcpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::TcpSocket::set_receive_timeout"],[62,4,1,"_CPPv4N4espp9TcpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::TcpSocket::set_receive_timeout::timeout"],[62,3,1,"_CPPv4N4espp9TcpSocket8transmitENSt11string_viewERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit"],[62,3,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorI7uint8_tEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit"],[62,3,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorIcEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit"],[62,4,1,"_CPPv4N4espp9TcpSocket8transmitENSt11string_viewERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::data"],[62,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorI7uint8_tEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::data"],[62,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorIcEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::data"],[62,4,1,"_CPPv4N4espp9TcpSocket8transmitENSt11string_viewERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::transmit_config"],[62,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorI7uint8_tEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::transmit_config"],[62,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorIcEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::transmit_config"],[62,3,1,"_CPPv4N4espp9TcpSocketD0Ev","espp::TcpSocket::~TcpSocket"],[77,2,1,"_CPPv4N4espp10ThermistorE","espp::Thermistor"],[77,2,1,"_CPPv4N4espp10Thermistor6ConfigE","espp::Thermistor::Config"],[77,1,1,"_CPPv4N4espp10Thermistor6Config4betaE","espp::Thermistor::Config::beta"],[77,1,1,"_CPPv4N4espp10Thermistor6Config14divider_configE","espp::Thermistor::Config::divider_config"],[77,1,1,"_CPPv4N4espp10Thermistor6Config21fixed_resistance_ohmsE","espp::Thermistor::Config::fixed_resistance_ohms"],[77,1,1,"_CPPv4N4espp10Thermistor6Config9log_levelE","espp::Thermistor::Config::log_level"],[77,1,1,"_CPPv4N4espp10Thermistor6Config23nominal_resistance_ohmsE","espp::Thermistor::Config::nominal_resistance_ohms"],[77,1,1,"_CPPv4N4espp10Thermistor6Config7read_mvE","espp::Thermistor::Config::read_mv"],[77,1,1,"_CPPv4N4espp10Thermistor6Config9supply_mvE","espp::Thermistor::Config::supply_mv"],[77,6,1,"_CPPv4N4espp10Thermistor21ResistorDividerConfigE","espp::Thermistor::ResistorDividerConfig"],[77,7,1,"_CPPv4N4espp10Thermistor21ResistorDividerConfig5LOWERE","espp::Thermistor::ResistorDividerConfig::LOWER"],[77,7,1,"_CPPv4N4espp10Thermistor21ResistorDividerConfig5UPPERE","espp::Thermistor::ResistorDividerConfig::UPPER"],[77,3,1,"_CPPv4N4espp10Thermistor10ThermistorERK6Config","espp::Thermistor::Thermistor"],[77,4,1,"_CPPv4N4espp10Thermistor10ThermistorERK6Config","espp::Thermistor::Thermistor::config"],[77,3,1,"_CPPv4N4espp10Thermistor11get_celsiusEv","espp::Thermistor::get_celsius"],[77,3,1,"_CPPv4N4espp10Thermistor14get_fahrenheitEv","espp::Thermistor::get_fahrenheit"],[77,3,1,"_CPPv4N4espp10Thermistor10get_kelvinEv","espp::Thermistor::get_kelvin"],[77,3,1,"_CPPv4N4espp10Thermistor14get_resistanceEv","espp::Thermistor::get_resistance"],[77,8,1,"_CPPv4N4espp10Thermistor10read_mv_fnE","espp::Thermistor::read_mv_fn"],[78,2,1,"_CPPv4N4espp5TimerE","espp::Timer"],[78,2,1,"_CPPv4N4espp5Timer6ConfigE","espp::Timer::Config"],[78,1,1,"_CPPv4N4espp5Timer6Config10auto_startE","espp::Timer::Config::auto_start"],[78,1,1,"_CPPv4N4espp5Timer6Config8callbackE","espp::Timer::Config::callback"],[78,1,1,"_CPPv4N4espp5Timer6Config7core_idE","espp::Timer::Config::core_id"],[78,1,1,"_CPPv4N4espp5Timer6Config5delayE","espp::Timer::Config::delay"],[78,1,1,"_CPPv4N4espp5Timer6Config9log_levelE","espp::Timer::Config::log_level"],[78,1,1,"_CPPv4N4espp5Timer6Config4nameE","espp::Timer::Config::name"],[78,1,1,"_CPPv4N4espp5Timer6Config6periodE","espp::Timer::Config::period"],[78,1,1,"_CPPv4N4espp5Timer6Config8priorityE","espp::Timer::Config::priority"],[78,1,1,"_CPPv4N4espp5Timer6Config16stack_size_bytesE","espp::Timer::Config::stack_size_bytes"],[78,3,1,"_CPPv4N4espp5Timer5TimerERK6Config","espp::Timer::Timer"],[78,4,1,"_CPPv4N4espp5Timer5TimerERK6Config","espp::Timer::Timer::config"],[78,8,1,"_CPPv4N4espp5Timer11callback_fnE","espp::Timer::callback_fn"],[78,3,1,"_CPPv4N4espp5Timer6cancelEv","espp::Timer::cancel"],[78,3,1,"_CPPv4NK4espp5Timer10is_runningEv","espp::Timer::is_running"],[78,3,1,"_CPPv4N4espp5Timer5startENSt6chrono8durationIfEE","espp::Timer::start"],[78,3,1,"_CPPv4N4espp5Timer5startEv","espp::Timer::start"],[78,4,1,"_CPPv4N4espp5Timer5startENSt6chrono8durationIfEE","espp::Timer::start::delay"],[78,3,1,"_CPPv4N4espp5Timer4stopEv","espp::Timer::stop"],[78,3,1,"_CPPv4N4espp5TimerD0Ev","espp::Timer::~Timer"],[6,2,1,"_CPPv4N4espp7Tla2528E","espp::Tla2528"],[6,6,1,"_CPPv4N4espp7Tla252810AlertLogicE","espp::Tla2528::AlertLogic"],[6,7,1,"_CPPv4N4espp7Tla252810AlertLogic11ACTIVE_HIGHE","espp::Tla2528::AlertLogic::ACTIVE_HIGH"],[6,7,1,"_CPPv4N4espp7Tla252810AlertLogic10ACTIVE_LOWE","espp::Tla2528::AlertLogic::ACTIVE_LOW"],[6,7,1,"_CPPv4N4espp7Tla252810AlertLogic11PULSED_HIGHE","espp::Tla2528::AlertLogic::PULSED_HIGH"],[6,7,1,"_CPPv4N4espp7Tla252810AlertLogic10PULSED_LOWE","espp::Tla2528::AlertLogic::PULSED_LOW"],[6,6,1,"_CPPv4N4espp7Tla25286AppendE","espp::Tla2528::Append"],[6,7,1,"_CPPv4N4espp7Tla25286Append10CHANNEL_IDE","espp::Tla2528::Append::CHANNEL_ID"],[6,7,1,"_CPPv4N4espp7Tla25286Append4NONEE","espp::Tla2528::Append::NONE"],[6,6,1,"_CPPv4N4espp7Tla25287ChannelE","espp::Tla2528::Channel"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH0E","espp::Tla2528::Channel::CH0"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH1E","espp::Tla2528::Channel::CH1"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH2E","espp::Tla2528::Channel::CH2"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH3E","espp::Tla2528::Channel::CH3"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH4E","espp::Tla2528::Channel::CH4"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH5E","espp::Tla2528::Channel::CH5"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH6E","espp::Tla2528::Channel::CH6"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH7E","espp::Tla2528::Channel::CH7"],[6,2,1,"_CPPv4N4espp7Tla25286ConfigE","espp::Tla2528::Config"],[6,1,1,"_CPPv4N4espp7Tla25286Config13analog_inputsE","espp::Tla2528::Config::analog_inputs"],[6,1,1,"_CPPv4N4espp7Tla25286Config6appendE","espp::Tla2528::Config::append"],[6,1,1,"_CPPv4N4espp7Tla25286Config9auto_initE","espp::Tla2528::Config::auto_init"],[6,1,1,"_CPPv4N4espp7Tla25286Config10avdd_voltsE","espp::Tla2528::Config::avdd_volts"],[6,1,1,"_CPPv4N4espp7Tla25286Config14device_addressE","espp::Tla2528::Config::device_address"],[6,1,1,"_CPPv4N4espp7Tla25286Config14digital_inputsE","espp::Tla2528::Config::digital_inputs"],[6,1,1,"_CPPv4N4espp7Tla25286Config20digital_output_modesE","espp::Tla2528::Config::digital_output_modes"],[6,1,1,"_CPPv4N4espp7Tla25286Config21digital_output_valuesE","espp::Tla2528::Config::digital_output_values"],[6,1,1,"_CPPv4N4espp7Tla25286Config15digital_outputsE","espp::Tla2528::Config::digital_outputs"],[6,1,1,"_CPPv4N4espp7Tla25286Config9log_levelE","espp::Tla2528::Config::log_level"],[6,1,1,"_CPPv4N4espp7Tla25286Config4modeE","espp::Tla2528::Config::mode"],[6,1,1,"_CPPv4N4espp7Tla25286Config18oversampling_ratioE","espp::Tla2528::Config::oversampling_ratio"],[6,1,1,"_CPPv4N4espp7Tla25286Config4readE","espp::Tla2528::Config::read"],[6,1,1,"_CPPv4N4espp7Tla25286Config5writeE","espp::Tla2528::Config::write"],[6,1,1,"_CPPv4N4espp7Tla252815DEFAULT_ADDRESSE","espp::Tla2528::DEFAULT_ADDRESS"],[6,6,1,"_CPPv4N4espp7Tla252810DataFormatE","espp::Tla2528::DataFormat"],[6,7,1,"_CPPv4N4espp7Tla252810DataFormat8AVERAGEDE","espp::Tla2528::DataFormat::AVERAGED"],[6,7,1,"_CPPv4N4espp7Tla252810DataFormat3RAWE","espp::Tla2528::DataFormat::RAW"],[6,6,1,"_CPPv4N4espp7Tla25284ModeE","espp::Tla2528::Mode"],[6,7,1,"_CPPv4N4espp7Tla25284Mode8AUTO_SEQE","espp::Tla2528::Mode::AUTO_SEQ"],[6,7,1,"_CPPv4N4espp7Tla25284Mode6MANUALE","espp::Tla2528::Mode::MANUAL"],[6,6,1,"_CPPv4N4espp7Tla252810OutputModeE","espp::Tla2528::OutputMode"],[6,7,1,"_CPPv4N4espp7Tla252810OutputMode10OPEN_DRAINE","espp::Tla2528::OutputMode::OPEN_DRAIN"],[6,7,1,"_CPPv4N4espp7Tla252810OutputMode9PUSH_PULLE","espp::Tla2528::OutputMode::PUSH_PULL"],[6,6,1,"_CPPv4N4espp7Tla252817OversamplingRatioE","espp::Tla2528::OversamplingRatio"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio4NONEE","espp::Tla2528::OversamplingRatio::NONE"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio7OSR_128E","espp::Tla2528::OversamplingRatio::OSR_128"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio6OSR_16E","espp::Tla2528::OversamplingRatio::OSR_16"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio5OSR_2E","espp::Tla2528::OversamplingRatio::OSR_2"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio6OSR_32E","espp::Tla2528::OversamplingRatio::OSR_32"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio5OSR_4E","espp::Tla2528::OversamplingRatio::OSR_4"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio6OSR_64E","espp::Tla2528::OversamplingRatio::OSR_64"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio5OSR_8E","espp::Tla2528::OversamplingRatio::OSR_8"],[6,3,1,"_CPPv4N4espp7Tla25287Tla2528ERK6Config","espp::Tla2528::Tla2528"],[6,4,1,"_CPPv4N4espp7Tla25287Tla2528ERK6Config","espp::Tla2528::Tla2528::config"],[6,3,1,"_CPPv4N4espp7Tla252810get_all_mvERNSt10error_codeE","espp::Tla2528::get_all_mv"],[6,4,1,"_CPPv4N4espp7Tla252810get_all_mvERNSt10error_codeE","espp::Tla2528::get_all_mv::ec"],[6,3,1,"_CPPv4N4espp7Tla252814get_all_mv_mapERNSt10error_codeE","espp::Tla2528::get_all_mv_map"],[6,4,1,"_CPPv4N4espp7Tla252814get_all_mv_mapERNSt10error_codeE","espp::Tla2528::get_all_mv_map::ec"],[6,3,1,"_CPPv4N4espp7Tla252823get_digital_input_valueE7ChannelRNSt10error_codeE","espp::Tla2528::get_digital_input_value"],[6,4,1,"_CPPv4N4espp7Tla252823get_digital_input_valueE7ChannelRNSt10error_codeE","espp::Tla2528::get_digital_input_value::channel"],[6,4,1,"_CPPv4N4espp7Tla252823get_digital_input_valueE7ChannelRNSt10error_codeE","espp::Tla2528::get_digital_input_value::ec"],[6,3,1,"_CPPv4N4espp7Tla252824get_digital_input_valuesERNSt10error_codeE","espp::Tla2528::get_digital_input_values"],[6,4,1,"_CPPv4N4espp7Tla252824get_digital_input_valuesERNSt10error_codeE","espp::Tla2528::get_digital_input_values::ec"],[6,3,1,"_CPPv4N4espp7Tla25286get_mvE7ChannelRNSt10error_codeE","espp::Tla2528::get_mv"],[6,4,1,"_CPPv4N4espp7Tla25286get_mvE7ChannelRNSt10error_codeE","espp::Tla2528::get_mv::channel"],[6,4,1,"_CPPv4N4espp7Tla25286get_mvE7ChannelRNSt10error_codeE","espp::Tla2528::get_mv::ec"],[6,3,1,"_CPPv4N4espp7Tla252810initializeERNSt10error_codeE","espp::Tla2528::initialize"],[6,4,1,"_CPPv4N4espp7Tla252810initializeERNSt10error_codeE","espp::Tla2528::initialize::ec"],[6,8,1,"_CPPv4N4espp7Tla25287read_fnE","espp::Tla2528::read_fn"],[6,3,1,"_CPPv4N4espp7Tla25285resetERNSt10error_codeE","espp::Tla2528::reset"],[6,4,1,"_CPPv4N4espp7Tla25285resetERNSt10error_codeE","espp::Tla2528::reset::ec"],[6,3,1,"_CPPv4N4espp7Tla252823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Tla2528::set_digital_output_mode"],[6,4,1,"_CPPv4N4espp7Tla252823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Tla2528::set_digital_output_mode::channel"],[6,4,1,"_CPPv4N4espp7Tla252823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Tla2528::set_digital_output_mode::ec"],[6,4,1,"_CPPv4N4espp7Tla252823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Tla2528::set_digital_output_mode::output_mode"],[6,3,1,"_CPPv4N4espp7Tla252824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Tla2528::set_digital_output_value"],[6,4,1,"_CPPv4N4espp7Tla252824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Tla2528::set_digital_output_value::channel"],[6,4,1,"_CPPv4N4espp7Tla252824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Tla2528::set_digital_output_value::ec"],[6,4,1,"_CPPv4N4espp7Tla252824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Tla2528::set_digital_output_value::value"],[6,8,1,"_CPPv4N4espp7Tla25288write_fnE","espp::Tla2528::write_fn"],[44,2,1,"_CPPv4N4espp13TouchpadInputE","espp::TouchpadInput"],[44,2,1,"_CPPv4N4espp13TouchpadInput6ConfigE","espp::TouchpadInput::Config"],[44,1,1,"_CPPv4N4espp13TouchpadInput6Config8invert_xE","espp::TouchpadInput::Config::invert_x"],[44,1,1,"_CPPv4N4espp13TouchpadInput6Config8invert_yE","espp::TouchpadInput::Config::invert_y"],[44,1,1,"_CPPv4N4espp13TouchpadInput6Config9log_levelE","espp::TouchpadInput::Config::log_level"],[44,1,1,"_CPPv4N4espp13TouchpadInput6Config7swap_xyE","espp::TouchpadInput::Config::swap_xy"],[44,1,1,"_CPPv4N4espp13TouchpadInput6Config13touchpad_readE","espp::TouchpadInput::Config::touchpad_read"],[44,3,1,"_CPPv4N4espp13TouchpadInput13TouchpadInputERK6Config","espp::TouchpadInput::TouchpadInput"],[44,4,1,"_CPPv4N4espp13TouchpadInput13TouchpadInputERK6Config","espp::TouchpadInput::TouchpadInput::config"],[44,3,1,"_CPPv4N4espp13TouchpadInput28get_home_button_input_deviceEv","espp::TouchpadInput::get_home_button_input_device"],[44,3,1,"_CPPv4N4espp13TouchpadInput25get_touchpad_input_deviceEv","espp::TouchpadInput::get_touchpad_input_device"],[44,8,1,"_CPPv4N4espp13TouchpadInput16touchpad_read_fnE","espp::TouchpadInput::touchpad_read_fn"],[44,3,1,"_CPPv4N4espp13TouchpadInputD0Ev","espp::TouchpadInput::~TouchpadInput"],[45,2,1,"_CPPv4N4espp7Tt21100E","espp::Tt21100"],[45,2,1,"_CPPv4N4espp7Tt211006ConfigE","espp::Tt21100::Config"],[45,1,1,"_CPPv4N4espp7Tt211006Config9log_levelE","espp::Tt21100::Config::log_level"],[45,1,1,"_CPPv4N4espp7Tt211006Config4readE","espp::Tt21100::Config::read"],[45,1,1,"_CPPv4N4espp7Tt2110015DEFAULT_ADDRESSE","espp::Tt21100::DEFAULT_ADDRESS"],[45,3,1,"_CPPv4N4espp7Tt211007Tt21100ERK6Config","espp::Tt21100::Tt21100"],[45,4,1,"_CPPv4N4espp7Tt211007Tt21100ERK6Config","espp::Tt21100::Tt21100::config"],[45,3,1,"_CPPv4NK4espp7Tt2110021get_home_button_stateEv","espp::Tt21100::get_home_button_state"],[45,3,1,"_CPPv4NK4espp7Tt2110020get_num_touch_pointsEv","espp::Tt21100::get_num_touch_points"],[45,3,1,"_CPPv4NK4espp7Tt2110015get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Tt21100::get_touch_point"],[45,4,1,"_CPPv4NK4espp7Tt2110015get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Tt21100::get_touch_point::num_touch_points"],[45,4,1,"_CPPv4NK4espp7Tt2110015get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Tt21100::get_touch_point::x"],[45,4,1,"_CPPv4NK4espp7Tt2110015get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Tt21100::get_touch_point::y"],[45,8,1,"_CPPv4N4espp7Tt211007read_fnE","espp::Tt21100::read_fn"],[45,3,1,"_CPPv4N4espp7Tt211006updateERNSt10error_codeE","espp::Tt21100::update"],[45,4,1,"_CPPv4N4espp7Tt211006updateERNSt10error_codeE","espp::Tt21100::update::ec"],[63,2,1,"_CPPv4N4espp9UdpSocketE","espp::UdpSocket"],[63,2,1,"_CPPv4N4espp9UdpSocket6ConfigE","espp::UdpSocket::Config"],[63,1,1,"_CPPv4N4espp9UdpSocket6Config9log_levelE","espp::UdpSocket::Config::log_level"],[63,2,1,"_CPPv4N4espp9UdpSocket13ReceiveConfigE","espp::UdpSocket::ReceiveConfig"],[63,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig11buffer_sizeE","espp::UdpSocket::ReceiveConfig::buffer_size"],[63,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig21is_multicast_endpointE","espp::UdpSocket::ReceiveConfig::is_multicast_endpoint"],[63,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig15multicast_groupE","espp::UdpSocket::ReceiveConfig::multicast_group"],[63,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig19on_receive_callbackE","espp::UdpSocket::ReceiveConfig::on_receive_callback"],[63,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig4portE","espp::UdpSocket::ReceiveConfig::port"],[63,2,1,"_CPPv4N4espp9UdpSocket10SendConfigE","espp::UdpSocket::SendConfig"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig10ip_addressE","espp::UdpSocket::SendConfig::ip_address"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig21is_multicast_endpointE","espp::UdpSocket::SendConfig::is_multicast_endpoint"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig20on_response_callbackE","espp::UdpSocket::SendConfig::on_response_callback"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig4portE","espp::UdpSocket::SendConfig::port"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig13response_sizeE","espp::UdpSocket::SendConfig::response_size"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig16response_timeoutE","espp::UdpSocket::SendConfig::response_timeout"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig17wait_for_responseE","espp::UdpSocket::SendConfig::wait_for_response"],[63,3,1,"_CPPv4N4espp9UdpSocket9UdpSocketERK6Config","espp::UdpSocket::UdpSocket"],[63,4,1,"_CPPv4N4espp9UdpSocket9UdpSocketERK6Config","espp::UdpSocket::UdpSocket::config"],[63,3,1,"_CPPv4N4espp9UdpSocket19add_multicast_groupERKNSt6stringE","espp::UdpSocket::add_multicast_group"],[63,4,1,"_CPPv4N4espp9UdpSocket19add_multicast_groupERKNSt6stringE","espp::UdpSocket::add_multicast_group::multicast_group"],[63,3,1,"_CPPv4N4espp9UdpSocket12enable_reuseEv","espp::UdpSocket::enable_reuse"],[63,3,1,"_CPPv4N4espp9UdpSocket13get_ipv4_infoEv","espp::UdpSocket::get_ipv4_info"],[63,3,1,"_CPPv4N4espp9UdpSocket8is_validEi","espp::UdpSocket::is_valid"],[63,3,1,"_CPPv4NK4espp9UdpSocket8is_validEv","espp::UdpSocket::is_valid"],[63,4,1,"_CPPv4N4espp9UdpSocket8is_validEi","espp::UdpSocket::is_valid::socket_fd"],[63,3,1,"_CPPv4N4espp9UdpSocket14make_multicastE7uint8_t7uint8_t","espp::UdpSocket::make_multicast"],[63,4,1,"_CPPv4N4espp9UdpSocket14make_multicastE7uint8_t7uint8_t","espp::UdpSocket::make_multicast::loopback_enabled"],[63,4,1,"_CPPv4N4espp9UdpSocket14make_multicastE7uint8_t7uint8_t","espp::UdpSocket::make_multicast::time_to_live"],[63,3,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive"],[63,4,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive::data"],[63,4,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive::max_num_bytes"],[63,4,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive::remote_info"],[63,8,1,"_CPPv4N4espp9UdpSocket19receive_callback_fnE","espp::UdpSocket::receive_callback_fn"],[63,8,1,"_CPPv4N4espp9UdpSocket20response_callback_fnE","espp::UdpSocket::response_callback_fn"],[63,3,1,"_CPPv4N4espp9UdpSocket4sendENSt11string_viewERK10SendConfig","espp::UdpSocket::send"],[63,3,1,"_CPPv4N4espp9UdpSocket4sendERKNSt6vectorI7uint8_tEERK10SendConfig","espp::UdpSocket::send"],[63,4,1,"_CPPv4N4espp9UdpSocket4sendENSt11string_viewERK10SendConfig","espp::UdpSocket::send::data"],[63,4,1,"_CPPv4N4espp9UdpSocket4sendERKNSt6vectorI7uint8_tEERK10SendConfig","espp::UdpSocket::send::data"],[63,4,1,"_CPPv4N4espp9UdpSocket4sendENSt11string_viewERK10SendConfig","espp::UdpSocket::send::send_config"],[63,4,1,"_CPPv4N4espp9UdpSocket4sendERKNSt6vectorI7uint8_tEERK10SendConfig","espp::UdpSocket::send::send_config"],[63,3,1,"_CPPv4N4espp9UdpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::UdpSocket::set_receive_timeout"],[63,4,1,"_CPPv4N4espp9UdpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::UdpSocket::set_receive_timeout::timeout"],[63,3,1,"_CPPv4N4espp9UdpSocket15start_receivingERN4Task6ConfigERK13ReceiveConfig","espp::UdpSocket::start_receiving"],[63,4,1,"_CPPv4N4espp9UdpSocket15start_receivingERN4Task6ConfigERK13ReceiveConfig","espp::UdpSocket::start_receiving::receive_config"],[63,4,1,"_CPPv4N4espp9UdpSocket15start_receivingERN4Task6ConfigERK13ReceiveConfig","espp::UdpSocket::start_receiving::task_config"],[63,3,1,"_CPPv4N4espp9UdpSocketD0Ev","espp::UdpSocket::~UdpSocket"],[58,2,1,"_CPPv4I0EN4espp8Vector2dE","espp::Vector2d"],[58,5,1,"_CPPv4I0EN4espp8Vector2dE","espp::Vector2d::T"],[58,3,1,"_CPPv4N4espp8Vector2d8Vector2dE1T1T","espp::Vector2d::Vector2d"],[58,3,1,"_CPPv4N4espp8Vector2d8Vector2dERK8Vector2d","espp::Vector2d::Vector2d"],[58,4,1,"_CPPv4N4espp8Vector2d8Vector2dERK8Vector2d","espp::Vector2d::Vector2d::other"],[58,4,1,"_CPPv4N4espp8Vector2d8Vector2dE1T1T","espp::Vector2d::Vector2d::x"],[58,4,1,"_CPPv4N4espp8Vector2d8Vector2dE1T1T","espp::Vector2d::Vector2d::y"],[58,3,1,"_CPPv4NK4espp8Vector2d3dotERK8Vector2d","espp::Vector2d::dot"],[58,4,1,"_CPPv4NK4espp8Vector2d3dotERK8Vector2d","espp::Vector2d::dot::other"],[58,3,1,"_CPPv4NK4espp8Vector2d9magnitudeEv","espp::Vector2d::magnitude"],[58,3,1,"_CPPv4NK4espp8Vector2d17magnitude_squaredEv","espp::Vector2d::magnitude_squared"],[58,3,1,"_CPPv4NK4espp8Vector2d10normalizedEv","espp::Vector2d::normalized"],[58,3,1,"_CPPv4NK4espp8Vector2dmlERK1T","espp::Vector2d::operator*"],[58,4,1,"_CPPv4NK4espp8Vector2dmlERK1T","espp::Vector2d::operator*::v"],[58,3,1,"_CPPv4N4espp8Vector2dmLERK1T","espp::Vector2d::operator*="],[58,4,1,"_CPPv4N4espp8Vector2dmLERK1T","espp::Vector2d::operator*=::v"],[58,3,1,"_CPPv4NK4espp8Vector2dplERK8Vector2d","espp::Vector2d::operator+"],[58,4,1,"_CPPv4NK4espp8Vector2dplERK8Vector2d","espp::Vector2d::operator+::rhs"],[58,3,1,"_CPPv4N4espp8Vector2dpLERK8Vector2d","espp::Vector2d::operator+="],[58,4,1,"_CPPv4N4espp8Vector2dpLERK8Vector2d","espp::Vector2d::operator+=::rhs"],[58,3,1,"_CPPv4NK4espp8Vector2dmiERK8Vector2d","espp::Vector2d::operator-"],[58,3,1,"_CPPv4NK4espp8Vector2dmiEv","espp::Vector2d::operator-"],[58,4,1,"_CPPv4NK4espp8Vector2dmiERK8Vector2d","espp::Vector2d::operator-::rhs"],[58,3,1,"_CPPv4N4espp8Vector2dmIERK8Vector2d","espp::Vector2d::operator-="],[58,4,1,"_CPPv4N4espp8Vector2dmIERK8Vector2d","espp::Vector2d::operator-=::rhs"],[58,3,1,"_CPPv4NK4espp8Vector2ddvERK1T","espp::Vector2d::operator/"],[58,3,1,"_CPPv4NK4espp8Vector2ddvERK8Vector2d","espp::Vector2d::operator/"],[58,4,1,"_CPPv4NK4espp8Vector2ddvERK1T","espp::Vector2d::operator/::v"],[58,4,1,"_CPPv4NK4espp8Vector2ddvERK8Vector2d","espp::Vector2d::operator/::v"],[58,3,1,"_CPPv4N4espp8Vector2ddVERK1T","espp::Vector2d::operator/="],[58,3,1,"_CPPv4N4espp8Vector2ddVERK8Vector2d","espp::Vector2d::operator/="],[58,4,1,"_CPPv4N4espp8Vector2ddVERK1T","espp::Vector2d::operator/=::v"],[58,4,1,"_CPPv4N4espp8Vector2ddVERK8Vector2d","espp::Vector2d::operator/=::v"],[58,3,1,"_CPPv4N4espp8Vector2daSERK8Vector2d","espp::Vector2d::operator="],[58,4,1,"_CPPv4N4espp8Vector2daSERK8Vector2d","espp::Vector2d::operator=::other"],[58,3,1,"_CPPv4N4espp8Vector2dixEi","espp::Vector2d::operator[]"],[58,4,1,"_CPPv4N4espp8Vector2dixEi","espp::Vector2d::operator[]::index"],[58,3,1,"_CPPv4I0_PNSt9enable_ifINSt17is_floating_pointI1UE5valueEE4typeEENK4espp8Vector2d7rotatedE8Vector2d1T","espp::Vector2d::rotated"],[58,5,1,"_CPPv4I0_PNSt9enable_ifINSt17is_floating_pointI1UE5valueEE4typeEENK4espp8Vector2d7rotatedE8Vector2d1T","espp::Vector2d::rotated::U"],[58,4,1,"_CPPv4I0_PNSt9enable_ifINSt17is_floating_pointI1UE5valueEE4typeEENK4espp8Vector2d7rotatedE8Vector2d1T","espp::Vector2d::rotated::radians"],[58,3,1,"_CPPv4N4espp8Vector2d1xE1T","espp::Vector2d::x"],[58,3,1,"_CPPv4NK4espp8Vector2d1xEv","espp::Vector2d::x"],[58,4,1,"_CPPv4N4espp8Vector2d1xE1T","espp::Vector2d::x::v"],[58,3,1,"_CPPv4N4espp8Vector2d1yE1T","espp::Vector2d::y"],[58,3,1,"_CPPv4NK4espp8Vector2d1yEv","espp::Vector2d::y"],[58,4,1,"_CPPv4N4espp8Vector2d1yE1T","espp::Vector2d::y::v"],[80,2,1,"_CPPv4N4espp6WifiApE","espp::WifiAp"],[80,2,1,"_CPPv4N4espp6WifiAp6ConfigE","espp::WifiAp::Config"],[80,1,1,"_CPPv4N4espp6WifiAp6Config7channelE","espp::WifiAp::Config::channel"],[80,1,1,"_CPPv4N4espp6WifiAp6Config9log_levelE","espp::WifiAp::Config::log_level"],[80,1,1,"_CPPv4N4espp6WifiAp6Config22max_number_of_stationsE","espp::WifiAp::Config::max_number_of_stations"],[80,1,1,"_CPPv4N4espp6WifiAp6Config8passwordE","espp::WifiAp::Config::password"],[80,1,1,"_CPPv4N4espp6WifiAp6Config4ssidE","espp::WifiAp::Config::ssid"],[80,3,1,"_CPPv4N4espp6WifiAp6WifiApERK6Config","espp::WifiAp::WifiAp"],[80,4,1,"_CPPv4N4espp6WifiAp6WifiApERK6Config","espp::WifiAp::WifiAp::config"],[81,2,1,"_CPPv4N4espp7WifiStaE","espp::WifiSta"],[81,2,1,"_CPPv4N4espp7WifiSta6ConfigE","espp::WifiSta::Config"],[81,1,1,"_CPPv4N4espp7WifiSta6Config6ap_macE","espp::WifiSta::Config::ap_mac"],[81,1,1,"_CPPv4N4espp7WifiSta6Config7channelE","espp::WifiSta::Config::channel"],[81,1,1,"_CPPv4N4espp7WifiSta6Config9log_levelE","espp::WifiSta::Config::log_level"],[81,1,1,"_CPPv4N4espp7WifiSta6Config19num_connect_retriesE","espp::WifiSta::Config::num_connect_retries"],[81,1,1,"_CPPv4N4espp7WifiSta6Config12on_connectedE","espp::WifiSta::Config::on_connected"],[81,1,1,"_CPPv4N4espp7WifiSta6Config15on_disconnectedE","espp::WifiSta::Config::on_disconnected"],[81,1,1,"_CPPv4N4espp7WifiSta6Config9on_got_ipE","espp::WifiSta::Config::on_got_ip"],[81,1,1,"_CPPv4N4espp7WifiSta6Config8passwordE","espp::WifiSta::Config::password"],[81,1,1,"_CPPv4N4espp7WifiSta6Config10set_ap_macE","espp::WifiSta::Config::set_ap_mac"],[81,1,1,"_CPPv4N4espp7WifiSta6Config4ssidE","espp::WifiSta::Config::ssid"],[81,3,1,"_CPPv4N4espp7WifiSta7WifiStaERK6Config","espp::WifiSta::WifiSta"],[81,4,1,"_CPPv4N4espp7WifiSta7WifiStaERK6Config","espp::WifiSta::WifiSta::config"],[81,8,1,"_CPPv4N4espp7WifiSta16connect_callbackE","espp::WifiSta::connect_callback"],[81,8,1,"_CPPv4N4espp7WifiSta19disconnect_callbackE","espp::WifiSta::disconnect_callback"],[81,8,1,"_CPPv4N4espp7WifiSta11ip_callbackE","espp::WifiSta::ip_callback"],[81,3,1,"_CPPv4N4espp7WifiSta12is_connectedEv","espp::WifiSta::is_connected"],[81,3,1,"_CPPv4N4espp7WifiStaD0Ev","espp::WifiSta::~WifiSta"],[14,2,1,"_CPPv4N4espp21__csv_documentation__E","espp::__csv_documentation__"],[73,2,1,"_CPPv4N4espp31__serialization_documentation__E","espp::__serialization_documentation__"],[74,2,1,"_CPPv4N4espp31__state_machine_documentation__E","espp::__state_machine_documentation__"],[75,2,1,"_CPPv4N4espp26__tabulate_documentation__E","espp::__tabulate_documentation__"],[74,2,1,"_CPPv4N4espp13state_machine16DeepHistoryStateE","espp::state_machine::DeepHistoryState"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState5entryEv","espp::state_machine::DeepHistoryState::entry"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState4exitEv","espp::state_machine::DeepHistoryState::exit"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState12exitChildrenEv","espp::state_machine::DeepHistoryState::exitChildren"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14getActiveChildEv","espp::state_machine::DeepHistoryState::getActiveChild"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState13getActiveLeafEv","espp::state_machine::DeepHistoryState::getActiveLeaf"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState10getInitialEv","espp::state_machine::DeepHistoryState::getInitial"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14getParentStateEv","espp::state_machine::DeepHistoryState::getParentState"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState11handleEventEP9EventBase","espp::state_machine::DeepHistoryState::handleEvent"],[74,4,1,"_CPPv4N4espp13state_machine16DeepHistoryState11handleEventEP9EventBase","espp::state_machine::DeepHistoryState::handleEvent::event"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState10initializeEv","espp::state_machine::DeepHistoryState::initialize"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState10makeActiveEv","espp::state_machine::DeepHistoryState::makeActive"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setActiveChildEP9StateBase","espp::state_machine::DeepHistoryState::setActiveChild"],[74,4,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setActiveChildEP9StateBase","espp::state_machine::DeepHistoryState::setActiveChild::childState"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setDeepHistoryEv","espp::state_machine::DeepHistoryState::setDeepHistory"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setParentStateEP9StateBase","espp::state_machine::DeepHistoryState::setParentState"],[74,4,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setParentStateEP9StateBase","espp::state_machine::DeepHistoryState::setParentState::parent"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState17setShallowHistoryEv","espp::state_machine::DeepHistoryState::setShallowHistory"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState4tickEv","espp::state_machine::DeepHistoryState::tick"],[74,2,1,"_CPPv4N4espp13state_machine9EventBaseE","espp::state_machine::EventBase"],[74,2,1,"_CPPv4N4espp13state_machine19ShallowHistoryStateE","espp::state_machine::ShallowHistoryState"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState5entryEv","espp::state_machine::ShallowHistoryState::entry"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState4exitEv","espp::state_machine::ShallowHistoryState::exit"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState12exitChildrenEv","espp::state_machine::ShallowHistoryState::exitChildren"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14getActiveChildEv","espp::state_machine::ShallowHistoryState::getActiveChild"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState13getActiveLeafEv","espp::state_machine::ShallowHistoryState::getActiveLeaf"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState10getInitialEv","espp::state_machine::ShallowHistoryState::getInitial"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14getParentStateEv","espp::state_machine::ShallowHistoryState::getParentState"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState11handleEventEP9EventBase","espp::state_machine::ShallowHistoryState::handleEvent"],[74,4,1,"_CPPv4N4espp13state_machine19ShallowHistoryState11handleEventEP9EventBase","espp::state_machine::ShallowHistoryState::handleEvent::event"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState10initializeEv","espp::state_machine::ShallowHistoryState::initialize"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState10makeActiveEv","espp::state_machine::ShallowHistoryState::makeActive"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setActiveChildEP9StateBase","espp::state_machine::ShallowHistoryState::setActiveChild"],[74,4,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setActiveChildEP9StateBase","espp::state_machine::ShallowHistoryState::setActiveChild::childState"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setDeepHistoryEv","espp::state_machine::ShallowHistoryState::setDeepHistory"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setParentStateEP9StateBase","espp::state_machine::ShallowHistoryState::setParentState"],[74,4,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setParentStateEP9StateBase","espp::state_machine::ShallowHistoryState::setParentState::parent"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState17setShallowHistoryEv","espp::state_machine::ShallowHistoryState::setShallowHistory"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState4tickEv","espp::state_machine::ShallowHistoryState::tick"],[74,2,1,"_CPPv4N4espp13state_machine9StateBaseE","espp::state_machine::StateBase"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase5entryEv","espp::state_machine::StateBase::entry"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase4exitEv","espp::state_machine::StateBase::exit"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase12exitChildrenEv","espp::state_machine::StateBase::exitChildren"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase14getActiveChildEv","espp::state_machine::StateBase::getActiveChild"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase13getActiveLeafEv","espp::state_machine::StateBase::getActiveLeaf"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase10getInitialEv","espp::state_machine::StateBase::getInitial"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase14getParentStateEv","espp::state_machine::StateBase::getParentState"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase11handleEventEP9EventBase","espp::state_machine::StateBase::handleEvent"],[74,4,1,"_CPPv4N4espp13state_machine9StateBase11handleEventEP9EventBase","espp::state_machine::StateBase::handleEvent::event"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase10initializeEv","espp::state_machine::StateBase::initialize"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase10makeActiveEv","espp::state_machine::StateBase::makeActive"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase14setActiveChildEP9StateBase","espp::state_machine::StateBase::setActiveChild"],[74,4,1,"_CPPv4N4espp13state_machine9StateBase14setActiveChildEP9StateBase","espp::state_machine::StateBase::setActiveChild::childState"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase14setDeepHistoryEv","espp::state_machine::StateBase::setDeepHistory"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase14setParentStateEP9StateBase","espp::state_machine::StateBase::setParentState"],[74,4,1,"_CPPv4N4espp13state_machine9StateBase14setParentStateEP9StateBase","espp::state_machine::StateBase::setParentState::parent"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase17setShallowHistoryEv","espp::state_machine::StateBase::setShallowHistory"],[74,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,8,10,11,12,13,14,15,16,18,19,22,23,24,25,26,28,33,34,36,39,40,43,45,46,48,49,50,51,52,53,55,57,58,59,61,62,63,65,66,67,68,69,72,75,76,77,78,81],"00":19,"000":[75,77],"000f":8,"00b":65,"01":[15,33,66],"010f":8,"01f":[19,22],"02":[7,66],"024v":1,"02x":66,"03":[52,59,66],"04":[33,66],"048v":1,"04x":36,"05":66,"054":75,"05f":51,"06":66,"067488":77,"0693":75,"06f":76,"0755":24,"096v":1,"0b00000001":66,"0b00000010":66,"0b00000011":46,"0b00000100":66,"0b00001000":66,"0b0000110":22,"0b00010000":66,"0b00100000":66,"0b00111111":46,"0b0100000":48,"0b01000000":66,"0b0110110":19,"0b10000000":66,"0b11":46,"0b11111":51,"0f":[7,8,13,19,22,23,33,49,50,51,52,53,55,59,67,69],"0m":78,"0s":50,"0x00":[46,48,66],"0x0000":16,"0x06":6,"0x060504030201":66,"0x10":[2,6],"0x13":65,"0x14":40,"0x16":6,"0x24":45,"0x38":39,"0x48":1,"0x51":70,"0x54":68,"0x55":43,"0x58":[36,46],"0x5d":40,"0xa6":66,"0xa8":68,"0xae":66,"0xf412fa42fe9":65,"0xff":[51,66],"0xffffffffffff":65,"1":[1,2,3,6,7,8,10,11,12,13,14,15,16,18,19,22,23,24,25,26,34,36,43,46,48,49,50,52,53,55,57,61,62,63,65,66,67,68,72,73,75,76,77,80],"10":[2,8,11,15,18,36,43,45,50,52,59,73,75,76,77],"100":[16,23,48,49,50,67,77],"1000":[3,8,16,18,36,50,67,72,77],"10000":77,"1000000":69,"10000000":69,"100m":[16,50,59,67,74,76,81],"1024":[1,2,3,6,8,10,13,19,22,23,34,46,48,51,59,62,63,66,69,76,77],"10k":77,"10m":[2,6,50,62,66,76,77],"10mhz":69,"11":[70,75],"11k":6,"12":[2,6,65,75],"123":34,"127":[62,63,65],"128":[1,2,6,62,63,65,72],"12800":16,"128x":[2,6],"13":[46,80],"135":16,"14":46,"144v":1,"14763":77,"15":[2,6,46,70,73,75,77],"1500":72,"152":77,"16":[1,2,6,16,46,48,65,66,75],"1600":1,"16384":[16,19,22],"1678892742599":34,"16kb":66,"16x":[2,6],"17":75,"1700":[13,49],"18":[65,69,75],"18688":65,"187":75,"19":[],"192":65,"1b":65,"1f":[18,23,49,50,67],"1s":[10,33,34,51,52,59,62,63,67,70,72,74,76,78],"2":[1,2,3,6,8,10,13,14,15,19,22,23,24,25,26,28,46,49,50,52,55,58,59,62,63,65,66,67,69,72,75,78],"20":[3,8,16,24,75,77],"200":[33,72,75],"200m":[1,76],"2013":75,"20143":19,"2016":75,"2019":75,"2023":70,"2046":65,"20df":19,"20m":13,"21":[8,13,75],"22":[],"224":[61,62,63],"23":[70,75],"23017":48,"239":[61,62,63],"23s17":48,"240":16,"2400":1,"2435":72,"2494":77,"25":[23,46,75,77],"250":1,"250136576":65,"250m":[18,43],"255":[12,46,51,61,62,63,65,66,69],"256":[3,65,69,72],"2566":75,"256v":1,"25c":77,"264":72,"265":72,"2657":77,"273":77,"298":77,"299":75,"2f":[13,23,77],"2pi":[19,22],"2s":78,"2x":[2,6],"3":[1,2,6,7,8,13,14,15,29,33,46,48,50,62,63,65,69,73,75,77,78],"30":[70,75,77],"300f":8,"300m":52,"31":[13,51,77],"313":75,"32":[1,2,6,13,65],"320":[8,16],"32x":[2,6],"33":13,"3300":[1,49,77],"3380":77,"34":[2,6,8],"3422":77,"3435":77,"3453":77,"3484":69,"3484_datasheet":69,"35981":77,"36":[8,13],"360":[12,19,22,51,69],"36005":19,"37":13,"370":75,"376":75,"37ma":46,"38":13,"39":13,"3940":77,"3950":77,"3986":65,"3f":[1,2,6,10,18,19,22,34,46,48,52,66,67,77,78],"3s":3,"4":[1,2,6,8,10,13,14,19,22,34,51,53,62,63,65,66,69,70,75,76,80],"40":[16,75,77],"400":36,"4096":[18,78],"42":[13,65,73],"43173a3eb323":19,"458":75,"461":75,"475":1,"48":[23,65,66],"4886":46,"48b":66,"490":1,"4\u03c0":75,"4b":65,"4kb":66,"4x":[2,6],"5":[1,2,3,6,8,13,14,19,22,23,26,28,33,34,39,46,48,51,55,59,62,63,65,66,69,73,75,77],"50":[16,46,50,66,69,75,77],"5000":[50,62,63,72],"5001":72,"500m":[3,5,13,23,36,39,40,49,52,59,76,78],"50c":77,"50m":[19,22,45,46,48,51,68,69],"50u":69,"512v":1,"53":16,"53229":77,"55":75,"571":75,"5f":[19,22,50,51,55,63,69],"5m":67,"5s":23,"6":[1,2,6,7,12,13,14,34,62,63,65,66,69,75,81],"60":[16,19,22,75],"61067330":24,"614":75,"61622309":66,"626":75,"64":[1,2,6,69],"649ee61c":19,"64kb":66,"64x":[2,6],"6742":75,"68":75,"7":[2,6,8,34,48,65,68,73,75,77],"70":75,"720":[19,22],"72593":34,"730":75,"75":[46,77],"792":75,"8":[1,2,6,12,15,23,34,46,48,59,65,66,70,75],"80":77,"80552":77,"817":75,"8192":18,"85":77,"8502":77,"854":75,"8554":72,"860":1,"8f9a":19,"8x":[2,6],"9":[18,46,69,75],"90":75,"920":1,"93hart_equ":77,"9692":11,"9781449324094":65,"9907":77,"999":11,"9e":65,"9e10":19,"9th":[2,6],"\u00b2":75,"\u00b3\u2074":75,"\u00b9":75,"\u00b9\u00b2f":75,"\u00b9\u00b9m\u00b3":75,"\u03ba":77,"\u03c9":[75,77],"\u16a0":75,"\u16a1":75,"\u16a2":75,"\u16a3":75,"\u16a4":75,"\u16a5":75,"\u16a6":75,"\u16a7":75,"\u16a8":75,"\u16a9":75,"\u16aa":75,"\u16ab":75,"\u16ac":75,"\u16ad":75,"\u16ae":75,"\u16af":75,"\u16b0":75,"\u16b1":75,"\u16b2":75,"\u16b3":75,"\u16b4":75,"\u16b5":75,"\u16b6":75,"\u16b7":75,"\u16b8":75,"\u16b9":75,"\u16ba":75,"\u16bb":75,"\u16bc":75,"\u16bd":75,"\u16be":75,"\u16bf":75,"\u16c0":75,"\u16c1":75,"\u16c2":75,"\u16c3":75,"\u16c4":75,"\u16c5":75,"\u16c6":75,"\u16c7":75,"\u16c8":75,"\u16c9":75,"\u16ca":75,"\u16cb":75,"\u16cc":75,"\u16cd":75,"\u16ce":75,"\u16cf":75,"\u16d0":75,"\u16d1":75,"\u16d2":75,"\u16d3":75,"\u2076":75,"\u2077":75,"abstract":[37,60,61,76],"boolean":24,"break":74,"byte":[1,2,3,6,15,16,19,22,23,24,34,46,48,51,59,61,62,63,65,66,68,69,70,72],"case":[19,22,63,69],"char":[24,43,62,72,76],"class":27,"const":[1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,22,23,24,25,26,28,29,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,61,62,63,65,66,67,68,69,70,72,76,77,78,80,81],"default":[1,2,6,11,13,15,16,33,34,39,40,43,45,46,48,51,53,55,57,58,59,68,69,70,72,73,80,81],"do":[2,5,10,13,14,23,34,43,59,72,73,74,75,76],"enum":[1,2,6,10,13,15,34,39,46,48,49,51,52,65,68,77],"export":75,"final":[13,19,22,36,39,40,45,46,48,59,65,66,68,70,72,74],"float":[1,2,3,5,6,7,8,10,12,13,15,18,19,22,23,25,26,28,29,33,34,46,48,49,50,51,52,53,54,55,58,59,61,62,63,67,69,74,76,77,78],"function":[1,2,3,5,6,7,8,10,11,12,13,15,16,18,19,22,23,24,25,26,27,28,29,33,34,35,36,37,38,39,40,42,43,44,45,46,48,49,50,51,52,53,54,55,57,58,59,60,61,62,63,65,66,67,69,72,74,76,77,78,80,81],"goto":69,"int":[1,2,5,7,10,11,13,16,18,19,22,23,24,31,46,50,51,58,59,61,62,63,65,66,67,68,69,72,73,74,75,76,77,78],"long":[11,72,75,78],"new":[5,7,8,10,11,16,23,25,26,28,29,31,39,40,45,46,49,50,51,52,55,57,58,65,66,67,68,72,76,78],"null":43,"public":[1,2,3,5,6,7,8,10,11,12,13,15,16,18,19,22,23,24,25,26,28,29,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,59,61,62,63,65,66,67,68,69,70,72,74,76,77,78,80,81],"return":[1,2,3,5,6,7,8,10,11,12,13,15,16,18,19,22,23,24,25,26,28,29,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,59,61,62,63,65,66,67,68,69,70,72,74,76,77,78,81],"short":[13,65],"static":[1,2,6,8,10,11,16,19,22,23,24,33,34,36,39,40,43,45,46,48,50,51,54,59,61,62,63,65,66,68,69,70,74,76,77,78],"super":14,"switch":[2,6,15,69],"throw":[11,24],"true":[1,2,6,7,8,10,11,13,14,15,16,18,19,22,23,24,31,33,34,36,39,40,43,44,45,46,48,49,50,51,52,57,61,62,63,65,66,67,68,69,70,72,74,75,76,78,81],"try":[],"void":[2,3,6,7,8,10,11,13,15,16,19,22,23,25,28,31,33,34,36,39,40,43,44,45,46,48,49,50,51,52,55,57,58,61,62,63,65,66,67,68,69,70,72,74,77,78,81],"while":[10,11,16,23,43,50,52,59,72,74,76,81],A:[2,6,7,10,13,23,30,31,48,51,62,65,68,72,75,78],And:51,As:23,By:11,For:[11,15,29,34,68,72,75,76],IN:34,IT:[24,66],If:[2,5,6,7,11,12,23,33,34,36,44,50,57,61,62,63,65,72,74,76,78,80,81],In:[13,23,46],Is:[61,62,63,76],It:[2,3,5,6,8,10,11,13,14,19,22,23,24,31,33,34,36,43,45,46,50,51,67,69,72,74,75,76,77],NOT:[2,13],No:[2,6,33,52,65],Not:24,ON:11,ONE:1,On:[2,33,43],The:[1,2,3,5,6,7,8,9,10,11,12,13,14,15,18,19,22,23,24,25,26,28,29,30,31,32,33,34,36,38,39,40,42,43,45,46,48,49,50,51,52,53,54,55,57,58,59,60,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],There:[19,21,22,27,35,47,59,74],These:[2,6,9,69,72],To:[23,68,72],Will:[7,19,22,46,57,59,61,66,72,74],With:49,_1:[39,40,43,45,59,68,70],_2:[39,40,43,45,59,68,70],_3:[39,40,43,45,68,70],_4:[39,40,68,70],_5:40,_:14,__csv_documentation__:14,__gnu_linux__:[14,73],__linux__:11,__serialization_documentation__:73,__state_machine_documentation__:74,__tabulate_documentation__:75,__unix__:75,__unnamed11__:68,__unnamed13__:68,__unnamed7__:65,__unnamed9__:65,_activest:74,_build:[31,68,70],_cli:11,_event_data:74,_in:11,_lv_refr_get_disp_refresh:[],_out:11,_parentst:74,_rate_limit:52,_really_:51,a0:[48,49],a1:49,a2:48,a_0:25,a_1:25,a_2:25,a_gpio:18,a_pin:48,ab:[57,77],abi:[21,37],abi_encod:18,abil:[52,59],abl:[31,49,62,74,78],about:[11,14,59,63,65,66,69,74,75,77],abov:[2,6,11,19,22,23,46,51,69,74],absolut:[19,22,24,65],absolute_uri:65,abxi:13,ac:65,acceler:28,accept:[31,62,72],access:[18,24,37,61,66,74,79,81],accord:[24,46,48,49,50,52,72],accordingli:[10,13],accumul:[18,19,22,68],accur:67,ack:[2,6],acknowledg:[36,62],across:[3,33],act:65,action:[74,76],activ:[2,6,7,10,13,48,65,66,72,74],active_high:[2,6,48],active_level:10,active_low:[2,6,13],activeleaf:74,activelevel:10,actual:[1,2,6,13,16,23,33,34,65,72,74,77],actual_celsiu:77,actual_kelvin:77,actuat:[34,35],ad0:46,ad1:46,ad:[1,2,8,13,23,58,65,72],adafruit:[13,34,46,65,69],adc1:77,adc:[13,18,34,37,67],adc_atten_db_11:[3,5,13,49,77],adc_channel_1:13,adc_channel_2:13,adc_channel_6:[3,5],adc_channel_7:[3,5,77],adc_channel_8:49,adc_channel_9:49,adc_channel_t:[3,5],adc_conv_single_unit_1:[3,77],adc_conv_single_unit_2:[],adc_decap:6,adc_digi_convert_mode_t:3,adc_typ:0,adc_unit_1:[3,5,77],adc_unit_2:[13,49],adc_unit_t:5,adcconfig:[3,5,13,49,68,70,77],add:[7,12,16,58,61,62,63,72],add_multicast_group:[61,62,63],add_publish:23,add_row:75,add_scan:72,add_subscrib:[10,23],addit:[3,12,15,37,49,58,76],addition:[2,6,10,11,72],addr:[34,61,66],address:[1,2,6,16,19,22,31,34,36,39,40,43,45,46,48,61,62,63,65,66,68,70,72,81],adjust:[33,62],ads1015:1,ads1015config:[1,13],ads1015rat:1,ads1115:1,ads1115config:1,ads1115rat:1,ads1x15:[4,13,37],ads7128:[2,6],ads7138:[4,37],ads_read:[1,2,13],ads_read_task_fn:[1,2,13],ads_task:[1,2,13],ads_writ:[1,2,13],adventur:14,advis:57,ae:65,affect:[19,22,72],affin:76,after:[2,6,15,43,49,51,57,61,62,63,66,69,72,78,81],again:[23,66,74],agent:72,alert:[2,6],alert_1000m:34,alert_750m:34,alert_log:2,alert_pin:2,alert_task:2,alertlog:[2,6],algorithm:[7,8,9,12,75],alias:[19,22],align:[51,75],aliv:31,all:[2,5,6,7,11,23,24,34,46,51,52,57,59,63,68,69,72,74],all_mv:[2,6],all_mv_map:6,alloc:[3,15,59,76],allocatingconfig:[15,16],allocation_flag:15,allow:[1,2,3,5,6,7,8,11,13,15,18,19,22,33,34,36,39,40,43,45,46,48,49,50,51,55,57,60,61,62,63,67,68,69,70,72,74,76,77],along:[54,66],alow:55,alpaca:[23,37],alpha:[50,55],alreadi:[23,24,25,62,63,72,76,78],also:[2,6,11,13,14,15,16,19,22,23,24,33,34,46,59,69,72,74,75,76],alt:43,alter_unit:[3,77],altern:[2,3,24,40,65],alwai:[3,5,7,8,19,22,24,34,57,59,72,74],am:19,amount:[3,24,57,58],amp:8,amplitud:55,an:[0,1,2,5,6,7,10,11,12,13,18,19,22,23,24,25,26,28,29,30,32,33,34,40,43,44,45,46,48,49,51,53,55,57,59,61,62,63,65,68,69,72,74,75,76,78,81],analog:[2,3,5,6,34,49],analog_input:[2,6],analogev:2,analogjoystickconfig:13,analyz:59,anaolg:13,android:[65,66],angl:[8,19,22],angle_filt:8,angle_openloop:8,angle_pid_config:8,ani:[2,5,6,7,8,10,11,14,19,22,31,46,51,61,62,63,66,69,72,74,75,76,78],anonym:[23,65],anoth:[10,11,23,24,58],answer:11,any_edg:10,anyth:[14,52,59,73,74,75],anywher:11,ap:[37,79,81],ap_mac:81,apa102_start_fram:51,apa:65,api:37,app:[65,66],app_main:59,appear:65,append:[2,6,72],appli:[3,46,49],applic:[37,72,75],appropri:[7,62,63],approxim:[2,6,49,54],ar:[2,4,6,7,8,9,11,13,16,17,18,21,23,24,27,33,34,35,46,47,48,49,51,52,57,59,60,62,65,66,67,68,69,72,73,74,76,78,79],arari:73,arbitrari:11,area:[15,16],arg:52,argument:[31,52,68,70],arithmet:25,around:[3,5,7,10,11,14,15,24,36,38,42,44,49,50,52,53,55,57,61,69,73,74,75,76],arrai:[1,2,6,16,19,22,25,28,29,34,46,48,53,61,62,63,66,73],arrow:11,articl:77,artifact:69,as5600:[21,37],as5600_ds000365_5:19,as5600_read:19,as5600_writ:19,asid:50,ask:76,aspect:11,assert:[],asset:34,assign:58,associ:[0,3,5,10,13,15,16,18,23,38,42,44,46,48,49,50,53,58,59,61,62,63,76],associt:[61,62,63],assum:[11,51,62,63,77],assumpt:[19,22],asymmetr:67,ate:24,atom:[8,13],attach:[16,46],attenu:[0,3,5,13,49,77],attribut:[1,2,6,19,22,39,40,43,45,46,48,51,65,66,68,69,70],audio:34,audiovib:34,authent:[31,65],auto:[1,2,3,5,6,8,10,11,13,14,16,18,19,22,23,24,33,34,36,39,40,43,45,46,48,49,50,51,52,59,62,63,66,67,68,69,70,73,74,75,76,77,78],auto_init:[2,6,19,22,34,36,46,48,66],auto_seq:[2,6],auto_start:[43,78],autoc:34,automat:[2,6,11,12,19,22,36,43,46,66,72,75,76,78],autonom:[2,6],autostop:76,avail:[3,18,23,58,66],avdd:[2,6],avdd_volt:[2,6],averag:[2,6,12],aw9523:[37,47],aw9523_read:46,aw9523_writ:46,aw9523b:46,awaken:14,ax:[13,49],axi:[2,8,13,49],b0:65,b1:65,b25:77,b2:65,b3:65,b4:65,b7:48,b:[7,11,12,13,14,18,30,43,46,48,51,55,59,65,66,68,69,73,76,77],b_0:25,b_1:25,b_2:25,b_bright:46,b_down:46,b_gpio:18,b_led:46,b_pin:48,b_up:46,back:[11,15,24,62,63,66,69],background:[33,78],background_color:75,backlight:[15,16,43],backlight_on_valu:[15,16],backlight_pin:[15,16],backspac:11,bad:[12,77],band:65,bandwidth:62,base:[8,12,19,22,25,26,27,28,29,33,50,51,59,61,66,67,69,72,74,75,77],base_encod:69,basi:[2,6],basic:11,batch:75,batteri:23,batteryst:23,bcd2byte:70,bcd:70,becaus:[8,19,22,24,69,75,78],becom:6,been:[2,6,11,25,34,43,51,62,63,66,68,69,72,76,78],befor:[2,6,18,24,33,51,62,66,72,74,76,78,81],beg:24,begin:[11,23,24,62,63,65,76],behavior:[33,67],being:[1,2,3,5,6,8,11,13,18,19,22,23,34,36,39,40,45,46,48,49,51,67,68,69,70,74,76,77],belong:63,below:[2,6,8,74,75],beta:[50,55,77],better:[28,67],between:[12,15,23,32,53,57,66],beyond:[11,14,69,75],bezier:[37,56],bezierinfo:53,bgr:51,bi:66,bia:33,biequad:25,binari:24,bind:[31,39,40,43,45,52,59,62,63,68,70,72],biquad:[26,27,29,37],biquad_filt:25,biquadfilt:25,biquadfilterdf1:25,biquadfilterdf2:[19,22,25,26,29],biquadrat:25,bit0:69,bit1:69,bit:[2,6,11,13,16,46,48,50,65,66,68],bitfield:[2,6],bitmask:2,bldc:[35,37],bldc_driver:7,bldc_haptic:33,bldc_motor:[8,9],bldc_type:8,bldcdriver:[7,8],bldchaptic:33,bldcmotor:[8,19,22,33],ble:[65,66],ble_appear:66,ble_radio_nam:66,ble_rol:66,blend:12,blerol:[65,66],blob:[11,16],block:[2,3,5,6,11,33,50,51,62,63,69,72,76,78],block_siz:69,blue:[12,14,51,69,75],bluetooth:65,bm8563:[37,68,71],board:[16,68],bob:[8,31,68,70],bodmer:16,bold:75,bool:[1,2,6,7,8,10,11,13,15,16,18,19,22,23,24,31,33,34,36,39,40,43,44,45,46,48,49,50,51,57,61,62,63,65,66,67,68,69,70,72,74,76,78,81],boot:43,border_bottom:75,border_color:75,border_left:75,border_right:75,border_top:75,both:[2,3,6,13,14,25,33,45,46,48,49,50,57,65,69,75],both_unit:[3,77],bother:45,bottom:11,bound:[33,62,69],bounded_no_det:33,box:[13,31,45,66,68,70],boxart:14,bp:2,br:65,breakout:68,breathing_period:50,breathing_start:50,bredr:65,bright:[15,46,51],bro:14,broadcast:[63,65],broken:72,brushless:[7,8,9],bs:23,bsp:16,bt:65,btappear:[65,66],bteir:65,btgoep:65,btl2cap:65,btspp:65,btssp_1_1:65,bttype:65,bu:[2,6,16,36,39,68],budget:75,bufer:76,buffer:[2,3,6,10,15,23,62,69,72,73,76],buffer_s:63,build:[27,37,72],built:[14,62,73,74,75],bundl:13,buscfg:16,busi:63,butterworth:[27,37],butterworth_filt:26,butterworthfilt:[19,22,26,29],button:[2,13,37,38,40,42,44,45,46,68],button_2:10,button_component_nam:10,button_st:[45,68],button_top:10,buttonst:[68,70],buzz1:34,buzz2:34,buzz3:34,buzz4:34,buzz5:34,byte2bcd:70,byte_ord:51,byteord:51,bytes_encod:69,bytes_encoder_config:69,bytes_written:[10,73],c:[7,11,14,16,23,24,37,65,69,73,75,77],c_str:24,cach:[40,72],calcul:[2,6,8,33,77],calibr:[5,8,34,49],call:[2,3,5,6,10,11,12,13,15,18,19,22,23,33,34,40,43,45,46,49,51,52,59,61,62,63,66,67,68,69,72,74,76,78,80,81],call_onc:23,callback:[1,2,3,5,6,8,10,13,15,18,19,22,23,34,36,39,40,43,45,46,48,49,50,51,59,60,61,62,63,66,67,68,69,70,72,74,76,77,78],callback_fn:[76,78],camera:72,can:[2,6,7,8,9,10,11,12,13,15,16,18,19,22,24,31,32,33,34,43,45,49,50,51,52,53,57,59,62,63,65,66,67,69,72,73,74,75,76,77,78,80],can_chang:50,cannot:[24,62,66,72,73],capabl:[46,65,66],capacit:[39,45],captain:75,captur:[2,6,48],carrier:65,carrier_data_ref:65,carrierpowerst:65,catalog:77,caus:[72,74],caution:11,cb:[16,23,72],cc:66,cdn:[46,69],cell:[14,75],celsiu:77,center:[13,33,49,57,75],central:65,central_onli:65,central_peripher:65,certain:[33,74],cf:65,ch04:65,ch0:[2,6],ch1:[2,6],ch2:[2,6],ch3:[2,6],ch4:[2,6],ch5:[2,6],ch6:[2,6],ch7:[2,6],chang:[8,10,12,33,46,48,50,52,55,67,72,74],change_gain:67,channel:[0,1,2,3,5,6,7,12,13,18,49,50,69,72,77,80,81],channel_id:[2,6],channel_sel:[2,6],channelconfig:50,charact:11,characterist:75,chart:[59,75],chdir:24,check:[2,7,8,10,24,31,33,50,61,62,68,72,78,81],child:74,childstat:74,chip:[1,2,3,6,18,21,40,46,47,48,51,66,70,77],choos:7,chose:77,chrono:[1,2,6,8,10,15,19,22,34,43,46,48,50,51,52,59,61,62,63,67,69,74,76,77,78],chrono_liter:[1,2,6,13,34],chunk:65,cin:[11,74],circl:49,circuit:77,circular:49,clamp:[7,12,67,69],clang:77,class_of_devic:65,classic:65,clean:[24,62,76],cleanup:[24,61],clear:[2,11,16,18,46,66,67,72],clear_event_high_flag:2,clear_event_low_flag:2,clear_lin:11,clear_pin:46,clear_screen:11,clear_to_end_of_lin:11,clear_to_start_of_lin:11,cli:[37,74],client:[31,32,37,60,61],client_socket:[62,63],client_task:[62,63],client_task_fn:[62,63],clifilesesson:11,clint:75,clisess:11,clk_speed:[1,2,6,13,19,22,34,36,46,48,66],clock:[2,6,36,51,65,69],clock_spe:16,clock_speed_hz:16,clock_src:69,close:[8,9,19,22,24,33,62,72],clutter:74,co:[51,69],coars:33,coarse_values_strong_det:33,code:[1,2,4,6,8,9,11,16,17,18,19,22,23,24,34,39,40,43,45,46,48,49,52,59,60,65,66,67,68,69,72,73,74,75,76,78,79],coeffici:[25,28,30,55,77],collect:[2,72],color:[11,15,16,37,51,69,75],color_data:15,color_map:16,column:[75,77],column_separ:75,com:[2,6,7,8,11,14,16,19,24,25,29,33,34,46,52,63,65,66,69,72,74,75,77,80,81],combin:[61,62,63],combo:61,come:63,comma:14,command:[8,16,31,37],common:[13,16,34,65],common_compon:11,commun:[1,2,6,13,19,22,34,39,40,43,45,46,48,62,63,66,68,70],compat:72,complet:[2,6,11,14,34,50,65,72,75,76],complex:76,complex_root:74,compon:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,18,19,20,21,22,23,24,25,26,28,29,30,31,33,34,35,36,37,38,39,40,42,43,44,45,46,47,48,49,50,51,52,53,54,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],compos:65,comput:[12,19,22,32,57,65,67,77],compute_voltag:77,condit:[18,36,50,76],condition_vari:[1,2,3,5,6,8,13,18,19,22,34,36,39,40,45,46,48,49,51,66,67,68,69,70,74,76,77],conf:[3,5],config:[1,2,3,5,6,7,8,10,13,15,18,19,22,24,26,28,29,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,59,61,62,63,65,66,67,68,69,70,72,76,77,78,80,81],config_bt_ble_en:66,config_esp32_wifi_nvs_en:[80,81],config_esp_maximum_retri:81,config_esp_wifi_password:[66,80,81],config_esp_wifi_ssid:[66,80,81],config_freertos_generate_run_time_stat:59,config_freertos_use_trace_facil:59,config_hardware_box:16,config_hardware_ttgo:16,config_hardware_wrover_kit:16,config_rtsp_server_port:72,configur:[0,1,2,3,5,6,7,8,10,11,13,15,16,18,19,22,24,26,28,29,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,59,61,62,63,65,66,67,68,69,70,72,73,74,76,77,78,81],configure_alert:2,configure_global_control:46,configure_l:46,configure_pow:7,configure_stdin_stdout:[11,74],confirm:65,confirm_valu:65,connect:[6,8,10,13,31,34,48,50,62,65,72,80,81],connect_callback:81,connect_config:62,connectconfig:62,consecut:2,consol:75,constant:[67,75],constexpr:[1,2,6,16,19,22,33,36,39,40,43,45,46,48,65,66,68,69,70,73],construct:[1,2,6,10,11,12,19,20,22,26,29,34,36,39,46,48,52,53,55,59,61,66,68,72,76,78],constructor:[2,6,11,12,23,33,40,43,45,46,51,52,58,61,69,70,72,77],consum:74,contain:[0,10,11,12,13,15,16,18,23,24,30,33,38,42,44,53,58,59,63,65,66,67,68,72,73,74,81],content:[24,75],context:[23,74,78],contin:[],continu:[2,4,6,11,24,34,37,63,76,77],continuous_adc:3,continuousadc:[3,77],control:[2,6,7,8,9,16,19,22,23,31,33,34,37,41,43,46,48,50,51,53,65,67,68,72],control_point:53,control_socket:72,controller_driv:16,conveni:[11,13,14,19,22,50,61,73,74,75],convers:[1,2,3,6,12,19,22,49,61],convert:[2,5,6,7,8,12,13,19,22,23,24,49,57,61,66,70,72,77],convert_mod:[3,77],convieni:[53,55],cool:52,coolei:75,coordin:[16,39,40,44],copi:[11,12,24,58,69,74,76],copy_encod:69,core:[10,65,76,78],core_id:[8,10,76,78],core_update_period:8,corner:[16,75],correct:[8,74],correspond:[2,6,16,34,46,68,77],could:[2,6,12,14,19,24,39,40,67,73,74,75],couldn:[23,24],count:[1,2,6,8,10,18,19,22,34,46,48,50,51,52,59,67,69,76,77],counter:[18,19,22],counts_per_revolut:[18,19,22],counts_per_revolution_f:[19,22],counts_to_degre:[19,22],counts_to_radian:[19,22],coupl:[23,49],cout:[11,75],cplusplu:11,cpp:[24,31,37,52,66,68,70,72],cpprefer:[24,52],cpu:59,cr:72,crd:18,creat:[2,8,10,11,12,13,14,16,18,19,22,24,31,33,49,51,52,57,59,62,63,65,66,67,69,72,74,75,76,77,80,81],create_dev:[],create_directori:24,creation:[19,22],credenti:65,cross:[2,52,76,78],cs:8,cseq:72,csv2:14,csv:[2,6,24,37],csv_data:14,ctrl:11,cubic:53,curent:[61,74],current:[7,8,10,11,13,16,18,19,22,23,31,32,33,43,44,46,50,52,55,58,59,60,67,68,69,72,77,81],current_directori:31,current_duti:50,current_hfsm_period:74,current_limit:8,current_pid_config:8,current_sens:8,currentlyact:74,currentsensor:8,currentsensorconcept:8,cursor:[11,16],curv:53,custom:[15,23,24,34,69,73],cutoff:[8,26,28],cv:[1,2,3,5,6,8,13,18,19,22,23,34,36,39,40,45,46,48,49,50,51,62,66,67,68,69,70,74,76,77],cv_retval:76,cv_statu:76,cxx:[],cyan:75,cycl:[7,34,50,69],d2:13,d3:13,d4:13,d5:13,d6:13,d:[8,13,23,52,61,62,63,70],d_current_filt:8,dai:70,dam:77,daniele77:11,data:[0,1,2,3,5,6,8,10,12,13,14,15,16,19,22,23,24,25,26,28,29,31,34,36,39,40,43,44,45,46,48,49,51,59,61,62,63,65,66,68,70,72,73,74,77,81],data_address:66,data_command_pin:16,data_len:[1,2,6,13,19,22,34,36,39,45,46,48,68],data_s:69,data_sheet:77,data_str:23,dataformat:[2,6],datasheet:[19,34,46,66,69,77],datasheet_info:77,date:[3,24,68,70,75],date_tim:[24,70],datetim:[68,70],dav:65,db:77,dbm:65,dc:[7,8,9,16],dc_level_bit:16,dc_pin:16,dc_pin_num:16,de:23,dead_zon:7,deadband:[13,49,57],deadzon:49,deadzone_radiu:49,deal:65,debug:[8,52,66,74,76,78],debug_rate_limit:52,deck:43,decod:[8,19,22,39,40,43,66,68,72],dedic:13,deep:74,deep_history_st:74,deephistoryst:74,default_address:[1,2,6,19,22,34,39,43,45,46,48,68,70],default_address_1:40,default_address_2:40,defautl:55,defin:[23,51,57,69,72,73,74],definit:[20,23],deftail:68,degre:[18,19,22],deinit:[3,36,81],deiniti:36,del:69,delai:[8,25],delet:[5,11,13,18,24,69],delete_fn:69,delimit:14,demo:[11,16],depend:[3,33,57,69,74],depth:69,dequ:11,deriv:[67,74],describ:[15,16,57,62,65,72],descriptor:[61,62,63],deseri:[10,23,65,73],design:[13,19,22,33,35,38,42,43,44,51,72,74,77],desir:[0,7,33],destin:24,destroi:[1,2,3,5,6,7,8,10,13,18,19,22,31,34,36,39,40,45,46,48,49,51,67,68,69,70,72,74,76,77,78],destruct:76,destructor:[11,23,33,69,72,76],detail:[8,33,62,65],detect:[10,11,39],detent:33,detent_config:33,detentconfig:[33,68,70],determin:[19,22],determinist:3,dev:16,dev_addr:[1,2,6,13,19,22,34,36,45,46,48],dev_kit:16,devcfg:16,develop:[8,16,65,74],devic:[1,2,6,16,19,22,33,34,36,38,39,42,44,45,46,48,65,66,68,80],device_address:[1,2,6,19,22,34,36,46,48],device_class:65,devkit:16,diagno:34,diagnost:34,did_pub:23,did_sub:[10,23],differ:[2,6,16,19,20,21,22,23,25,27,34,47,50,51,52,66,67,69,74],digial:28,digit:[2,6,25,26,29],digital_biquad_filt:[25,29],digital_input:[2,6],digital_output:[2,6],digital_output_mod:[2,6],digital_output_valu:[2,6],digitalconfig:13,digitalev:2,dim:46,dimension:58,dir_entri:24,dirac:75,direct:[5,13,25,46,48,66],directli:[2,6,7,9,21,34,35,51,53],director:75,directori:[24,31,68,70],directory_iter:24,directory_list:24,disabl:[2,6,7,8,11,18,19,46,66,69],disconnect:[72,81],disconnect_callback:81,discontinu:57,discover:65,discuss:[11,66],disp:[],displai:[14,37,65,72],display_driv:[16,17],display_event_menu:74,distinguish:73,distribut:[23,57],divid:[12,25,58,67,69,77],divider_config:77,divis:77,dma:[3,69,77],dma_en:69,dnp:[2,6],doc:[7,11,15,31,68,69,70,77,80,81],document:[11,14,19,69,73,74,75],doe:[3,5,7,11,14,18,19,22,24,31,33,46,48,51,61,68,72,73,74,75,78],doesn:[2,6,24],don:[1,2,3,5,6,8,13,18,19,22,23,34,36,39,40,45,46,48,49,51,59,62,63,66,67,68,69,70,74,76,77,78],done:[23,50,61,62,63],dot:58,doubl:[11,15],double_buff:15,double_click:34,down:[11,13,42,51,61,62,63,67,68,74,76],download:65,doxygen:[31,68,70],doxygenfunct:[31,68,70],drain:[2,6],draw:[15,16],drive:[2,8,23,34,35,46,69],driven:[33,35],driver:[1,2,6,8,9,11,13,15,17,19,22,35,36,37,38,40,42,44,45,46,48,51,66,68,70,72],driverconcept:8,drv2605:[35,37],drv:16,ds:[2,6,34],dsiplai:15,dsp:[25,28],dsprelat:[25,29],dt:70,dual:[13,65],dualconfig:13,dummycurrentsens:8,dump:75,durat:[1,2,6,8,10,15,19,22,33,34,46,48,50,51,52,59,61,62,63,67,69,74,76,77,78],duration0:69,duration1:69,dure:[66,67,74],duti:[7,50],duty_a:7,duty_b:7,duty_c:7,duty_perc:50,duty_resolut:50,dx:14,dynam:[8,33,55,66,67],dynamictask:76,e2:77,e:[11,24,34,51,55,65,69,74,77],each:[2,3,5,6,7,12,13,23,24,29,31,33,46,49,52,59,68,72,73],earli:[1,2,3,5,6,8,13,18,19,22,34,36,39,40,45,46,48,49,51,67,68,69,70,74,76,77],easili:[2,6,19,60,75,76],eastwood:75,ec:[1,2,6,10,13,19,22,23,24,34,36,39,40,43,45,46,48,66,68,70,72,73],eccentr:[34,35],ecm:34,ed:18,edg:[2,6,10,19,22,33,34,69],edit:11,edr:65,eeprom:66,effici:[6,14],eh_ctrl:66,eight:1,eir:65,either:[13,18,59,77],el_angl:8,elaps:[1,2,6,10,34,50,52,66,67,76,77,78],electr:[8,75],element:[5,58],els:[2,3,5,8,10,24,36,45,46,48,66,70,73,74,75,77],em:[10,23],emb:75,embed:75,embedded_t:75,emplace_back:66,empti:[34,51,65,72,80,81],empty_row:75,emu:[31,68,70],en:[7,11,24,25,26,29,31,52,61,62,63,65,66,68,69,70,77,80,81],enabl:[2,3,5,6,7,8,10,11,13,15,23,33,43,46,59,60,62,66,75,76,80,81],enable_if:[18,58],enable_reus:[61,62,63],encapsul:66,encod:[33,37,41,72],encode_fn:69,encoded_symbol:69,encoder_input:38,encoder_typ:20,encoder_update_period:[19,22],encoderinput:38,encodertyp:18,encrypt:65,end:[2,6,11,16,23,24,33,34,51,62,63,65,66,74,76],end_fram:51,endev:74,endif:[16,66,75],endl:[11,75],endpoint:[61,62,63],energi:65,enforc:[74,75],english:[46,65],enough:[11,76],ensur:[8,11,57,68,69,80,81],enter:[2,6,11,42,74],enterpris:65,entri:[59,74],enumer:[1,2,6,10,13,15,34,39,46,48,49,51,52,65,68,77],eoi:72,epc:65,equal:11,equat:[18,25,77],equival:[11,14,46,75],erm:[34,35],erm_0:34,erm_1:34,erm_2:34,erm_3:34,erm_4:34,err:[1,2,6,13,19,22,24,34,46,48,66],error:[1,2,6,10,13,19,22,23,24,34,39,40,43,45,46,48,52,66,67,68,69,70,72,77],error_cod:[1,2,6,10,13,19,22,23,24,34,36,39,40,43,45,46,48,66,68,70,72,73],error_rate_limit:52,escap:42,esp32:[3,7,11,13,24,31,33,45,49,68,69,70,72,75,80,81],esp32s2:3,esp32s3:3,esp:[3,5,7,10,11,16,18,25,28,31,36,37,50,52,63,66,68,69,70,72,75,76,78,80,81],esp_bt_dev_get_address:66,esp_err_t:[16,69],esp_error_check:16,esp_lcd_ili9341:16,esp_log:52,esp_ok:[1,2,6,13,19,22,34,46,48,66,69],esp_wrover_dev_kit:[],esphom:16,espp:[1,2,3,5,6,7,8,10,11,12,13,15,16,18,19,22,23,24,25,26,28,29,31,32,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,76,77,78,80,81],espressif:[7,11,16,28,63,69,80,81],estim:75,etc:[10,24,42,46,48,51,67,69,73],evalu:[53,55],even:[66,73,75],evenli:33,event1:23,event1_cb:23,event2:23,event2_cb:23,event:[2,6,10,11,37,66,74,81],event_callback_fn:[10,23],event_count:2,event_flag:2,event_high_flag:2,event_low_flag:2,event_manag:23,eventbas:74,eventdata:81,eventmanag:[10,23],everi:[15,19,22,52],everybodi:11,everyth:11,exactli:65,exampl:[4,9,17,60,79],exceed:81,excel:8,except:[11,24],exchang:65,execut:[11,23,74,76,78],exis:81,exist:[7,11,14,24,72,73,74,75],exit:[1,2,3,5,6,8,11,13,18,19,22,34,36,39,40,45,46,48,49,51,67,68,69,70,74,76,77],exitact:11,exitchildren:74,exitselect:74,exp:[55,59],expand:37,expir:78,explicit:[10,11,36,39,40,43,45,61,68,70,72,76,77,78],explicitli:[11,76],expos:[11,14,52,75],extend:65,extern:[2,6,11,34,49,65,74,75],external_typ:65,extra:[69,72],extra_head:72,exttrigedg:34,exttriglvl:34,f4:65,f:[11,24],f_cutoff:[26,28],f_sampl:[26,28],fa:65,facil:59,factor:[19,22,28,33,77],fade:50,fade_time_m:50,fahrenheit:77,fail:[1,2,6,10,13,19,22,34,36,39,45,46,48,66,68,73,81],fake:76,fall:[2,6,10,66,69],falling_edg:10,fals:[1,2,3,5,6,7,8,10,11,13,16,18,19,22,23,24,31,33,34,36,39,40,43,44,45,46,48,49,50,51,57,59,62,63,66,67,68,69,70,72,74,76,77,78,81],famili:[1,2,6],far:11,fast:[37,56,66],fast_co:54,fast_ln:54,fast_math:54,fast_sin:54,fast_sqrt:54,fastest:[19,22],fault:7,fclose:24,fe:65,featur:[2,11],feedback:[33,34,35],feel:8,few:[11,16,23,74],ff:65,fi:[80,81],field:[2,6,8,24,49,65,66,68,72],field_fal:66,field_ris:66,figur:[14,24,73,74,75],file2:24,file:[32,37],file_byt:24,file_cont:24,file_s:24,file_str:24,file_system:24,filenam:14,filesystem:31,fill:[16,25,28,44,49,61,62,63,66],filter:[3,5,8,18,19,22,30,37,77],filter_cutoff_hz:[19,22],filter_fn:[8,19,22],fine:33,fine_values_no_det:33,fine_values_with_det:33,finger563:74,finish:[11,33,69],first:[2,8,23,34,51,62,63,65,66,72,77,78],first_row_is_head:14,fish:11,fit:15,fix:77,fixed_length_encod:73,fixed_resistance_ohm:77,flag:[2,6,16,23,65,66,69],flip:57,floatrangemapp:49,flush:[15,16,24],flush_callback:[15,16],flush_cb:16,flush_fn:15,fmod:50,fmt:[2,3,5,6,11,13,14,16,18,19,22,23,36,39,40,43,45,46,48,49,50,59,62,63,66,67,68,69,70,72,73,74,75,76,77,78,81],foc:[7,8],foc_typ:8,foctyp:8,folder:[4,9,11,14,17,18,49,52,59,60,67,73,74,75,76,78,79],follow:[2,6,8,25,33,34,51,54,59,65,66,69,74,77],font_align:75,font_background_color:75,font_color:75,font_styl:75,fontalign:75,fontstyl:75,fopen:24,forc:[7,15],force_refresh:15,form:[25,26,72],format:[2,6,14,16,23,24,37,59,65,72,75,76,77],formula:77,forum:65,forward:11,found:[19,22,34,45,65,66],four:1,frac:[25,55,77],frag_typ:72,fragment:72,frame:[2,6,51,72],fread:24,free:[15,24,50,69,75],free_spac:24,freebook:[25,29],freerto:[10,59,76,78],frequenc:[3,5,19,22,26,28,33,50],frequency_hz:50,frequent:[15,67],from:[1,2,3,5,6,7,8,11,12,13,15,16,19,22,23,24,27,31,33,34,35,36,37,39,40,43,44,45,46,48,49,50,52,55,57,58,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,81],from_sockaddr:61,fs:24,fseek:24,ft5x06:[37,41],ftell:24,fthat:12,ftm:66,ftp:[37,65,72],ftp_anon:65,ftp_client_sess:31,ftp_ftp:65,ftp_server:31,ftpclientsess:31,ftpserver:31,fulfil:[19,22],full:[7,46,51,72],fulli:[34,74,76],fun:23,further:72,futur:[52,65,72],fwrite:24,g:[12,24,34,46,51,55,65,69,77],g_bright:46,g_down:46,g_led:46,g_up:46,gain:[1,33,67],game:65,gamepad:[65,66],gamma:[50,55],gate:7,gaussian:[37,50,56],gb:14,gbc:14,gener:[2,19,22,27,61,65,69,72,80,81],generatedeventbas:74,generic_hid:65,geometr:12,gestur:39,get:[1,2,3,6,7,8,10,11,12,13,14,15,16,18,19,22,23,24,31,33,38,39,40,42,43,44,45,46,48,49,50,51,55,59,61,62,63,65,66,67,69,70,72,73,74,75,76,77,81],get_accumul:[19,22],get_all_mv:[2,6],get_all_mv_map:[2,6],get_bright:15,get_button_input_devic:38,get_button_st:68,get_celsiu:77,get_config:67,get_count:[18,19,22],get_dat:70,get_data:72,get_date_tim:70,get_degre:[18,19,22],get_digital_input_valu:[2,6],get_duti:50,get_electrical_angl:8,get_encoder_input_devic:38,get_error:67,get_event_data:2,get_event_flag:2,get_event_high_flag:2,get_event_low_flag:2,get_fahrenheit:77,get_free_spac:24,get_ftm_length:66,get_head:72,get_height:72,get_histori:11,get_home_button_input_devic:44,get_home_button_st:[40,45],get_id:65,get_info:76,get_input_devic:42,get_integr:67,get_interrupt_captur:48,get_interrupt_statu:66,get_ipv4_info:[61,62,63],get_jpeg_data:72,get_kei:43,get_kelvin:77,get_mechanical_degre:[19,22],get_mechanical_radian:[19,22],get_mjpeg_head:72,get_mount_point:24,get_mv:[2,3,6,77],get_num_q_t:72,get_num_touch_point:[39,40,45],get_offset:[16,72],get_output:46,get_output_cent:57,get_output_max:57,get_output_min:57,get_output_rang:57,get_packet:72,get_partition_label:24,get_payload:72,get_pin:[46,48],get_posit:33,get_power_supply_limit:7,get_q:72,get_q_tabl:72,get_quantization_t:72,get_radian:[18,19,22],get_rat:3,get_remote_info:62,get_resist:77,get_revolut:18,get_root_path:24,get_rpm:[19,22],get_rpt_head:72,get_rtp_header_s:72,get_scan_data:72,get_session_id:72,get_shaft_angl:8,get_shaft_veloc:8,get_siz:65,get_stat:13,get_terminal_s:11,get_tim:70,get_total_spac:24,get_touch_point:[39,40,45],get_touchpad_input_devic:44,get_type_specif:72,get_used_spac:24,get_user_input:11,get_user_select:74,get_valu:[13,49],get_values_fn:49,get_vers:72,get_voltag:77,get_voltage_limit:7,get_width:72,getactivechild:74,getactiveleaf:74,getiniti:74,getinputhistori:11,getlin:11,getparentst:74,getsocknam:[61,62,63],getter:[58,72],gettimerperiod:74,gettin:49,gimbal:33,github:[11,14,16,33,53,63,66,69,72,74,75],give:[61,74,76],given:[2,6,23,26,68,72,74],glitch:18,global:[3,46],go:[23,24,74],goe:[2,6],gone:76,goodby:11,googl:66,got:[2,23,72,81],gotten:[11,81],gpio:[2,7,10,13,15,18,46,48,50,69],gpio_a:13,gpio_a_h:[7,8],gpio_a_l:[7,8],gpio_b:13,gpio_b_h:[7,8],gpio_b_l:[7,8],gpio_c_h:[7,8],gpio_c_l:[7,8],gpio_config:2,gpio_config_t:2,gpio_down:13,gpio_en:[7,8],gpio_evt_queu:2,gpio_fault:[7,8],gpio_i:13,gpio_install_isr_servic:2,gpio_intr_negedg:2,gpio_isr_handl:2,gpio_isr_handler_add:2,gpio_joystick_select:13,gpio_left:13,gpio_mode_input:2,gpio_mode_output:43,gpio_num:[10,51,69],gpio_num_10:43,gpio_num_12:70,gpio_num_14:70,gpio_num_18:[16,39,40,43,45],gpio_num_19:[16,36,68],gpio_num_22:[16,36,68],gpio_num_23:16,gpio_num_2:10,gpio_num_37:10,gpio_num_45:16,gpio_num_48:16,gpio_num_4:16,gpio_num_5:16,gpio_num_6:16,gpio_num_7:16,gpio_num_8:[39,40,43,45],gpio_num_nc:36,gpio_num_t:[15,16,36],gpio_pullup:13,gpio_pullup_dis:[2,6,36],gpio_pullup_en:[1,2,13,19,22,34,39,45,46,48,66,70],gpio_pullup_t:36,gpio_right:13,gpio_select:13,gpio_set_direct:43,gpio_set_level:43,gpio_start:13,gpio_up:13,gpio_x:13,gpo:66,grab:49,gradient:12,grai:52,graphic:12,gravit:75,grb:51,greater:52,green:[12,51,52,69,75],greengrass:75,grei:75,ground:13,group:[24,61,62,63,65],group_publ:65,grow:[],gt911:[37,41],guarante:51,guard:74,gui:[15,16,59],guid:[11,80,81],h:[11,12,16,52,72],ha:[2,6,8,11,13,18,19,22,23,24,31,34,40,43,46,48,50,51,59,62,63,65,66,69,72,74,75,76,78,81],hack:11,half:[19,22,25],handl:[10,11,31,46,48,51,62,63,69,74,76],handle_all_ev:74,handle_res:11,handleev:74,handler:[2,10,63],handov:65,handover_vers:65,happen:[11,23],haptic:37,haptic_config:33,haptic_motor:33,hapticconfig:33,hardawr:50,hardwar:[8,18,28,46,50,51,72],harmless:78,hart:77,has_ev:74,has_q_tabl:72,has_stop:74,has_valu:[3,5,13,49,50,77],hash:65,have:[2,6,8,11,14,15,23,25,33,34,38,46,49,50,51,52,59,62,67,68,69,72,74,75,76,77,78,80,81],hc:65,heart:8,height:[11,15,16,72],hello:[11,66],hello_everysess:11,help:65,helper:61,henri:8,here:[11,14,19,23,34,46,48,66,67,74,75,78],hertz:36,hid:65,hid_dev_mod:66,hide_bord:75,hide_border_left:75,hide_border_right:75,hide_border_top:75,high:[2,3,6,7,10,15,18,33,43,48,59,69],high_level:10,high_limit:18,high_resolution_clock:[1,2,6,8,10,19,22,34,46,48,50,51,52,59,67,69,76,77],high_threshold_mv:2,high_water_mark:59,higher:[25,28],highlight:75,histori:[11,25,26,28,29,74],history_s:11,hmi:16,hold:[11,15,65,66],home:[38,40,44,45],hop:[61,62,63],horizont:75,host:[2,6,16,46,65,80],hot:77,hour:70,how:[8,14,15,18,67,73,74,75,77],howev:25,hpp:[0,1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,20,22,23,24,25,26,28,29,30,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,54,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],hr:65,hs:65,hsfm:74,hsv:[12,51,68,69,70],html:[7,11,15,16,25,29,65,69,80,81],http:[2,6,7,8,11,14,15,16,19,24,25,26,29,33,34,46,52,53,61,62,63,65,66,69,72,74,75,77,80,81],http_www:65,https_www:65,hue:[12,51,69],human:[14,24,75],human_read:24,hz:[3,33],i2c:[4,19,21,22,34,37,39,40,43,45,46,47,48,51,66,68,70],i2c_cfg:[1,2,6,13,19,22,34,46,48,66],i2c_config_t:[1,2,6,13,19,22,34,46,48,66],i2c_driver_instal:[1,2,6,13,19,22,34,46,48,66],i2c_freq_hz:[1,2,6,13,19,22,34,46,48,66],i2c_master_read_from_devic:[1,2,6,13],i2c_master_write_read_devic:[19,22,34,46,48,66],i2c_master_write_to_devic:[1,2,6,13,19,22,34,46,48,66],i2c_mode_mast:[1,2,6,13,19,22,34,46,48,66],i2c_num:[1,2,6,13,19,22,34,46,48,66],i2c_num_0:[36,39,40,43,45,68,70],i2c_param_config:[1,2,6,13,19,22,34,46,48,66],i2c_port_t:36,i2c_read:34,i2c_scl_io:[1,2,6,13,19,22,34,46,48,66],i2c_sda_io:[1,2,6,13,19,22,34,46,48,66],i2c_timeout_m:[1,2,6,13,19,22,34,46,48,66],i2c_writ:34,i:[2,6,8,14,18,37,47,51,59,66,67,73,74,75,76,77],i_gpio:18,id:[2,6,10,31,34,65,72,76,78],ident:11,identifi:[34,65,72],idf:[3,5,7,10,11,36,37,50,52,63,69,80,81],ifs:24,ifstream:24,ignor:[11,18,23],iir:28,il:65,ili9331:[],imag:72,imap:65,imax:46,imax_25:46,imax_50:46,imax_75:46,immedi:[74,76],imped:[7,75],impl:[26,29],implement:[2,6,7,8,9,11,12,25,26,28,29,31,32,33,53,54,55,58,65,72,74,78],implicit:[19,22],improv:11,impuls:28,inact:65,includ:[0,1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,20,22,23,24,25,26,28,29,30,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,54,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],incom:62,incomplet:65,increas:[10,18,52,67],increment:[2,6,18,38,46],incur:15,independ:[49,58,75],index:[2,6,18,51,58,72,77],indic:[46,48,62,63,65,66,76],individu:[6,49,53],induct:8,infinit:28,info:[1,2,3,5,6,10,13,18,23,33,34,49,51,52,59,61,62,63,67,69,72,77,78],info_rate_limit:52,inform:[12,15,19,22,26,29,46,48,49,51,53,59,61,62,63,65,66,69,74,77,80,81],infrar:69,inherit:11,init:[34,36,49,61,62],init_ipv4:61,init_low_level:66,initail:[3,77],initi:[1,2,3,5,6,7,8,10,13,15,16,18,19,22,28,34,36,38,42,43,44,46,48,49,50,55,57,61,62,63,66,69,74,76,78,80,81],inlin:[1,2,3,5,6,7,8,10,11,13,15,16,18,19,22,23,24,25,26,28,29,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,59,61,62,63,65,66,67,68,69,70,72,74,76,77,78,80,81],inout:2,input:[2,6,8,10,11,13,19,22,25,26,28,29,33,34,37,40,46,48,49,57,70],input_delay_n:16,input_driv:[38,42,44],input_valu:2,inquiri:65,insert:11,insid:2,instal:[1,2,6,10,13,19,22,34,46,48,66],instanc:[23,24,75],instant:50,instanti:59,instead:[11,31,57,73,74],instruct:28,instrument:[2,6,34],int16_t:18,int8_t:73,integ:[7,18,54,61,66],integr:67,integrator_max:[8,67],integrator_min:[8,67],intend:[53,74,76],interact:[11,21,23,24,43,47,72],interest:[13,23],interfac:[7,9,10,15,21,24,31,33,34,36,37,40,43,46,47,48,51,68,69,72],interfer:33,intermedi:65,intern:[2,11,13,16,18,25,26,28,29,34,46,48,61,74],interpol:12,interrupt:[2,10,18,46,48,66,76],interrupt_typ:10,interrupttyp:10,interv:43,intr_typ:2,introduc:57,inttrig:34,invalid:[11,12],invalid_argu:11,invers:50,invert:[13,44,46,48,50,57],invert_color:16,invert_i:44,invert_input:57,invert_output:57,invert_x:44,invoc:67,io:[15,16,24,37,53,65],io_conf:2,io_num:2,ip2str:81,ip:[31,61,62,63,72,81],ip_add_membership:[61,62,63],ip_address:[31,62,63,72],ip_callback:81,ip_event_got_ip_t:81,ip_evt:81,ip_info:81,ip_multicast_loop:[61,62,63],ip_multicast_ttl:[61,62,63],ipv4:61,ipv4_ptr:61,ipv6:61,ipv6_ptr:61,ir:69,irdaobex:65,is_a_press:13,is_act:72,is_al:31,is_b_press:13,is_charg:23,is_clos:72,is_complet:72,is_connect:[31,62,72,81],is_dir:24,is_directori:24,is_down_press:13,is_en:[7,8],is_fault:7,is_floating_point:58,is_left_press:13,is_multicast_endpoint:63,is_passive_data_connect:31,is_press:[10,13,68],is_right_press:13,is_run:[33,76,78],is_select_press:13,is_start:76,is_start_press:13,is_up_press:13,is_valid:[61,62,63],isr:[2,10],issu:11,istream:11,it_st:66,ital:75,item:[14,24],iter:[16,23,24,62,63,76,78],its:[2,3,6,19,22,23,31,33,46,48,55,59,61,62,63,66,67,74,80],itself:[15,23,38,42,44,72,76],j:75,join:[61,62,63],josh:75,joybonnet:[1,13],joystick:[2,13,37,65],joystick_config:13,joystick_i:13,joystick_select:13,joystick_x:13,jpeg:72,jpeg_data:72,jpeg_fram:72,jpeg_frame_callback_t:72,jpeg_head:72,jpegfram:72,jpeghead:72,jpg:14,js1:49,js2:49,jump:57,june:75,just:[2,13,19,22,23,65,69,72,73,74,77],k:[11,77],k_bemf:8,kbit:66,kd:[8,33,67],kd_factor_max:33,kd_factor_min:33,keep:78,keepal:62,kei:[11,43,65,66,72],kelvin:77,key_cb:43,key_cb_fn:43,keyboard:[11,37,41,65],keypad:[37,41,43],keypad_input:42,keypadinput:42,kg:75,ki:[8,67],kind:[20,74],kit:[],know:[15,19,22,23,76],known:[65,74],kohm:48,kp:[8,33,67],kp_factor:33,kv:8,kv_rate:8,l:11,label:[16,24],lack:24,lambda:[1,2,6,13,19,22,34,46,48,52,66,77],landscap:[15,16],landscape_invert:15,larg:72,larger:[3,11,72],last:[13,18,34,40,45,49,51,65,67,68,74],last_button_st:68,last_it_st:66,last_unus:13,latch:69,later:[7,16,18,78],latest:[7,11,44,49,59,67,69,77,80,81],launch:65,lazi:14,lcd:16,lcd_send_lin:16,lcd_spi_post_transfer_callback:16,lcd_spi_pre_transfer_callback:16,lcd_write:16,le:65,le_rol:65,le_sc_confirm:65,le_sc_random:65,lead:[3,12],leaf:74,learn:[34,65],least:[18,51,62,68],leav:[2,6],led:[2,37,46,69],led_callback:50,led_channel:50,led_encod:[51,69],led_encoder_st:69,led_fade_time_m:50,led_reset_cod:69,led_stip:69,led_strip:[51,69],led_task:50,ledc:50,ledc_channel_5:50,ledc_channel_t:50,ledc_high_speed_mod:[],ledc_low_speed_mod:50,ledc_mode_t:50,ledc_timer_10_bit:50,ledc_timer_13_bit:50,ledc_timer_2:50,ledc_timer_bit_t:50,ledc_timer_t:50,ledstrip:51,left:[13,16,18,42,51,68,75],legaci:65,legend:[14,75],len:[40,51],length:[2,6,16,25,28,36,39,40,45,51,58,65,66,68,69],less:[7,49,65,66,76],let:[11,15,23,59],level0:69,level1:69,level:[7,8,9,10,23,33,34,39,43,45,48,51,52,61,62,63,65,68,69,72,74,77,78],leverag:28,lh:[68,70],lib:34,libarari:73,libfmt:52,librari:[11,23,24,33,34,37,65,73,75],licens:75,life:[11,73],lifecycl:15,light:[12,38,42,44,52,73,74,75],like:[23,61],lilygo:[37,41],limit:[7,8,11,18,52,65,67],limit_voltag:[7,8],line:37,line_input:11,linear:[34,35],lineinput:11,link:[14,24],links_awaken:14,list:[2,6,24,34,65],list_directori:24,listconfig:24,listen:[31,62,72],lit:[2,6,34],littl:[23,50],littlef:24,lk:[1,2,3,5,6,8,13,18,19,22,23,34,36,39,40,45,46,48,49,50,51,67,68,69,70,74,76,77],ll:[1,2,6,13,19,22,23,34,39,40,43,45,46,48,51,66,68,70,78],ln:77,load:[13,14,65],local:65,lock:[62,66,76],log:[2,6,8,10,23,33,34,37,38,39,40,42,43,44,45,46,48,50,51,59,66,68,69,70,72,74,76,77,78],log_level:[1,2,3,5,6,7,8,10,13,15,18,19,22,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,62,63,66,67,68,69,70,72,74,76,77,78,80,81],logger1:52,logger1_thread:52,logger2:52,logger2_thread:52,logger:[1,2,3,5,6,7,8,10,13,15,18,19,22,23,24,33,34,36,37,38,39,40,42,43,44,45,46,48,49,50,51,61,62,63,66,67,68,69,70,72,74,76,77,78,80,81],logger_:[15,49],logger_config:61,logger_fn:52,logic:[2,6,13,63,65],long_local_nam:65,longer:11,loop:[8,9,11,19,22,24,33,52,76],loop_foc:8,loop_iter:52,loopback_en:[61,62,63],loos:23,lose:11,lot:[10,75],low:[2,5,6,7,8,9,10,13,18,23,48,61,65,69],low_level:10,low_limit:18,low_threshold_mv:2,lower:[18,46,48,77],lowest:[10,76,78],lowpass:[27,37],lowpass_filt:28,lowpassfilt:28,lra:[34,35],lsb:[2,6,46,48],lv_area_t:[15,16],lv_color_t:[15,16],lv_disp_drv_t:[15,16],lv_disp_flush_readi:15,lv_disp_t:[],lv_indev_t:[38,42,44],lv_tick_inc:15,lvgl:[15,16,38,42,44],lvgl_esp32_driv:16,lvgl_tft:16,m:[1,2,3,5,6,8,13,18,19,22,23,33,34,36,39,40,45,46,48,49,50,51,52,62,66,67,68,69,70,74,75,76,77],m_pi:[19,22,59],ma:77,mac:[65,66,81],mac_addr:65,mac_address:65,machin:37,macro:52,made:66,magenta:75,magic_enum_no_check_support:74,magnet:[21,33,37,75],magnetic_det:33,magnitud:[49,58,67],magnitude_squar:58,mai:[2,3,6,10,33,51,65,66,74],mailbox:66,mailto:65,main:[8,15,69],mainli:15,maintain:[15,19,22,66],make:[1,2,6,8,13,19,22,23,24,34,36,39,40,43,45,46,48,61,65,66,68,70,72,74,77],make_alternative_carri:65,make_android_launch:[65,66],make_ev:74,make_handover_request:65,make_handover_select:[65,66],make_le_oob_pair:[65,66],make_multicast:[61,62,63],make_oob_pair:65,make_shar:[8,16],make_text:[65,66],make_uniqu:[1,2,6,11,13,34,50,59,62,63,69,76],make_uri:[65,66],make_wifi_config:[65,66],makeact:74,maker:75,malloc_cap_8bit:15,malloc_cap_dma:15,manag:[5,12,13,14,15,24,37,46,48,50,62,63,65,66],mani:[8,10,18,23,62,63,81],manipul:10,manual:[2,6,11,33,72,74],manual_chid:[2,6],map:[2,6,13,49,57,72],mapped_mv:2,mapper:[37,49,56],mario:14,mark:[59,72],markdownexport:75,marker:72,mask:[46,48],maskaravivek:65,mass:[34,35],master:[1,2,6,11,13,16,19,22,34,46,48,63,66,69],match:[24,31,68,70],math:[37,53,55,57,58],matrix:42,max:[2,7,18,33,34,46,55,57,62,63,67,80],max_connect:62,max_data_s:72,max_glitch_n:18,max_led_curr:46,max_num_byt:[62,63],max_number_of_st:80,max_pending_connect:62,max_receive_s:62,max_transfer_sz:16,maximum:[7,13,19,22,46,49,57,62,63,67,72],maxledcurr:46,maybe_duti:50,maybe_mv:[3,5,77],maybe_r:3,maybe_x_mv:[13,49],maybe_y_mv:[13,49],mb:[24,65],mb_ctrl:66,mcp23x17:[37,47],mcp23x17_read:48,mcp23x17_write:48,mcpwm:[7,33],me:65,mean:[7,10,12,19,22,25,49,57,59,69,73,76,78],measur:[3,5,8,18,19,22,49,67,77],mechan:[3,8,19,22,23,31],media:65,mega_man:14,megaman1:14,megaman:14,member:[1,2,3,5,6,7,8,10,12,13,15,18,19,22,24,26,28,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,59,61,62,63,65,66,67,68,69,70,72,76,77,78,80,81],memori:[11,15,25,28,50,66,69,75,76],memset:[1,2,6,13,16,19,22,34,46,48,66],mention:11,menu:11,menuconfig:24,mere:7,messag:[1,2,6,10,13,23,24,34,45,46,48,65,66,68,70,72,73,74],message_begin:65,message_end:65,method:[8,10,18,24,53,55,67,72,73],metroid1:14,metroid:14,mhz:[],micro:16,micros_per_sec:69,middl:65,might:78,millisecond:[36,43,50],millivolt:77,mime_media:65,min:[2,33,57],minimum:[13,49,57,67],minu:72,minut:[19,22,70],mireq:16,mirror:48,mirror_i:16,mirror_x:16,miso:[],miso_io_num:16,mit:75,mix:12,mjepg:72,mjpeg:72,mkdir:24,mode:[1,2,3,6,10,13,16,19,22,33,34,46,48,50,65,66],model:[12,74],moder:5,modern:75,modif:8,modifi:[16,46,72],modulo:[19,22],monitor:37,month:70,more:[2,3,6,11,12,15,26,27,29,34,49,50,51,52,55,61,62,63,65,69,74,77],mosi:16,mosi_io_num:16,most:[3,8,13,19,22,49,67],motion:[8,33],motion_control_typ:8,motioncontroltyp:8,motoion:8,motor:[7,9,19,22,33,35,37],motor_task:8,motor_task_fn:8,motor_typ:34,motorconcept:33,motortyp:34,mount:24,mount_point:24,mous:65,move:[8,11,51,59,69,76],move_down:39,move_left:39,move_right:39,move_up:39,movement:11,movi:75,ms:15,msb:[2,6,46,48],msb_first:69,msg:74,mt6701:[8,21,37],mt6701_read:[8,22],mt6701_write:[8,22],much:[25,75],multi_byte_charact:75,multi_rev_no_det:33,multicast:[61,62],multicast_address:[61,62,63],multicast_group:[61,62,63],multipl:[3,5,8,13,33,34,35,52,67,72],multipli:[33,58,67],must:[2,5,6,8,11,18,23,24,43,59,61,62,63,65,66,73,74,76,80,81],mutabl:[58,76],mutat:76,mute:2,mutex:[1,2,3,5,6,8,13,18,19,22,23,34,36,39,40,45,46,48,49,50,51,62,66,67,68,69,70,74,76,77],mutual:45,mux:[2,6],mv:[1,2,3,5,6,49,77],mystruct:73,n:[2,3,5,6,11,13,14,18,19,22,23,24,25,29,30,36,39,40,43,45,46,48,49,50,59,62,63,66,67,68,69,70,72,73,74,75,76,77,78,81],name:[1,2,3,5,6,8,10,13,14,18,19,22,23,34,36,39,40,45,46,48,49,50,51,59,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78],namespac:[1,2,6,13,24,34,75],nanosecond:18,navig:11,nby:75,ncharact:75,ncustom:75,ndef:[37,64,66],ndeflib:65,ndefmessag:65,ne:[14,68],nearest:[33,54],necessari:[8,76],need:[3,5,10,11,19,22,23,24,25,33,43,46,59,65,67,69,74,76],needs_zero_search:[19,22],neg:[51,58,67,77],negat:[13,58],neo_bff_io:51,neo_bff_num_l:51,neopixel_writ:51,nest:75,network:[37,62,63,65,80],new_address:68,new_data:[40,45],new_duti:50,new_object:73,new_siz:11,new_target:8,newli:76,newlin:59,newtonian:75,next:[11,33,34,69],nf:65,nfault:8,nfc:[37,65,66],nfcforum:65,nice:75,nicer:52,nm:8,no_timeout:76,nocolor:11,node:[61,62,63,74],nois:57,nomin:77,nominal_resistance_ohm:77,non:[3,33,57,66],nonallocatingconfig:15,none:[2,6,15,31,39,52,65,68,70,74],normal:[15,23,25,58,74],normalizd:[26,28],normalized_cutoff_frequ:[19,22,26,28],note:[1,2,3,5,6,8,10,11,13,18,19,22,23,24,31,33,34,36,39,40,45,46,48,49,51,52,62,63,67,68,69,70,73,74,75,76,77],noth:[7,59,78],notifi:[2,72,76],now:[1,2,6,8,10,11,14,19,22,23,33,34,39,40,43,45,46,48,50,51,52,59,62,63,66,67,68,69,70,76,77],ntc:[6,77],ntc_channel:6,ntc_mv:6,ntc_smd_standard_series_0402:77,ntcg103jf103ft1:77,nthe:81,nullopt:[50,63],nullptr:[8,11,19,22,24,58,62,63,66,74,81],num:72,num_connect_retri:81,num_l:51,num_periods_to_run:50,num_pole_pair:8,num_seconds_to_run:[50,52,67,76],num_steps_per_iter:76,num_task:[59,76],num_touch:44,num_touch_point:[39,40,45],number:[1,2,3,6,8,10,11,15,16,18,19,22,24,25,28,33,34,39,40,44,45,46,48,50,51,54,61,62,63,65,66,69,70,72,77,80,81],number_of_link:24,nvs_flash_init:[80,81],o:[2,6,37,47],object:[8,10,11,12,14,23,51,52,55,59,65,68,69,72,73,74,76,77,78],occur:[2,6,23,40,43,45,46,48,66,72,74],octob:75,oddli:[],off:[2,7,11,18,33,46,52,65,72,77],offset:[16,66,72],offset_i:16,offset_x:16,ofs:24,ofstream:24,ohm:[8,77],ok:[11,72],oldest:11,on_connect:81,on_disconnect:81,on_got_ip:81,on_jpeg_fram:72,on_off_strong_det:33,on_receive_callback:63,on_response_callback:[62,63],onc:[6,13,18,19,22,23,72,78],once_flag:23,one:[2,10,11,19,22,23,31,50,51,62,63,66,69,74,75,78],oneshot:[4,37],oneshot_adc:5,oneshotadc:[5,13,49],onli:[2,6,8,11,13,14,18,19,22,23,25,49,52,58,63,65,66,69,72,73,74,75,78],oob:[65,66],open:[2,6,8,9,11,24,33,62,65,80,81],open_drain:[2,6,46],oper:[2,6,12,24,26,28,29,53,55,58,67,68,70,77],oppos:12,opposit:50,optim:[8,25,54],option:[2,3,5,6,7,8,11,13,15,16,19,22,38,44,49,50,51,52,57,61,62,63,65,72,73,76,78],order:[2,6,25,26,27,30,37,51,52,62],oreilli:65,org:[25,26,29,61,62,63,65,77],orient:[8,15],origin:24,oscil:[2,57],osr_128:[2,6],osr_16:[2,6],osr_2:[2,6],osr_32:[2,6],osr_4:[2,6],osr_64:[2,6],osr_8:[2,6],ostream:11,ostringstream:14,other:[2,6,8,11,12,15,58,61,62,63,66,67,73,74,76,80],otherwis:[2,6,7,8,10,13,19,22,23,31,33,34,40,43,46,48,49,50,62,63,65,66,69,70,72,74,76,78,81],our:[50,61,62,63,76],out:[11,14,24,59,61,62,63,65,69,73,74,75,77],output:[2,6,8,9,11,18,23,24,25,26,28,29,31,44,46,48,50,52,55,57,59,66,67,68,70],output_cent:57,output_drive_mode_p0:46,output_invert:50,output_max:[8,57,67],output_min:[8,57,67],output_mod:[2,6],output_rang:57,outputdrivemodep0:46,outputmod:[2,6],outsid:[2,11,12],over:[2,7,21,24,47,50,60,62,63,72,76],overflow:[18,25],overhead:[15,23],overload:24,oversampl:[2,6],oversampling_ratio:[2,6],oversamplingratio:[2,6],overstai:52,overth:[2,6],overwrit:[46,72,78],own:[3,15,19,22,31,46,48,61,62,63,80],owner:24,p0:46,p0_0:46,p0_1:46,p0_2:46,p0_3:46,p0_5:46,p1:46,p1_0:46,p1_1:46,p1_5:46,p1_6:46,p1_7:46,p1_8:46,p:[2,6,11,14,67,75],pa_0:48,pack:13,packag:65,packet:[61,62,63,65,72],packet_:72,pad:13,padding_bottom:75,padding_left:75,padding_right:75,padding_top:75,page:[24,65,77],pair:[8,65,66],panel:44,param:[1,2,6,8,15,19,22,23,34,39,40,43,44,45,46,48,49,51,61,62,63,66,68,69,70,76,81],paramet:[1,2,3,5,6,7,8,10,11,12,13,15,16,19,20,22,23,24,25,26,28,29,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,61,62,63,65,66,67,68,69,70,72,74,76,77,78,80,81],parent:74,pars:[14,59,72],part:[7,16,33,44,77],parti:73,partit:24,partition_label:24,pass:[2,6,10,16,23,31,52,57],passiv:31,password:[31,65,80,81],pasv:31,pat:65,path:[24,31,72],paul:75,paus:[15,72],payload:[65,66,72],payload_id:66,payload_s:72,pb_7:48,pdf:[2,6,19,34,46,65,66,69,77],pend:62,per:[1,2,3,6,8,19,22],perceiv:12,percent:50,percentag:[7,33,50],perform:[2,3,5,6,12,24,49,76],perhipher:50,period:[10,13,15,19,22,23,36,39,40,45,46,48,59,66,68,70,74,78],peripher:[7,18,33,35,43,50,51,65,69],peripheral_centr:65,peripheral_onli:[65,66],permeabl:75,permiss:24,permitt:75,person:65,phase:[7,8],phase_induct:8,phase_resist:8,phillip:75,phone:[65,66],photo:66,php:65,pick:18,pico:49,pid:[8,33,37],pid_config:67,pin:[1,2,6,7,8,10,13,15,16,34,36,43,46,48,50,69,76,78],pin_bit_mask:2,pin_mask:48,pinout:8,pixel:[15,16,51,72],pixel_buffer_s:[15,16],place:[23,33],placehold:[39,40,43,45,68,70],plai:[34,72,75],plan:77,planck:75,platform:[52,76,78],play_hapt:33,playback:34,pleas:[11,12,14,29,34,74,75],plot:[2,6],pn532:65,point:[12,18,24,25,28,33,37,39,40,44,45,50,53,54,58,62,63,65,66,79,81],pointer:[1,2,6,15,16,19,22,25,28,33,34,44,46,48,49,51,61,62,66,69,72,74,76,81],pokemon:14,pokemon_blu:14,pokemon_r:14,pokemon_yellow:14,polar:48,pole:8,poll:[13,19,22,39,40,43,45,46,48,66,68,70],polling_interv:43,pomax:53,pop:65,popul:63,port0:[46,48],port1:[46,48],port:[8,15,31,36,39,40,43,45,46,48,61,62,63,68,70,72],port_0_direction_mask:[46,48],port_0_interrupt_mask:[46,48],port_1_direction_mask:[46,48],port_1_interrupt_mask:[46,48],port_a:48,port_a_direction_mask:[],port_a_interrupt_mask:[],port_b:48,port_b_direction_mask:[],port_b_interrupt_mask:[],portmax_delai:2,portrait:[15,16],portrait_invert:15,porttick_period_m:[1,2,6,13,19,22,34,46,48,66],pos_typ:24,posit:[8,11,16,18,19,22,33,44,45,49,57],posix:[60,61],possibl:[2,6,7,15,57,65],post:65,post_cb:16,post_transfer_callback:15,poster:65,potenti:[3,25,31,68,70],power:[2,6,7,8,43,51,65],power_ctrl:43,power_st:65,power_supply_voltag:[7,8],pranav:14,pre:[16,67,69],pre_cb:16,precis:69,preconfigur:34,predetermin:[2,6],prefer:65,prefix:[2,6,24],prepend:52,present:[36,45,65,72],preset:34,press:[2,10,11,13,40,43,44,45,68],prevent:[15,67],previou:[11,46,50,78],previous:[7,57],primari:69,primarili:11,primary_data:69,print:[2,3,5,6,11,13,14,18,19,22,23,36,39,40,43,45,46,48,49,50,52,59,62,63,66,67,68,69,70,72,73,74,75,76,77,78,81],printf:[13,19,22,46,48,66],prior:[66,80,81],prioriti:[3,8,10,15,52,59,76,78],privat:11,probe:36,probe_devic:[36,43],process:[50,62,63,76],processor:[2,6,28,76],produc:12,product:[46,58,69,74,77],profil:33,programm:2,programmed_data:66,project:[7,11,31,68,69,70,72,80,81],prompt:11,prompt_fn:11,proper:[12,74],properli:[5,72],proport:67,protocol:[31,51,62,63,69],protocol_examples_common:11,prototyp:[23,44,70],provid:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,21,22,23,24,25,26,27,28,29,30,32,33,35,36,37,38,40,42,43,44,46,47,48,49,50,51,52,53,54,55,57,58,59,60,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,79,81],prt:61,pseudost:74,psram:75,pub:23,publish:[10,23],pull:[2,6,46,48],pull_up_en:2,pulldown:10,pulldown_en:10,pullup:[10,36],pullup_en:10,puls:[2,6,18,69],pulsed_high:[2,6],pulsed_low:[2,6],pulsing_strong_1:34,pulsing_strong_2:34,pure:[18,74],push:[2,6],push_back:75,push_pul:[2,6,46],put:66,pwm:[7,8,9,34,50],pwmanalog:34,py:49,python:59,q0:72,q0_tabl:72,q1:72,q1_tabl:72,q:[8,28,72],q_current_filt:8,q_factor:28,qt:49,qtpy:36,quadhd_io_num:16,quadratur:18,quadwp_io_num:16,qualiti:28,quantiti:75,quantiz:72,queri:36,question:[11,14,50,66,75],queu:69,queue:[2,10,11,69],queue_siz:16,quickli:74,quit:66,quit_test:[13,19,22,48,66,68],quote_charact:14,qwiic:[36,68],qwiicn:[37,70],r0:77,r1:[2,6,77],r25:77,r2:[2,6,77],r:[12,24,46,51,57,65,69,77],r_0:77,r_bright:46,r_down:46,r_led:46,r_scale:77,r_up:46,race:50,rad:8,radian:[8,18,19,22,58],radio:[65,66],radio_mac_addr:66,radiu:49,rainbow:[51,69],ram:15,ranav:[14,75],random:65,random_valu:65,rang:[1,7,12,19,22,24,26,28,33,35,37,49,55,56,77,80],range_mapp:57,rangemapp:[49,57],rate:[1,3,8,19,22,46,48,52],rate_limit:52,ratio:[2,6],ration:53,raw:[1,2,5,6,8,13,19,22,49,53,61,65,66,68],rb:24,re:[11,13,19,22,34,61,62,63,69,74,77],reach:[34,62,66,74],read:[1,2,3,5,6,8,10,11,13,19,22,24,34,36,38,39,40,42,43,44,45,46,48,49,62,66,68,70,77],read_address:68,read_at_regist:[36,39,68,70],read_at_register_fn:39,read_button_accumul:68,read_current_st:68,read_data:[36,40],read_fn:[1,2,6,19,22,34,38,42,43,45,46,48,66,70],read_gestur:39,read_joystick:[13,49],read_kei:43,read_len:40,read_mv:[5,13,49,77],read_mv_fn:77,read_raw:5,read_siz:36,read_valu:14,readabl:[14,24,75],reader:[3,5,49],readi:[43,78],readm:75,readthedoc:65,real:[23,34],realli:[14,73,74,75],realtim:34,reason:[73,76],receic:23,receiv:[2,16,61,62,63,66,72],receive_callback_fn:[61,62,63],receive_config:63,receiveconfig:63,recent:[2,3,8,13,19,22,49,67],recommend:[19,22,23,49,76],record:[65,66],record_data:66,rectangular:49,recurs:[24,74],recursive_directory_iter:24,recvfrom:[61,63],red:[12,14,51,52,69,75],redraw:[11,15],redrawn:11,reepres:72,refer:37,reference_wrapp:33,refresh:15,reg:66,reg_addr:[19,22,34,36,46,48,66],regard:[19,22],regardless:49,region:[2,6],regist:[2,6,10,19,22,23,34,36,38,39,42,44,46,48,66,68,70,72],register_address:[36,70],registr:23,registri:23,reinit:62,reiniti:62,reistor:46,rel:57,relat:[11,50],releas:[10,75],relev:[24,77],reli:74,reliabl:[19,22,62],remain:52,remot:[37,62,63,65],remote_control:65,remote_info:63,remov:[7,11,23,24],remove_publish:23,remove_subscrib:23,renam:24,render:[15,59],repeat:78,repeatedli:[69,76,78],replac:11,report:66,repres:[12,19,22,31,50,58,65,66,67,68,69,72],represent:[12,65,75],request:[2,6,31,61,62,63,65,66,72],requir:[8,66,75],rescal:12,reserv:65,reset:[2,6,16,18,66,67,69],reset_fn:69,reset_pin:16,reset_st:67,reset_tick:69,reset_valu:16,resist:[8,77],resistor:[10,46,77],resistordividerconfig:77,resiz:[11,24,59,76],resolut:[50,69],resolution_hz:[51,69],resolv:[31,68,70],reson:[34,35],resourc:[5,61,62,63,66,69],respect:[4,72,74],respond:[61,62,63],respons:[15,24,28,31,65,67,72],response_callback_fn:[61,62,63],response_s:[62,63],response_timeout:63,restart:[74,78],restartselect:74,restrict:[19,22],result:[2,3,6,11,12,58,72],resum:15,ret:16,ret_stat:69,retri:[72,81],retriev:[3,13,44,49],return_to_center_with_det:33,return_to_center_with_detents_and_multiple_revolut:33,reusabl:[11,37],revers:[62,63],revolut:[18,19,22,33],rf:66,rf_activ:66,rf_get_msg:66,rf_intterupt:66,rf_put_msg:66,rf_user:66,rf_write:66,rfc:[65,72],rfid:[65,66],rgb:[12,51,68,69,70],rh:[12,58,68,70],right:[8,11,13,31,42,51,66,68,75],rise:[10,34,66,69],rising_edg:10,risk:25,rmdir:24,rmt:[37,51],rmt_bytes_encoder_config_t:69,rmt_channel_handle_t:69,rmt_clk_src_default:69,rmt_clock_source_t:69,rmt_encod:69,rmt_encode_state_t:69,rmt_encoder_handle_t:69,rmt_encoder_t:69,rmt_encoding_complet:69,rmt_encoding_mem_ful:69,rmt_encoding_reset:69,rmt_symbol_word_t:69,rmtencod:[51,69],robust:[11,52],robustli:57,role:65,root:[24,31,74],root_list:24,root_menu:11,root_path:24,rotari:33,rotat:[8,15,16,19,22,33,34,35,51,58,69],round:54,routin:49,row:[14,75],row_index:14,row_t:75,rpm:[8,19,22],rpm_to_rad:8,rstp:65,rt_fmt_str:52,rtc:[37,70],rtcp:72,rtcp_packet:72,rtcp_port:72,rtcppacket:72,rtd:65,rtp:[34,72],rtp_jpeg_packet:72,rtp_packet:72,rtp_port:72,rtpjpegpacket:72,rtppacket:72,rtsp:[37,65],rtsp_client:72,rtsp_path:72,rtsp_port:72,rtsp_server:72,rtsp_session:72,rtspclient:72,rtspserver:72,rtspsession:72,rule:75,run:[3,8,11,15,19,22,23,31,33,43,50,52,59,75,78],runtim:52,s2:[3,16],s3:[3,13,45],s:[2,6,8,9,10,11,12,14,19,22,23,31,33,46,48,49,50,51,52,57,59,63,68,69,73,74,75,76,77],s_isdir:24,safe:[50,67],same:[2,5,6,8,23,65,67,78],sampl:[1,2,3,6,8,11,19,22,25,26,28,29,66,67,77],sample_mv:[1,13],sample_r:1,sample_rate_hz:[3,77],sandbox:24,sar:[2,6],sarch:[19,22],satisfi:74,satur:[12,67],scalar:58,scale:[8,55,58,67,77],scaler:55,scan:[2,6,72,81],scan_data:72,scenario:[80,81],schedul:78,scheme:8,scl:[2,6,36],scl_io_num:[1,2,6,13,19,22,34,36,39,40,43,45,46,48,66,68,70],scl_pullup_en:[1,2,6,13,19,22,34,36,39,45,46,48,66,70],sclk:16,sclk_io_num:16,scope:76,scottbez1:33,screen:[11,16],sda:36,sda_io_num:[1,2,6,13,19,22,34,36,39,40,43,45,46,48,66,68,70],sda_pullup_en:[1,2,6,13,19,22,34,36,39,45,46,48,66,70],sdp:72,search:[19,22],second:[1,2,3,8,19,22,26,27,37,46,48,50,52,58,70,72,76,77,78],secondari:15,seconds_per_minut:[19,22],seconds_since_start:59,section:[12,26,27,37],sectionimpl:29,secur:[65,80,81],security_manager_flag:65,security_manager_tk:65,see:[2,6,8,11,12,14,15,16,18,25,26,29,34,49,53,59,61,62,63,65,66,69,74,75,77,80,81],seek_end:24,seek_set:24,seekg:24,seem:[11,24,72],segment:15,sel:2,select:[2,3,13,31,34,51,65,68,74],select_bit_mask:2,select_librari:34,select_press:2,select_valu:2,self:45,send:[10,15,16,31,36,51,62,63,66,69,72],send_bright:51,send_command:16,send_config:[62,63],send_data:16,send_fram:72,send_request:72,send_rtcp_packet:72,send_rtp_packet:72,sendconfig:63,sender:[61,62,63],sender_info:[61,62,63],sendto:61,sens:[8,45],sensor:[8,19,22,45,77],sensor_direct:8,sensorconcept:8,sensordirect:8,sent:[2,6,16,31,51,62,63,69,72],sentenc:75,separ:[13,14,15,46,59],septemb:75,sequenc:[2,6,23,34,59,65,66,74],seri:[29,72,77],serial:[10,21,23,34,37,43,46,47,48,65,66,72],serializa:73,series_second_order_sect:[25,29],serizalizt:14,server:[32,37,60,61],server_address:[62,63,72],server_config:63,server_port:72,server_socket:[62,63],server_task:62,server_task_config:[62,63],server_task_fn:62,server_uri:72,servic:[2,65],session:[11,31,69,72],session_st:69,set:[1,2,6,7,8,10,11,15,16,19,22,23,34,40,43,45,46,48,49,50,51,54,55,57,59,61,62,63,65,66,68,69,70,72,74,77,78,80,81],set_al:51,set_analog_alert:2,set_ap_mac:81,set_bright:15,set_calibr:49,set_config:67,set_dat:70,set_date_tim:70,set_deadzon:49,set_digital_alert:2,set_digital_output_mod:[2,6],set_digital_output_valu:[2,6],set_direct:[46,48],set_drawing_area:16,set_duti:50,set_encod:[51,69],set_fade_with_tim:50,set_handle_res:11,set_histori:11,set_history_s:11,set_id:[65,66],set_input_polar:48,set_interrupt:46,set_interrupt_mirror:48,set_interrupt_on_chang:48,set_interrupt_on_valu:48,set_interrupt_polar:48,set_label:16,set_log_callback:74,set_log_level:23,set_met:16,set_mod:34,set_motion_control_typ:8,set_offset:16,set_payload:72,set_phase_st:7,set_phase_voltag:8,set_pin:[46,48],set_pixel:51,set_pull_up:48,set_pwm:7,set_receive_timeout:[61,62,63],set_record:66,set_session_log_level:72,set_tag:52,set_text:75,set_tim:70,set_verbos:52,set_vers:72,set_voltag:7,set_waveform:34,setactivechild:74,setcolor:11,setdeephistori:74,sethandleres:11,setinputhistori:11,setinputhistorys:11,setnocolor:11,setparentst:74,setpoint:[8,33],setshallowhistori:74,setter:[58,72],setup:[2,72],sever:[21,27,47],sftp:65,sgn:54,shaft:[8,19,22],shallow:74,shallow_history_st:74,shallowhistoryst:74,shamelessli:75,shape:55,share:65,shared_ptr:8,sharp_click:34,sheet:[2,6],shield:13,shift:[51,55,68],shift_bi:51,shift_left:51,shift_right:51,shifter:55,shop:[46,69],short_local_nam:65,shorten:65,shot:78,should:[7,8,11,12,13,15,16,24,25,28,43,48,49,50,51,58,61,62,63,65,67,68,69,72,74,76,78],shouldn:[24,52],show:[11,51,74,76],showcas:23,shown:52,shut:76,side:[7,32],sign:[18,54,57],signal:[2,13,15,25,26,28,29,34,51,67,69],signatur:[43,45,76],signific:68,similar:69,simpl:[0,5,10,23,24,30,31,36,43,52,65,67,73,76,77],simple_callback_fn:76,simpleconfig:76,simplefoc:8,simpler:[50,69],simpli:[2,3,6,11,19],simplifi:72,simultan:[11,65],sin:59,sinc:[2,8,18,19,22,23,24,43,46,68,69,72,76,77],singl:[2,5,6,18,33,38,51,52],single_unit_1:[3,77],single_unit_2:3,singleton:[23,24],sinusoid:8,sip:65,sixteen:1,size:[10,11,15,23,24,34,43,59,62,63,65,66,69,70,72,73,76,77,78],size_t:[1,2,3,6,8,10,11,13,14,15,16,18,19,22,23,24,25,26,28,29,34,36,39,40,43,45,46,48,50,51,52,59,61,62,63,68,69,70,72,73,75,76,78,81],sizeof:[1,2,6,13,16,19,22,34,46,48,66,69,72],sk6085:69,sk6805:69,sk6805_10mhz_bytes_encoder_config:69,sk6805_freq_hz:51,sk6812:51,sleep:[1,2,3,5,6,8,13,18,19,22,23,34,36,39,40,45,46,48,49,50,51,52,59,67,68,69,70,74,76,77,78],sleep_for:[3,10,16,23,43,50,51,52,59,62,63,67,72,74,76,78,81],sleep_until:76,slope:55,slot:34,slow:5,small:[33,55],smart:65,smartknob:33,smb:65,snap:33,snprintf:76,so:[1,2,5,6,8,11,13,14,16,18,19,22,23,24,27,31,33,34,37,45,46,48,51,57,59,66,67,69,72,74,75,76,77,78],so_recvtimeo:[61,62,63],so_reuseaddr:[61,62,63],so_reuseport:[61,62,63],sockaddr:61,sockaddr_in6:61,sockaddr_in:61,sockaddr_storag:[61,62,63],socket:[31,37,60,72],socket_fd:[61,62,63],soft_bump:34,soft_fuzz:34,softwar:[2,6,15,23],software_rotation_en:[15,16],some:[1,2,6,8,11,13,19,21,22,23,24,27,33,34,46,48,52,54,59,61,65,66,69,74,76],someth:[15,76],sometim:11,somewhat:33,sos_filt:29,sosfilt:[26,29],sourc:[63,69],source_address:61,sp:65,sp_hash_c192:65,sp_hash_c256:65,sp_hash_r256:65,sp_random_r192:65,space:[8,12,24,33,51,69,75],space_vector_pwm:8,sparignli:57,sparkfun:[13,68],spawn:[19,22,31,72,74,76],spawn_endevent_ev:74,spawn_event1_ev:74,spawn_event2_ev:74,spawn_event3_ev:74,spawn_event4_ev:74,specfici:1,special:[20,34,46,69],specif:[12,33,35,38,42,44,72,74,76],specifi:[2,6,19,22,24,33,52,63,72,78],speed:[8,19,22,36,50,62,75],speed_mod:50,spi2_host:16,spi:[16,19,22,48],spi_bus_add_devic:16,spi_bus_config_t:16,spi_bus_initi:16,spi_device_interface_config_t:16,spi_dma_ch_auto:16,spi_dmaconfig:[],spi_num:16,spi_queue_s:16,spic:16,spics_io_num:16,spike:55,spimast:[],spinum:[],spitransfers:[],sporad:5,spot:8,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:58,sr:65,ssid:[65,66,80,81],st25dv04k:66,st25dv:[37,64],st25dv_read:66,st25dv_write:66,st7789_defin:16,st7789v_8h_sourc:16,st:[24,66],st_mode:24,st_size:24,sta:[37,79],stabl:65,stack:[10,23,59,76,78],stack_size_byt:[1,2,6,8,13,19,22,23,34,46,48,51,59,62,63,66,69,76,78],stackoverflow:[24,66,75],stand:8,standalon:[21,47],standard:[24,52,57,72],star:34,start:[1,2,3,5,6,8,10,11,13,15,16,18,19,22,23,31,33,34,36,39,40,43,45,46,48,49,50,51,52,58,59,60,62,63,66,67,68,69,70,72,74,76,77],start_fast_transfer_mod:66,start_fram:51,start_receiv:63,startup:[19,22],stat:[24,59],state:[7,10,13,19,22,23,25,26,28,29,34,37,39,40,44,45,46,48,59,65,66,67,68,69,70],state_a:7,state_b:7,state_bas:74,state_c:7,state_machin:74,state_of_charg:23,statebas:74,static_cast:[2,52,69],station:[37,79,80],statist:2,statistics_en:2,statu:[2,66],std:[1,2,3,5,6,8,10,11,13,14,15,16,18,19,22,23,29,31,33,34,36,39,40,43,44,45,46,48,49,50,51,52,53,57,58,59,60,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],stdby:8,stdin:74,stdin_out:11,stdout:74,steinhart:77,step:76,still:49,stop:[1,2,3,5,6,8,13,15,18,19,22,23,31,33,34,36,39,40,43,45,46,48,49,50,51,59,62,63,66,67,68,69,70,72,74,77,78,81],stop_fast_transfer_mod:66,storag:[11,61],store:[11,13,16,24,30,55,65,66,72,77],stori:75,str:14,strcutur:16,stream:[11,14,72],streamer:72,strength:33,strictli:73,string:[10,11,14,23,24,52,59,61,62,63,65,72,73,76,80,81],string_view:[10,16,24,31,52,62,63,65,66,72,74,76,78],strip:[37,69],strong:33,strong_buzz:34,strong_click:34,strongli:73,struct:[1,2,3,5,6,7,8,10,12,13,15,18,19,22,23,24,26,28,30,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,59,61,62,63,65,66,67,68,69,70,72,73,76,77,78,80,81],structur:[1,2,6,8,13,15,16,23,34,38,42,43,44,46,48,49,50,53,55,61,62,63,65,67,70,74,80,81],sub:[11,23],sub_menu:11,sub_sub_menu:11,subclass:[29,61,72,74],subdirectori:24,submenu:11,submodul:11,subscib:23,subscrib:[10,23],subscript:23,subsequ:[2,65],subset:13,substat:74,subsub:11,subsubmenu:11,subsystem:[3,5,15,50],subtract:58,subystem:81,succe:[39,68],success:[1,2,6,19,22,34,36,43,46,48,66,70,72],successfulli:[18,23,61,62,63,69,72,73],suffix:52,suggest:69,suit:12,sulli:75,super_mario_1:14,super_mario_3:14,super_mario_bros_1:14,super_mario_bros_3:14,suppli:[7,77],supply_mv:77,support:[2,6,8,11,12,13,18,20,24,34,39,45,46,51,60,65,66,72],sure:[8,72],swap:44,swap_xi:44,symlink:[2,6,34],symmetr:55,syst_address:66,system:[11,14,23,37,59,66,73,74,75,76,77],sytl:73,t5t:66,t:[1,2,3,5,6,8,13,14,16,18,19,22,23,24,34,36,37,39,40,41,45,46,48,49,50,51,52,53,55,57,58,59,62,63,65,66,67,68,69,70,74,76,77,78],t_0:77,t_keyboard:43,ta:13,tabl:[2,6,24,59,65,72,75,77],tabul:37,tag:[52,65,66],take:[5,24,75],taken:24,talk:[46,51],target:[8,81],task1:23,task2:23,task:[1,2,3,5,6,8,10,13,15,18,19,22,23,31,33,34,36,37,39,40,43,45,46,48,49,50,51,62,63,66,67,68,69,70,72,74,77,78],task_1_fn:23,task_2_fn:23,task_callback:59,task_config:63,task_fn:[3,5,13,18,19,22,34,36,39,40,45,46,48,49,51,59,66,67,68,69,70,74,76,77],task_id:59,task_iter:76,task_monitor:59,task_nam:[59,76],task_prior:3,task_stack_size_byt:[10,59],taskmonitor:59,tb:13,tcp:[37,60,72],tcp_socket:62,tcpclientsess:62,tcpobex:65,tcpserver:62,tcpsocket:[61,62,72],tcptransmitconfig:62,tdata:73,tdk:77,tdown:13,tear:[61,62,63,76],teardown:72,tel:65,tell:[51,69],tellg:24,telnet:65,temp:77,temperatur:77,temperature_celsiu:23,templat:[8,18,20,24,26,29,31,33,52,53,57,58,76],temporari:65,termin:[11,74,75,76],test2:24,test:[3,8],test_dir:24,test_fil:24,test_start:76,texa:[2,6,34],text:65,tflite:16,tft_driver:16,tft_espi:16,tftp:65,th:[15,30],than:[7,11,15,49,52,66,72],thank:11,thei:[11,13,33,72,74,76],them:[2,6,11,12,13,23,55,69,72,74,76],therefor:[3,5,11,12,19,22,34,57,76],thermistor:37,thermistor_ntcg_en:77,thi:[1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,22,23,24,25,31,33,34,36,37,39,40,43,45,46,48,49,50,51,52,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],thin:55,thing:59,think:11,third:73,this_thread:[3,10,16,23,43,50,51,52,59,62,63,67,72,74,76,78,81],those:[23,46,52,59,74],though:[23,76],thread:[23,31,33,50,59,62,63,67,72,76],threshold:[2,6],through:[2,6,8,33,34,51,57,69,74],throughput:3,ti:[2,6,34],tick:74,tickselect:74,time:[2,5,6,7,11,13,19,22,23,24,34,46,48,50,51,52,59,63,66,67,68,69,70,74,76,77,78,81],time_point:24,time_t:[24,31],time_to_l:[61,62,63],timeout:[36,61,62,63,76],timeout_m:36,timer:[37,50],timer_fn:78,tinys3:[8,69],tk:65,tkeyboard:43,tkip:65,tla2528:[4,37],tla:6,tla_read:6,tla_read_task_fn:6,tla_task:6,tla_writ:6,tleft:13,tloz_links_awaken:14,tloz_links_awakening_dx:14,tm:59,tmc6300:8,tname:73,tnf:65,to_str:75,to_time_t:[24,31],toggl:43,toi:75,toler:77,tone:51,too:[11,72,75],top:74,topic:[10,23],torqu:8,torque_control:8,torquecontroltyp:8,total:[18,24],total_spac:24,touch:[37,41,44],touchpad:[37,41,45,65],touchpad_input:44,touchpad_read:44,touchpad_read_fn:44,touchpadinput:44,tp:[24,31],tpd_commercial_ntc:77,trace:59,track:67,transact:69,transaction_queue_depth:69,transceiv:37,transfer:[16,27,32,37,66],transfer_funct:30,transferfunct:[29,30],transform:[8,23],transit:74,transition_click_1:34,transition_hum_1:34,transmiss:[62,69],transmit:[23,51,61,62,63,65],transmit_config:62,transmitconfig:[],transmitt:69,transport:72,tree:[63,69,74],tri:11,trigger:[2,5,6,33,34,48,66],tright:13,trim_polici:14,trim_whitespac:14,triple_click:34,truncat:11,ts:34,tselect:13,tstart:13,tt1535109:75,tt1979376:75,tt21100:[37,41],tt3263904:75,ttgo:[],ttl:[61,62,63],tup:13,tupl:77,turn:[2,15,52,65],tvalu:73,two:[1,12,13,15,46,48,52,59,69],twothird:1,tx:65,tx_config:[],tx_power_level:65,type:[1,2,4,6,8,10,11,13,15,18,19,21,22,23,24,27,33,34,37,39,40,43,44,45,46,47,48,49,51,52,58,61,62,63,65,66,68,69,70,72,73,76,77,78,81],type_specif:72,typedef:[1,2,6,8,10,11,15,19,22,23,34,39,40,43,44,45,46,48,49,51,61,62,63,66,68,69,70,76,77,78,81],typenam:[24,31,52,53,57,58],typic:42,u:[58,65],ua:7,uart:11,uart_serial_plott:[2,6],ub:7,uc:7,ud:8,udp:[37,60,72],udp_multicast:63,udp_socket:63,udpserv:63,udpsocket:[61,63],uic:[65,66],uint16_t:[1,15,16,31,39,40,44,45,46,48,65,66,69,70],uint32_t:[2,13,15,16,36,50,65,72,73],uint64_t:[65,66],uint8_t:[1,2,6,10,13,15,16,19,22,23,34,36,39,40,43,44,45,46,48,51,52,61,62,63,65,66,68,69,70,72,73,80,81],uint:69,uk:65,unabl:[31,68,70],unbound:33,unbounded_no_det:33,uncalibr:[13,49],uncent:57,unchang:65,under:[18,24],underflow:18,underlin:75,understand:65,unicast:63,uniqu:[62,72,76],unique_lock:[1,2,3,5,6,8,13,18,19,22,23,34,36,39,40,45,46,48,49,50,51,62,66,67,68,69,70,74,76,77],unique_ptr:[59,62,72,76],unit:[0,3,5,8,13,18,24,25,49,58,77],univers:11,universal_const:75,unknown:[8,65,81],unless:23,unlimit:11,unlink:24,unmap:49,unord:[2,6,63],unordered_map:[2,6,72],unregist:[38,42,44],unreli:63,until:[2,6,11,23,24,33,34,50,51,62,63,69,74,76,78],unus:[13,18,33],unweight:53,unwind:74,up:[2,3,11,13,15,18,24,34,39,42,43,45,46,48,55,62,66,67,68,72,74,76,78],upat:15,updat:[7,8,10,13,15,19,22,25,26,28,29,33,40,45,46,48,49,50,52,55,57,58,61,66,67,68,74],update_address:68,update_detent_config:33,update_period:[8,15,19,22],upper:[16,77],uq:8,uri:[65,72],urn:65,urn_epc:65,urn_epc_id:65,urn_epc_pat:65,urn_epc_raw:65,urn_epc_tag:65,urn_nfc:65,us:[1,2,3,5,6,7,8,9,10,11,12,13,15,16,18,19,20,22,23,24,25,26,31,32,33,34,35,39,40,42,43,45,46,48,49,50,51,52,53,55,57,59,60,61,62,63,65,66,68,69,70,72,73,74,75,76,77,78],usag:[11,14,75],used_spac:24,user:[2,3,5,6,9,10,11,16,18,19,22,31,33,34,46,48,68,69,70,72,76],user_data:[],usernam:31,ust:23,util:[24,49,52,54,58,59,61,65,66],uuid:65,uuids_128_bit_complet:65,uuids_128_bit_parti:65,uuids_16_bit_complet:65,uuids_16_bit_parti:65,uuids_32_bit_complet:65,uuids_32_bit_parti:65,v:[8,12,57,58],v_in:77,vacuum:75,val_mask:48,valid:[31,34,51,61,62,63,72],valu:[1,2,3,5,6,10,12,13,14,15,18,19,22,24,28,33,34,39,40,46,48,49,50,51,52,53,54,55,57,58,65,66,67,68,69,70,72,73,75,76,77],vari:33,variabl:[16,49,52,76],varieti:[2,6],variou:51,ve:[11,24,76],vector2d:[37,53,56],vector2f:[49,68,70],vector:[2,3,5,6,8,10,13,14,23,24,28,49,50,51,58,59,61,62,63,65,66,72,73,76,77],veloc:[8,19,22],velocity_filt:[8,19,22],velocity_filter_fn:[19,22],velocity_limit:8,velocity_openloop:8,velocity_pid_config:8,veloicti:8,veolciti:[19,22],verbos:[1,2,3,5,6,7,8,10,13,15,18,19,22,23,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,62,63,66,67,68,69,70,72,74,76,77,78,80,81],veri:11,version:[6,11,58,65,72],via:[6,24,34,46,48],vibe:34,vibrat:[33,34],video:[15,72],view:[62,63,65],vio:8,virtual:[13,74],visual:59,volt:[2,6,7],voltag:[1,2,3,5,6,7,8,9,23,77],voltage_limit:7,vram0:15,vram1:15,vram:15,vram_size_byt:15,vram_size_px:15,vtaskgetinfo:59,w:[24,34,52,57],wa:[1,2,3,5,6,7,10,11,13,16,18,19,22,23,31,34,39,43,45,48,49,61,62,63,66,68,69,70,72,74,76],wai:[1,2,3,5,6,8,11,13,14,18,19,22,24,33,34,36,39,40,45,46,48,49,51,65,67,68,69,70,73,74,75,76,77],wait:[23,33,43,62,63,76],wait_for:[1,3,5,13,18,19,22,23,34,36,39,40,45,46,48,49,50,51,62,66,67,68,69,70,74,76],wait_for_respons:[62,63],wait_tim:50,wait_until:[2,6,8,76,77],want:[1,2,3,5,6,8,11,13,15,18,19,22,23,33,34,46,48,49,50,51,59,62,63,66,67,69,74,76,77,78],warn:[1,2,3,5,6,7,8,10,13,15,18,19,22,23,24,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,62,63,66,67,68,69,70,72,76,77,78,80,81],warn_rate_limit:52,watch:65,water:59,wave:55,waveform:34,we:[1,2,6,7,8,11,13,19,22,23,24,33,34,39,40,43,45,46,48,50,51,61,62,63,66,68,69,70,74,76,77,78],weak:33,webgm:74,week:70,weekdai:70,weight:53,weightedconfig:53,welcom:52,well:[2,13,21,23,27,29,34,55,59,62,65,66,72,74,76],well_known:65,wep:65,were:[2,6,7,11,45,49,61,62,63,67,74,76],what:[5,6,7,23,69,74],whatev:[46,48],whe:81,when:[1,2,3,5,6,8,11,13,16,18,19,20,22,23,33,34,36,39,40,43,45,46,48,49,51,57,61,62,63,66,67,68,69,70,72,73,74,76,77,78,81],whenev:74,where:[9,18,33,59,63,74,77],whether:[3,10,11,13,15,19,22,24,43,50,51,57,61,62,63,69,72,76,81],which:[1,2,3,5,6,8,9,10,11,12,13,14,15,19,22,23,24,25,26,27,28,33,34,35,38,39,40,42,43,46,47,48,50,51,52,53,54,57,58,59,62,63,65,66,68,69,72,74,75,76,77,80,81],white:75,who:16,whole:[72,74],wi:[80,81],width:[11,15,16,33,72,75],wifi:[37,65],wifi_ap:80,wifi_sta:81,wifiap:80,wifiauthenticationtyp:65,wificonfig:65,wifiencryptiontyp:65,wifista:81,wiki:[25,26,29,61,62,63,77],wikipedia:[18,25,26,29,61,62,63,77],wind:67,window_size_byt:[3,77],windup:67,wire:69,wireless:66,wish:[11,13],witdth:18,within:[12,19,21,22,23,33,52,57,63,75,76,77],without:[2,3,11,33,59,66,69,72],word:75,work:[6,8,10,11,24,33,59,72,76],world:11,worri:77,would:[18,23,74,76],wpa2:65,wpa2_enterpris:65,wpa2_person:65,wpa:65,wpa_enterpris:65,wpa_person:65,wpa_wpa2_person:65,wrap:[7,18,23,46,69,75],wrapper:[3,5,10,11,14,15,24,36,38,42,44,49,50,52,53,55,69,73,74,75],write:[1,2,6,8,11,13,15,16,19,22,24,28,34,36,39,40,43,46,48,51,66,68,70],write_data:[36,40],write_fn:[1,2,6,19,22,34,39,40,43,46,48,51,66,68,70],write_len:40,write_read:[36,40,68],write_read_fn:[40,68],write_row:14,write_s:36,written:[51,65,66,74],wrote:[14,24],ws2811:51,ws2812:51,ws2812_10mhz_bytes_encoder_config:69,ws2812_freq_hz:69,ws2812b:69,ws2813:51,www:[2,6,25,29,34,65,66],x1:58,x2:58,x:[2,6,11,13,16,25,39,40,44,45,46,48,49,58,59,66,72],x_calibr:[13,49],x_channel:6,x_mv:[1,2,6,13,49],xe:16,xml:[31,68,70],xml_in:[31,68,70],xqueuecreat:2,xqueuerec:2,xs:16,y1:58,y2:58,y:[2,6,13,16,25,39,40,44,45,49,52,55,58,72,80,81],y_calibr:[13,49],y_channel:6,y_mv:[1,2,6,13,49],ye:[16,81],year:70,yellow:[14,52,75],yet:[8,19,22,32,76],yield:69,you:[3,6,8,11,13,14,15,18,23,24,43,50,51,52,55,57,59,66,67,69,72,73,74,75,76,80,81],your:[23,52,59,75],yourself:74,ys:16,z:18,zelda1:14,zelda2:14,zelda:14,zelda_2:14,zero:[8,18,51,57,66,77],zero_electric_offset:8,zoom_in:39,zoom_out:39},titles:["ADC Types","ADS1x15 I2C ADC","ADS7138 I2C ADC","Continuous ADC","ADC APIs","Oneshot ADC","TLA2528 I2C 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","I2C","ESPP Documentation","Encoder Input","FT5x06 Touch Controller","GT911 Touch Controller","Input APIs","Keypad Input","LilyGo T-Keyboard","Touchpad Input","TT21100 Touch Controller","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","QwiicNES","Remote Control Transceiver (RMT)","BM8563","RTC APIs","RTSP APIs","Serialization APIs","State Machine APIs","Tabulate APIs","Task APIs","Thermistor APIs","Timer APIs","WiFi APIs","WiFi Access Point (AP)","WiFi Station (STA)"],titleterms:{"1":[33,51,69,78],"2":33,"class":[1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,22,23,24,25,26,28,29,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],"function":[30,31,68,70],"long":76,Then:78,abi:18,abiencod:18,access:80,adc:[0,1,2,3,4,5,6,49,77],ads1x15:1,ads7138:2,again:78,alpaca:73,analog:13,ap:80,apa102:51,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,35,36,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,69,70,71,72,73,74,75,76,77,78,79,80,81],as5600:19,aw9523:46,basic:[33,52,59,67,76],bench:74,bezier:53,biquad:25,bldc:[7,8,9,33],bm8563:70,box:16,breath:50,butterworth:26,button:10,buzz:33,cancel:78,cli:11,click:33,client:[62,63,72],color:12,command:11,complex:[14,67,73,74,75],config:16,continu:3,control:[13,39,40,45,69],csv:14,data:69,de:73,delai:78,devic:74,digit:13,displai:[15,16,17],document:37,driver:[7,16,34],drv2605:34,encod:[18,19,20,21,22,38,69],esp32:16,espp:37,event:23,exampl:[1,2,3,5,6,8,10,11,13,14,16,18,19,22,23,24,33,34,36,39,40,43,45,46,48,49,50,51,52,59,62,63,66,67,68,69,70,72,73,74,75,76,77,78,80,81],expand:[46,47,48],fast:54,file:[0,1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,20,22,23,24,25,26,28,29,30,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,54,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],filesystem:24,filter:[25,26,27,28,29],format:52,ft5x06:39,ftp:[31,32],gaussian:55,gener:74,get_latest_info:59,gt911:40,haptic:[33,34,35],header:[0,1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,20,22,23,24,25,26,28,29,30,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,54,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],hfsm:74,i2c:[1,2,6,13,36],i:[46,48],ili9341:16,info:[24,76],input:[38,41,42,44],interfac:11,io:47,itself:78,joystick:49,keyboard:43,keypad:42,kit:16,led:[50,51],lilygo:43,line:11,linear:[18,50],log:52,logger:52,lowpass:28,machin:74,macro:[11,14,73,74,75],magnet:[19,22],manag:23,mani:76,mapper:57,markdown:75,math:[54,56],mcp23x17:48,monitor:59,motor:[8,34],mt6701:22,multicast:63,ndef:65,network:60,newlib:24,nfc:64,o:[46,48],oneshot:[5,11,78],order:29,pid:67,plai:33,point:80,posix:24,qwiicn:68,rang:57,reader:14,real:74,refer:[0,1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,20,22,23,24,25,26,28,29,30,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,54,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],remot:69,request:76,respons:[62,63],rmt:69,rotat:18,rtc:71,rtsp:72,run:[74,76],s3:16,second:29,section:29,serial:73,server:[31,62,63,72],so:29,socket:[61,62,63],spi:51,st25dv:66,st7789:16,sta:81,start:78,state:74,station:81,std:24,stop:76,strip:51,structur:73,system:24,t:43,tabul:75,task:[59,76],tcp:62,test:74,thermistor:77,thread:52,timer:78,tla2528:6,touch:[39,40,45],touchpad:44,transceiv:69,transfer:30,transmit:69,tt21100:45,ttgo:16,type:[0,20],udp:63,union:[65,68],usag:[8,33],valid:77,vector2d:58,verbos:52,via:51,wifi:[79,80,81],writer:14,wrover:16,ws2812:69}}) \ No newline at end of file +Search.setIndex({docnames:["adc/adc_types","adc/ads1x15","adc/ads7138","adc/continuous_adc","adc/index","adc/oneshot_adc","adc/tla2528","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","i2c","index","input/encoder_input","input/ft5x06","input/gt911","input/index","input/keypad_input","input/t_keyboard","input/touchpad_input","input/tt21100","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","qwiicnes","rmt","rtc/bm8563","rtc/index","rtsp","serialization","state_machine","tabulate","task","thermistor","timer","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","adc/tla2528.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","i2c.rst","index.rst","input/encoder_input.rst","input/ft5x06.rst","input/gt911.rst","input/index.rst","input/keypad_input.rst","input/t_keyboard.rst","input/touchpad_input.rst","input/tt21100.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","qwiicnes.rst","rmt.rst","rtc/bm8563.rst","rtc/index.rst","rtsp.rst","serialization.rst","state_machine.rst","tabulate.rst","task.rst","thermistor.rst","timer.rst","wifi/index.rst","wifi/wifi_ap.rst","wifi/wifi_sta.rst"],objects:{"":[[74,0,1,"c.MAGIC_ENUM_NO_CHECK_SUPPORT","MAGIC_ENUM_NO_CHECK_SUPPORT"],[14,0,1,"c.__gnu_linux__","__gnu_linux__"],[73,0,1,"c.__gnu_linux__","__gnu_linux__"],[11,0,1,"c.__linux__","__linux__"],[75,0,1,"c.__unix__","__unix__"],[65,1,1,"_CPPv4N19PhonyNameDueToError3rawE","PhonyNameDueToError::raw"],[68,1,1,"_CPPv4N19PhonyNameDueToError3rawE","PhonyNameDueToError::raw"],[18,2,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoderE","espp::AbiEncoder"],[18,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder10AbiEncoderERK6Config","espp::AbiEncoder::AbiEncoder"],[18,4,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder10AbiEncoderERK6Config","espp::AbiEncoder::AbiEncoder::config"],[18,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder10AbiEncoderERK6Config","espp::AbiEncoder::AbiEncoder::type"],[18,2,1,"_CPPv4N4espp10AbiEncoder6ConfigE","espp::AbiEncoder::Config"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config6a_gpioE","espp::AbiEncoder::Config::a_gpio"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config6b_gpioE","espp::AbiEncoder::Config::b_gpio"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config21counts_per_revolutionE","espp::AbiEncoder::Config::counts_per_revolution"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config10high_limitE","espp::AbiEncoder::Config::high_limit"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config6i_gpioE","espp::AbiEncoder::Config::i_gpio"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config9log_levelE","espp::AbiEncoder::Config::log_level"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config9low_limitE","espp::AbiEncoder::Config::low_limit"],[18,1,1,"_CPPv4N4espp10AbiEncoder6Config13max_glitch_nsE","espp::AbiEncoder::Config::max_glitch_ns"],[18,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoderE","espp::AbiEncoder::T"],[18,3,1,"_CPPv4N4espp10AbiEncoder5clearEv","espp::AbiEncoder::clear"],[18,3,1,"_CPPv4N4espp10AbiEncoder9get_countEv","espp::AbiEncoder::get_count"],[18,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_degreesENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_degrees"],[18,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_degreesENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_degrees::type"],[18,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_radiansENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_radians"],[18,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder11get_radiansENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_radians::type"],[18,3,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder15get_revolutionsENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_revolutions"],[18,5,1,"_CPPv4I_11EncoderTypeEN4espp10AbiEncoder15get_revolutionsENSt9enable_ifIXeq4typeN11EncoderType10ROTATIONALEEfE4typeEv","espp::AbiEncoder::get_revolutions::type"],[18,3,1,"_CPPv4N4espp10AbiEncoder5startEv","espp::AbiEncoder::start"],[18,3,1,"_CPPv4N4espp10AbiEncoder4stopEv","espp::AbiEncoder::stop"],[18,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_mvEiRNSt10error_codeE","espp::Ads1x15::sample_mv"],[1,4,1,"_CPPv4N4espp7Ads1x159sample_mvEiRNSt10error_codeE","espp::Ads1x15::sample_mv::channel"],[1,4,1,"_CPPv4N4espp7Ads1x159sample_mvEiRNSt10error_codeE","espp::Ads1x15::sample_mv::ec"],[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,"_CPPv4N4espp7Ads71386Config9auto_initE","espp::Ads7138::Config::auto_init"],[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,"_CPPv4N4espp7Ads71386Config20digital_output_modesE","espp::Ads7138::Config::digital_output_modes"],[2,1,1,"_CPPv4N4espp7Ads71386Config21digital_output_valuesE","espp::Ads7138::Config::digital_output_values"],[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_tRNSt10error_codeE","espp::Ads7138::clear_event_high_flag"],[2,4,1,"_CPPv4N4espp7Ads713821clear_event_high_flagE7uint8_tRNSt10error_codeE","espp::Ads7138::clear_event_high_flag::ec"],[2,4,1,"_CPPv4N4espp7Ads713821clear_event_high_flagE7uint8_tRNSt10error_codeE","espp::Ads7138::clear_event_high_flag::flags"],[2,3,1,"_CPPv4N4espp7Ads713820clear_event_low_flagE7uint8_tRNSt10error_codeE","espp::Ads7138::clear_event_low_flag"],[2,4,1,"_CPPv4N4espp7Ads713820clear_event_low_flagE7uint8_tRNSt10error_codeE","espp::Ads7138::clear_event_low_flag::ec"],[2,4,1,"_CPPv4N4espp7Ads713820clear_event_low_flagE7uint8_tRNSt10error_codeE","espp::Ads7138::clear_event_low_flag::flags"],[2,3,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogicRNSt10error_codeE","espp::Ads7138::configure_alert"],[2,4,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogicRNSt10error_codeE","espp::Ads7138::configure_alert::alert_logic"],[2,4,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogicRNSt10error_codeE","espp::Ads7138::configure_alert::ec"],[2,4,1,"_CPPv4N4espp7Ads713815configure_alertE10OutputMode10AlertLogicRNSt10error_codeE","espp::Ads7138::configure_alert::output_mode"],[2,3,1,"_CPPv4N4espp7Ads713810get_all_mvERNSt10error_codeE","espp::Ads7138::get_all_mv"],[2,4,1,"_CPPv4N4espp7Ads713810get_all_mvERNSt10error_codeE","espp::Ads7138::get_all_mv::ec"],[2,3,1,"_CPPv4N4espp7Ads713814get_all_mv_mapERNSt10error_codeE","espp::Ads7138::get_all_mv_map"],[2,4,1,"_CPPv4N4espp7Ads713814get_all_mv_mapERNSt10error_codeE","espp::Ads7138::get_all_mv_map::ec"],[2,3,1,"_CPPv4N4espp7Ads713823get_digital_input_valueE7ChannelRNSt10error_codeE","espp::Ads7138::get_digital_input_value"],[2,4,1,"_CPPv4N4espp7Ads713823get_digital_input_valueE7ChannelRNSt10error_codeE","espp::Ads7138::get_digital_input_value::channel"],[2,4,1,"_CPPv4N4espp7Ads713823get_digital_input_valueE7ChannelRNSt10error_codeE","espp::Ads7138::get_digital_input_value::ec"],[2,3,1,"_CPPv4N4espp7Ads713824get_digital_input_valuesERNSt10error_codeE","espp::Ads7138::get_digital_input_values"],[2,4,1,"_CPPv4N4espp7Ads713824get_digital_input_valuesERNSt10error_codeE","espp::Ads7138::get_digital_input_values::ec"],[2,3,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_tRNSt10error_codeE","espp::Ads7138::get_event_data"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_tRNSt10error_codeE","espp::Ads7138::get_event_data::ec"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_tRNSt10error_codeE","espp::Ads7138::get_event_data::event_flags"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_tRNSt10error_codeE","espp::Ads7138::get_event_data::event_high_flags"],[2,4,1,"_CPPv4N4espp7Ads713814get_event_dataEP7uint8_tP7uint8_tP7uint8_tRNSt10error_codeE","espp::Ads7138::get_event_data::event_low_flags"],[2,3,1,"_CPPv4N4espp7Ads713815get_event_flagsERNSt10error_codeE","espp::Ads7138::get_event_flags"],[2,4,1,"_CPPv4N4espp7Ads713815get_event_flagsERNSt10error_codeE","espp::Ads7138::get_event_flags::ec"],[2,3,1,"_CPPv4N4espp7Ads713819get_event_high_flagERNSt10error_codeE","espp::Ads7138::get_event_high_flag"],[2,4,1,"_CPPv4N4espp7Ads713819get_event_high_flagERNSt10error_codeE","espp::Ads7138::get_event_high_flag::ec"],[2,3,1,"_CPPv4N4espp7Ads713818get_event_low_flagERNSt10error_codeE","espp::Ads7138::get_event_low_flag"],[2,4,1,"_CPPv4N4espp7Ads713818get_event_low_flagERNSt10error_codeE","espp::Ads7138::get_event_low_flag::ec"],[2,3,1,"_CPPv4N4espp7Ads71386get_mvE7ChannelRNSt10error_codeE","espp::Ads7138::get_mv"],[2,4,1,"_CPPv4N4espp7Ads71386get_mvE7ChannelRNSt10error_codeE","espp::Ads7138::get_mv::channel"],[2,4,1,"_CPPv4N4espp7Ads71386get_mvE7ChannelRNSt10error_codeE","espp::Ads7138::get_mv::ec"],[2,3,1,"_CPPv4N4espp7Ads713810initializeERNSt10error_codeE","espp::Ads7138::initialize"],[2,4,1,"_CPPv4N4espp7Ads713810initializeERNSt10error_codeE","espp::Ads7138::initialize::ec"],[2,8,1,"_CPPv4N4espp7Ads71387read_fnE","espp::Ads7138::read_fn"],[2,3,1,"_CPPv4N4espp7Ads71385resetERNSt10error_codeE","espp::Ads7138::reset"],[2,4,1,"_CPPv4N4espp7Ads71385resetERNSt10error_codeE","espp::Ads7138::reset::ec"],[2,3,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert::channel"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert::ec"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert::event"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert::event_count"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert::high_threshold_mv"],[2,4,1,"_CPPv4N4espp7Ads713816set_analog_alertE7Channelff11AnalogEventiRNSt10error_codeE","espp::Ads7138::set_analog_alert::low_threshold_mv"],[2,3,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEventRNSt10error_codeE","espp::Ads7138::set_digital_alert"],[2,4,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEventRNSt10error_codeE","espp::Ads7138::set_digital_alert::channel"],[2,4,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEventRNSt10error_codeE","espp::Ads7138::set_digital_alert::ec"],[2,4,1,"_CPPv4N4espp7Ads713817set_digital_alertE7Channel12DigitalEventRNSt10error_codeE","espp::Ads7138::set_digital_alert::event"],[2,3,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Ads7138::set_digital_output_mode"],[2,4,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Ads7138::set_digital_output_mode::channel"],[2,4,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Ads7138::set_digital_output_mode::ec"],[2,4,1,"_CPPv4N4espp7Ads713823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Ads7138::set_digital_output_mode::output_mode"],[2,3,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Ads7138::set_digital_output_value"],[2,4,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Ads7138::set_digital_output_value::channel"],[2,4,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Ads7138::set_digital_output_value::ec"],[2,4,1,"_CPPv4N4espp7Ads713824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Ads7138::set_digital_output_value::value"],[2,8,1,"_CPPv4N4espp7Ads71388write_fnE","espp::Ads7138::write_fn"],[19,2,1,"_CPPv4N4espp6As5600E","espp::As5600"],[19,3,1,"_CPPv4N4espp6As56006As5600ERK6Config","espp::As5600::As5600"],[19,4,1,"_CPPv4N4espp6As56006As5600ERK6Config","espp::As5600::As5600::config"],[19,1,1,"_CPPv4N4espp6As560021COUNTS_PER_REVOLUTIONE","espp::As5600::COUNTS_PER_REVOLUTION"],[19,1,1,"_CPPv4N4espp6As560023COUNTS_PER_REVOLUTION_FE","espp::As5600::COUNTS_PER_REVOLUTION_F"],[19,1,1,"_CPPv4N4espp6As560017COUNTS_TO_DEGREESE","espp::As5600::COUNTS_TO_DEGREES"],[19,1,1,"_CPPv4N4espp6As560017COUNTS_TO_RADIANSE","espp::As5600::COUNTS_TO_RADIANS"],[19,2,1,"_CPPv4N4espp6As56006ConfigE","espp::As5600::Config"],[19,1,1,"_CPPv4N4espp6As56006Config9auto_initE","espp::As5600::Config::auto_init"],[19,1,1,"_CPPv4N4espp6As56006Config14device_addressE","espp::As5600::Config::device_address"],[19,1,1,"_CPPv4N4espp6As56006Config4readE","espp::As5600::Config::read"],[19,1,1,"_CPPv4N4espp6As56006Config13update_periodE","espp::As5600::Config::update_period"],[19,1,1,"_CPPv4N4espp6As56006Config15velocity_filterE","espp::As5600::Config::velocity_filter"],[19,1,1,"_CPPv4N4espp6As56006Config5writeE","espp::As5600::Config::write"],[19,1,1,"_CPPv4N4espp6As560015DEFAULT_ADDRESSE","espp::As5600::DEFAULT_ADDRESS"],[19,1,1,"_CPPv4N4espp6As560018SECONDS_PER_MINUTEE","espp::As5600::SECONDS_PER_MINUTE"],[19,3,1,"_CPPv4NK4espp6As560015get_accumulatorEv","espp::As5600::get_accumulator"],[19,3,1,"_CPPv4NK4espp6As56009get_countEv","espp::As5600::get_count"],[19,3,1,"_CPPv4NK4espp6As560011get_degreesEv","espp::As5600::get_degrees"],[19,3,1,"_CPPv4NK4espp6As560022get_mechanical_degreesEv","espp::As5600::get_mechanical_degrees"],[19,3,1,"_CPPv4NK4espp6As560022get_mechanical_radiansEv","espp::As5600::get_mechanical_radians"],[19,3,1,"_CPPv4NK4espp6As560011get_radiansEv","espp::As5600::get_radians"],[19,3,1,"_CPPv4NK4espp6As56007get_rpmEv","espp::As5600::get_rpm"],[19,3,1,"_CPPv4N4espp6As560010initializeERNSt10error_codeE","espp::As5600::initialize"],[19,4,1,"_CPPv4N4espp6As560010initializeERNSt10error_codeE","espp::As5600::initialize::ec"],[19,3,1,"_CPPv4NK4espp6As560017needs_zero_searchEv","espp::As5600::needs_zero_search"],[19,8,1,"_CPPv4N4espp6As56007read_fnE","espp::As5600::read_fn"],[19,8,1,"_CPPv4N4espp6As560018velocity_filter_fnE","espp::As5600::velocity_filter_fn"],[19,8,1,"_CPPv4N4espp6As56008write_fnE","espp::As5600::write_fn"],[46,2,1,"_CPPv4N4espp6Aw9523E","espp::Aw9523"],[46,3,1,"_CPPv4N4espp6Aw95236Aw9523ERK6Config","espp::Aw9523::Aw9523"],[46,4,1,"_CPPv4N4espp6Aw95236Aw9523ERK6Config","espp::Aw9523::Aw9523::config"],[46,2,1,"_CPPv4N4espp6Aw95236ConfigE","espp::Aw9523::Config"],[46,1,1,"_CPPv4N4espp6Aw95236Config9auto_initE","espp::Aw9523::Config::auto_init"],[46,1,1,"_CPPv4N4espp6Aw95236Config14device_addressE","espp::Aw9523::Config::device_address"],[46,1,1,"_CPPv4N4espp6Aw95236Config9log_levelE","espp::Aw9523::Config::log_level"],[46,1,1,"_CPPv4N4espp6Aw95236Config15max_led_currentE","espp::Aw9523::Config::max_led_current"],[46,1,1,"_CPPv4N4espp6Aw95236Config20output_drive_mode_p0E","espp::Aw9523::Config::output_drive_mode_p0"],[46,1,1,"_CPPv4N4espp6Aw95236Config21port_0_direction_maskE","espp::Aw9523::Config::port_0_direction_mask"],[46,1,1,"_CPPv4N4espp6Aw95236Config21port_0_interrupt_maskE","espp::Aw9523::Config::port_0_interrupt_mask"],[46,1,1,"_CPPv4N4espp6Aw95236Config21port_1_direction_maskE","espp::Aw9523::Config::port_1_direction_mask"],[46,1,1,"_CPPv4N4espp6Aw95236Config21port_1_interrupt_maskE","espp::Aw9523::Config::port_1_interrupt_mask"],[46,1,1,"_CPPv4N4espp6Aw95236Config4readE","espp::Aw9523::Config::read"],[46,1,1,"_CPPv4N4espp6Aw95236Config5writeE","espp::Aw9523::Config::write"],[46,1,1,"_CPPv4N4espp6Aw952315DEFAULT_ADDRESSE","espp::Aw9523::DEFAULT_ADDRESS"],[46,6,1,"_CPPv4N4espp6Aw952313MaxLedCurrentE","espp::Aw9523::MaxLedCurrent"],[46,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent4IMAXE","espp::Aw9523::MaxLedCurrent::IMAX"],[46,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent7IMAX_25E","espp::Aw9523::MaxLedCurrent::IMAX_25"],[46,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent7IMAX_50E","espp::Aw9523::MaxLedCurrent::IMAX_50"],[46,7,1,"_CPPv4N4espp6Aw952313MaxLedCurrent7IMAX_75E","espp::Aw9523::MaxLedCurrent::IMAX_75"],[46,6,1,"_CPPv4N4espp6Aw952317OutputDriveModeP0E","espp::Aw9523::OutputDriveModeP0"],[46,7,1,"_CPPv4N4espp6Aw952317OutputDriveModeP010OPEN_DRAINE","espp::Aw9523::OutputDriveModeP0::OPEN_DRAIN"],[46,7,1,"_CPPv4N4espp6Aw952317OutputDriveModeP09PUSH_PULLE","espp::Aw9523::OutputDriveModeP0::PUSH_PULL"],[46,6,1,"_CPPv4N4espp6Aw95234PortE","espp::Aw9523::Port"],[46,7,1,"_CPPv4N4espp6Aw95234Port5PORT0E","espp::Aw9523::Port::PORT0"],[46,7,1,"_CPPv4N4espp6Aw95234Port5PORT1E","espp::Aw9523::Port::PORT1"],[46,3,1,"_CPPv4N4espp6Aw952310clear_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins"],[46,3,1,"_CPPv4N4espp6Aw952310clear_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins"],[46,3,1,"_CPPv4N4espp6Aw952310clear_pinsE8uint16_tRNSt10error_codeE","espp::Aw9523::clear_pins"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE8uint16_tRNSt10error_codeE","espp::Aw9523::clear_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins::mask"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE8uint16_tRNSt10error_codeE","espp::Aw9523::clear_pins::mask"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins::p0"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins::p1"],[46,4,1,"_CPPv4N4espp6Aw952310clear_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::clear_pins::port"],[46,3,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrentRNSt10error_codeE","espp::Aw9523::configure_global_control"],[46,4,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrentRNSt10error_codeE","espp::Aw9523::configure_global_control::ec"],[46,4,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrentRNSt10error_codeE","espp::Aw9523::configure_global_control::max_led_current"],[46,4,1,"_CPPv4N4espp6Aw952324configure_global_controlE17OutputDriveModeP013MaxLedCurrentRNSt10error_codeE","espp::Aw9523::configure_global_control::output_drive_mode_p0"],[46,3,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led"],[46,3,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led"],[46,3,1,"_CPPv4N4espp6Aw952313configure_ledE8uint16_tRNSt10error_codeE","espp::Aw9523::configure_led"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led::ec"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led::ec"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE8uint16_tRNSt10error_codeE","espp::Aw9523::configure_led::ec"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led::mask"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE8uint16_tRNSt10error_codeE","espp::Aw9523::configure_led::mask"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led::p0"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led::p1"],[46,4,1,"_CPPv4N4espp6Aw952313configure_ledE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::configure_led::port"],[46,3,1,"_CPPv4N4espp6Aw952310get_outputE4PortRNSt10error_codeE","espp::Aw9523::get_output"],[46,3,1,"_CPPv4N4espp6Aw952310get_outputERNSt10error_codeE","espp::Aw9523::get_output"],[46,4,1,"_CPPv4N4espp6Aw952310get_outputE4PortRNSt10error_codeE","espp::Aw9523::get_output::ec"],[46,4,1,"_CPPv4N4espp6Aw952310get_outputERNSt10error_codeE","espp::Aw9523::get_output::ec"],[46,4,1,"_CPPv4N4espp6Aw952310get_outputE4PortRNSt10error_codeE","espp::Aw9523::get_output::port"],[46,3,1,"_CPPv4N4espp6Aw95238get_pinsE4PortRNSt10error_codeE","espp::Aw9523::get_pins"],[46,3,1,"_CPPv4N4espp6Aw95238get_pinsERNSt10error_codeE","espp::Aw9523::get_pins"],[46,4,1,"_CPPv4N4espp6Aw95238get_pinsE4PortRNSt10error_codeE","espp::Aw9523::get_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw95238get_pinsERNSt10error_codeE","espp::Aw9523::get_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw95238get_pinsE4PortRNSt10error_codeE","espp::Aw9523::get_pins::port"],[46,3,1,"_CPPv4N4espp6Aw952310initializeERNSt10error_codeE","espp::Aw9523::initialize"],[46,4,1,"_CPPv4N4espp6Aw952310initializeERNSt10error_codeE","espp::Aw9523::initialize::ec"],[46,3,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_tRNSt10error_codeE","espp::Aw9523::led"],[46,4,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_tRNSt10error_codeE","espp::Aw9523::led::brightness"],[46,4,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_tRNSt10error_codeE","espp::Aw9523::led::ec"],[46,4,1,"_CPPv4N4espp6Aw95233ledE8uint16_t7uint8_tRNSt10error_codeE","espp::Aw9523::led::pin"],[46,3,1,"_CPPv4N4espp6Aw95236outputE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::output"],[46,3,1,"_CPPv4N4espp6Aw95236outputE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::output"],[46,3,1,"_CPPv4N4espp6Aw95236outputE8uint16_tRNSt10error_codeE","espp::Aw9523::output"],[46,4,1,"_CPPv4N4espp6Aw95236outputE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::output::ec"],[46,4,1,"_CPPv4N4espp6Aw95236outputE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::output::ec"],[46,4,1,"_CPPv4N4espp6Aw95236outputE8uint16_tRNSt10error_codeE","espp::Aw9523::output::ec"],[46,4,1,"_CPPv4N4espp6Aw95236outputE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::output::p0"],[46,4,1,"_CPPv4N4espp6Aw95236outputE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::output::p1"],[46,4,1,"_CPPv4N4espp6Aw95236outputE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::output::port"],[46,4,1,"_CPPv4N4espp6Aw95236outputE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::output::value"],[46,4,1,"_CPPv4N4espp6Aw95236outputE8uint16_tRNSt10error_codeE","espp::Aw9523::output::value"],[46,8,1,"_CPPv4N4espp6Aw95237read_fnE","espp::Aw9523::read_fn"],[46,3,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction"],[46,3,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction"],[46,4,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction::ec"],[46,4,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction::ec"],[46,4,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction::mask"],[46,4,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction::p0"],[46,4,1,"_CPPv4N4espp6Aw952313set_directionE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction::p1"],[46,4,1,"_CPPv4N4espp6Aw952313set_directionE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_direction::port"],[46,3,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt"],[46,3,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt"],[46,4,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt::ec"],[46,4,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt::ec"],[46,4,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt::mask"],[46,4,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt::p0"],[46,4,1,"_CPPv4N4espp6Aw952313set_interruptE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt::p1"],[46,4,1,"_CPPv4N4espp6Aw952313set_interruptE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_interrupt::port"],[46,3,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins"],[46,3,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins"],[46,3,1,"_CPPv4N4espp6Aw95238set_pinsE8uint16_tRNSt10error_codeE","espp::Aw9523::set_pins"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE8uint16_tRNSt10error_codeE","espp::Aw9523::set_pins::ec"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins::mask"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE8uint16_tRNSt10error_codeE","espp::Aw9523::set_pins::mask"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins::p0"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE7uint8_t7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins::p1"],[46,4,1,"_CPPv4N4espp6Aw95238set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Aw9523::set_pins::port"],[46,8,1,"_CPPv4N4espp6Aw95238write_fnE","espp::Aw9523::write_fn"],[53,2,1,"_CPPv4I0EN4espp6BezierE","espp::Bezier"],[53,3,1,"_CPPv4N4espp6Bezier6BezierERK14WeightedConfig","espp::Bezier::Bezier"],[53,3,1,"_CPPv4N4espp6Bezier6BezierERK6Config","espp::Bezier::Bezier"],[53,4,1,"_CPPv4N4espp6Bezier6BezierERK14WeightedConfig","espp::Bezier::Bezier::config"],[53,4,1,"_CPPv4N4espp6Bezier6BezierERK6Config","espp::Bezier::Bezier::config"],[53,2,1,"_CPPv4N4espp6Bezier6ConfigE","espp::Bezier::Config"],[53,1,1,"_CPPv4N4espp6Bezier6Config14control_pointsE","espp::Bezier::Config::control_points"],[53,5,1,"_CPPv4I0EN4espp6BezierE","espp::Bezier::T"],[53,2,1,"_CPPv4N4espp6Bezier14WeightedConfigE","espp::Bezier::WeightedConfig"],[53,1,1,"_CPPv4N4espp6Bezier14WeightedConfig14control_pointsE","espp::Bezier::WeightedConfig::control_points"],[53,1,1,"_CPPv4N4espp6Bezier14WeightedConfig7weightsE","espp::Bezier::WeightedConfig::weights"],[53,3,1,"_CPPv4NK4espp6Bezier2atEf","espp::Bezier::at"],[53,4,1,"_CPPv4NK4espp6Bezier2atEf","espp::Bezier::at::t"],[53,3,1,"_CPPv4NK4espp6BezierclEf","espp::Bezier::operator()"],[53,4,1,"_CPPv4NK4espp6BezierclEf","espp::Bezier::operator()::t"],[25,2,1,"_CPPv4N4espp15BiquadFilterDf1E","espp::BiquadFilterDf1"],[25,3,1,"_CPPv4N4espp15BiquadFilterDf16updateEf","espp::BiquadFilterDf1::update"],[25,4,1,"_CPPv4N4espp15BiquadFilterDf16updateEf","espp::BiquadFilterDf1::update::input"],[25,2,1,"_CPPv4N4espp15BiquadFilterDf2E","espp::BiquadFilterDf2"],[25,3,1,"_CPPv4N4espp15BiquadFilterDf26updateEKf","espp::BiquadFilterDf2::update"],[25,3,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update"],[25,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEKf","espp::BiquadFilterDf2::update::input"],[25,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update::input"],[25,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update::length"],[25,4,1,"_CPPv4N4espp15BiquadFilterDf26updateEPKfPf6size_t","espp::BiquadFilterDf2::update::output"],[7,2,1,"_CPPv4N4espp10BldcDriverE","espp::BldcDriver"],[7,3,1,"_CPPv4N4espp10BldcDriver10BldcDriverERK6Config","espp::BldcDriver::BldcDriver"],[7,4,1,"_CPPv4N4espp10BldcDriver10BldcDriverERK6Config","espp::BldcDriver::BldcDriver::config"],[7,2,1,"_CPPv4N4espp10BldcDriver6ConfigE","espp::BldcDriver::Config"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config9dead_zoneE","espp::BldcDriver::Config::dead_zone"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_a_hE","espp::BldcDriver::Config::gpio_a_h"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_a_lE","espp::BldcDriver::Config::gpio_a_l"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_b_hE","espp::BldcDriver::Config::gpio_b_h"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_b_lE","espp::BldcDriver::Config::gpio_b_l"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_c_hE","espp::BldcDriver::Config::gpio_c_h"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config8gpio_c_lE","espp::BldcDriver::Config::gpio_c_l"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config11gpio_enableE","espp::BldcDriver::Config::gpio_enable"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config10gpio_faultE","espp::BldcDriver::Config::gpio_fault"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config13limit_voltageE","espp::BldcDriver::Config::limit_voltage"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config9log_levelE","espp::BldcDriver::Config::log_level"],[7,1,1,"_CPPv4N4espp10BldcDriver6Config20power_supply_voltageE","espp::BldcDriver::Config::power_supply_voltage"],[7,3,1,"_CPPv4N4espp10BldcDriver15configure_powerEff","espp::BldcDriver::configure_power"],[7,4,1,"_CPPv4N4espp10BldcDriver15configure_powerEff","espp::BldcDriver::configure_power::power_supply_voltage"],[7,4,1,"_CPPv4N4espp10BldcDriver15configure_powerEff","espp::BldcDriver::configure_power::voltage_limit"],[7,3,1,"_CPPv4N4espp10BldcDriver7disableEv","espp::BldcDriver::disable"],[7,3,1,"_CPPv4N4espp10BldcDriver6enableEv","espp::BldcDriver::enable"],[7,3,1,"_CPPv4NK4espp10BldcDriver22get_power_supply_limitEv","espp::BldcDriver::get_power_supply_limit"],[7,3,1,"_CPPv4NK4espp10BldcDriver17get_voltage_limitEv","espp::BldcDriver::get_voltage_limit"],[7,3,1,"_CPPv4NK4espp10BldcDriver10is_enabledEv","espp::BldcDriver::is_enabled"],[7,3,1,"_CPPv4N4espp10BldcDriver10is_faultedEv","espp::BldcDriver::is_faulted"],[7,3,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state"],[7,4,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state::state_a"],[7,4,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state::state_b"],[7,4,1,"_CPPv4N4espp10BldcDriver15set_phase_stateEiii","espp::BldcDriver::set_phase_state::state_c"],[7,3,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm"],[7,4,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm::duty_a"],[7,4,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm::duty_b"],[7,4,1,"_CPPv4N4espp10BldcDriver7set_pwmEfff","espp::BldcDriver::set_pwm::duty_c"],[7,3,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage"],[7,4,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage::ua"],[7,4,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage::ub"],[7,4,1,"_CPPv4N4espp10BldcDriver11set_voltageEfff","espp::BldcDriver::set_voltage::uc"],[7,3,1,"_CPPv4N4espp10BldcDriverD0Ev","espp::BldcDriver::~BldcDriver"],[33,2,1,"_CPPv4I_12MotorConceptEN4espp11BldcHapticsE","espp::BldcHaptics"],[33,3,1,"_CPPv4N4espp11BldcHaptics11BldcHapticsERK6Config","espp::BldcHaptics::BldcHaptics"],[33,4,1,"_CPPv4N4espp11BldcHaptics11BldcHapticsERK6Config","espp::BldcHaptics::BldcHaptics::config"],[33,2,1,"_CPPv4N4espp11BldcHaptics6ConfigE","espp::BldcHaptics::Config"],[33,1,1,"_CPPv4N4espp11BldcHaptics6Config13kd_factor_maxE","espp::BldcHaptics::Config::kd_factor_max"],[33,1,1,"_CPPv4N4espp11BldcHaptics6Config13kd_factor_minE","espp::BldcHaptics::Config::kd_factor_min"],[33,1,1,"_CPPv4N4espp11BldcHaptics6Config9kp_factorE","espp::BldcHaptics::Config::kp_factor"],[33,1,1,"_CPPv4N4espp11BldcHaptics6Config9log_levelE","espp::BldcHaptics::Config::log_level"],[33,1,1,"_CPPv4N4espp11BldcHaptics6Config5motorE","espp::BldcHaptics::Config::motor"],[33,5,1,"_CPPv4I_12MotorConceptEN4espp11BldcHapticsE","espp::BldcHaptics::M"],[33,3,1,"_CPPv4NK4espp11BldcHaptics12get_positionEv","espp::BldcHaptics::get_position"],[33,3,1,"_CPPv4NK4espp11BldcHaptics10is_runningEv","espp::BldcHaptics::is_running"],[33,3,1,"_CPPv4N4espp11BldcHaptics11play_hapticERKN6detail12HapticConfigE","espp::BldcHaptics::play_haptic"],[33,4,1,"_CPPv4N4espp11BldcHaptics11play_hapticERKN6detail12HapticConfigE","espp::BldcHaptics::play_haptic::config"],[33,3,1,"_CPPv4N4espp11BldcHaptics5startEv","espp::BldcHaptics::start"],[33,3,1,"_CPPv4N4espp11BldcHaptics4stopEv","espp::BldcHaptics::stop"],[33,3,1,"_CPPv4N4espp11BldcHaptics20update_detent_configERKN6detail12DetentConfigE","espp::BldcHaptics::update_detent_config"],[33,4,1,"_CPPv4N4espp11BldcHaptics20update_detent_configERKN6detail12DetentConfigE","espp::BldcHaptics::update_detent_config::config"],[33,3,1,"_CPPv4N4espp11BldcHapticsD0Ev","espp::BldcHaptics::~BldcHaptics"],[8,2,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor"],[8,3,1,"_CPPv4N4espp9BldcMotor9BldcMotorERK6Config","espp::BldcMotor::BldcMotor"],[8,4,1,"_CPPv4N4espp9BldcMotor9BldcMotorERK6Config","espp::BldcMotor::BldcMotor::config"],[8,5,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor::CS"],[8,2,1,"_CPPv4N4espp9BldcMotor6ConfigE","espp::BldcMotor::Config"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config12angle_filterE","espp::BldcMotor::Config::angle_filter"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config13current_limitE","espp::BldcMotor::Config::current_limit"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config13current_senseE","espp::BldcMotor::Config::current_sense"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config16d_current_filterE","espp::BldcMotor::Config::d_current_filter"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config6driverE","espp::BldcMotor::Config::driver"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config8foc_typeE","espp::BldcMotor::Config::foc_type"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config9kv_ratingE","espp::BldcMotor::Config::kv_rating"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config9log_levelE","espp::BldcMotor::Config::log_level"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config14num_pole_pairsE","espp::BldcMotor::Config::num_pole_pairs"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config16phase_inductanceE","espp::BldcMotor::Config::phase_inductance"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config16phase_resistanceE","espp::BldcMotor::Config::phase_resistance"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config16q_current_filterE","espp::BldcMotor::Config::q_current_filter"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config6sensorE","espp::BldcMotor::Config::sensor"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config17torque_controllerE","espp::BldcMotor::Config::torque_controller"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config15velocity_filterE","espp::BldcMotor::Config::velocity_filter"],[8,1,1,"_CPPv4N4espp9BldcMotor6Config14velocity_limitE","espp::BldcMotor::Config::velocity_limit"],[8,5,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor::D"],[8,5,1,"_CPPv4I_13DriverConcept_13SensorConcept_20CurrentSensorConceptEN4espp9BldcMotorE","espp::BldcMotor::S"],[8,3,1,"_CPPv4N4espp9BldcMotor7disableEv","espp::BldcMotor::disable"],[8,3,1,"_CPPv4N4espp9BldcMotor6enableEv","espp::BldcMotor::enable"],[8,8,1,"_CPPv4N4espp9BldcMotor9filter_fnE","espp::BldcMotor::filter_fn"],[8,3,1,"_CPPv4N4espp9BldcMotor20get_electrical_angleEv","espp::BldcMotor::get_electrical_angle"],[8,3,1,"_CPPv4N4espp9BldcMotor15get_shaft_angleEv","espp::BldcMotor::get_shaft_angle"],[8,3,1,"_CPPv4N4espp9BldcMotor18get_shaft_velocityEv","espp::BldcMotor::get_shaft_velocity"],[8,3,1,"_CPPv4NK4espp9BldcMotor10is_enabledEv","espp::BldcMotor::is_enabled"],[8,3,1,"_CPPv4N4espp9BldcMotor8loop_focEv","espp::BldcMotor::loop_foc"],[8,3,1,"_CPPv4N4espp9BldcMotor4moveEf","espp::BldcMotor::move"],[8,4,1,"_CPPv4N4espp9BldcMotor4moveEf","espp::BldcMotor::move::new_target"],[8,3,1,"_CPPv4N4espp9BldcMotor23set_motion_control_typeEN6detail17MotionControlTypeE","espp::BldcMotor::set_motion_control_type"],[8,4,1,"_CPPv4N4espp9BldcMotor23set_motion_control_typeEN6detail17MotionControlTypeE","espp::BldcMotor::set_motion_control_type::motion_control_type"],[8,3,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage"],[8,4,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage::el_angle"],[8,4,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage::ud"],[8,4,1,"_CPPv4N4espp9BldcMotor17set_phase_voltageEfff","espp::BldcMotor::set_phase_voltage::uq"],[8,3,1,"_CPPv4N4espp9BldcMotorD0Ev","espp::BldcMotor::~BldcMotor"],[70,2,1,"_CPPv4N4espp6Bm8563E","espp::Bm8563"],[70,3,1,"_CPPv4N4espp6Bm85636Bm8563ERK6Config","espp::Bm8563::Bm8563"],[70,4,1,"_CPPv4N4espp6Bm85636Bm8563ERK6Config","espp::Bm8563::Bm8563::config"],[70,2,1,"_CPPv4N4espp6Bm85636ConfigE","espp::Bm8563::Config"],[70,1,1,"_CPPv4N4espp6Bm85636Config9log_levelE","espp::Bm8563::Config::log_level"],[70,1,1,"_CPPv4N4espp6Bm85636Config4readE","espp::Bm8563::Config::read"],[70,1,1,"_CPPv4N4espp6Bm85636Config5writeE","espp::Bm8563::Config::write"],[70,1,1,"_CPPv4N4espp6Bm856315DEFAULT_ADDRESSE","espp::Bm8563::DEFAULT_ADDRESS"],[70,2,1,"_CPPv4N4espp6Bm85634DateE","espp::Bm8563::Date"],[70,1,1,"_CPPv4N4espp6Bm85634Date3dayE","espp::Bm8563::Date::day"],[70,1,1,"_CPPv4N4espp6Bm85634Date5monthE","espp::Bm8563::Date::month"],[70,1,1,"_CPPv4N4espp6Bm85634Date7weekdayE","espp::Bm8563::Date::weekday"],[70,1,1,"_CPPv4N4espp6Bm85634Date4yearE","espp::Bm8563::Date::year"],[70,2,1,"_CPPv4N4espp6Bm85638DateTimeE","espp::Bm8563::DateTime"],[70,1,1,"_CPPv4N4espp6Bm85638DateTime4dateE","espp::Bm8563::DateTime::date"],[70,1,1,"_CPPv4N4espp6Bm85638DateTime4timeE","espp::Bm8563::DateTime::time"],[70,2,1,"_CPPv4N4espp6Bm85634TimeE","espp::Bm8563::Time"],[70,1,1,"_CPPv4N4espp6Bm85634Time4hourE","espp::Bm8563::Time::hour"],[70,1,1,"_CPPv4N4espp6Bm85634Time6minuteE","espp::Bm8563::Time::minute"],[70,1,1,"_CPPv4N4espp6Bm85634Time6secondE","espp::Bm8563::Time::second"],[70,3,1,"_CPPv4N4espp6Bm85638bcd2byteE7uint8_t","espp::Bm8563::bcd2byte"],[70,4,1,"_CPPv4N4espp6Bm85638bcd2byteE7uint8_t","espp::Bm8563::bcd2byte::value"],[70,3,1,"_CPPv4N4espp6Bm85638byte2bcdE7uint8_t","espp::Bm8563::byte2bcd"],[70,4,1,"_CPPv4N4espp6Bm85638byte2bcdE7uint8_t","espp::Bm8563::byte2bcd::value"],[70,3,1,"_CPPv4N4espp6Bm85638get_dateERNSt10error_codeE","espp::Bm8563::get_date"],[70,4,1,"_CPPv4N4espp6Bm85638get_dateERNSt10error_codeE","espp::Bm8563::get_date::ec"],[70,3,1,"_CPPv4N4espp6Bm856313get_date_timeERNSt10error_codeE","espp::Bm8563::get_date_time"],[70,4,1,"_CPPv4N4espp6Bm856313get_date_timeERNSt10error_codeE","espp::Bm8563::get_date_time::ec"],[70,3,1,"_CPPv4N4espp6Bm85638get_timeERNSt10error_codeE","espp::Bm8563::get_time"],[70,4,1,"_CPPv4N4espp6Bm85638get_timeERNSt10error_codeE","espp::Bm8563::get_time::ec"],[70,8,1,"_CPPv4N4espp6Bm85637read_fnE","espp::Bm8563::read_fn"],[70,3,1,"_CPPv4N4espp6Bm85638set_dateERK4DateRNSt10error_codeE","espp::Bm8563::set_date"],[70,4,1,"_CPPv4N4espp6Bm85638set_dateERK4DateRNSt10error_codeE","espp::Bm8563::set_date::d"],[70,4,1,"_CPPv4N4espp6Bm85638set_dateERK4DateRNSt10error_codeE","espp::Bm8563::set_date::ec"],[70,3,1,"_CPPv4N4espp6Bm856313set_date_timeERK8DateTimeRNSt10error_codeE","espp::Bm8563::set_date_time"],[70,4,1,"_CPPv4N4espp6Bm856313set_date_timeERK8DateTimeRNSt10error_codeE","espp::Bm8563::set_date_time::dt"],[70,4,1,"_CPPv4N4espp6Bm856313set_date_timeERK8DateTimeRNSt10error_codeE","espp::Bm8563::set_date_time::ec"],[70,3,1,"_CPPv4N4espp6Bm85638set_timeERK4TimeRNSt10error_codeE","espp::Bm8563::set_time"],[70,4,1,"_CPPv4N4espp6Bm85638set_timeERK4TimeRNSt10error_codeE","espp::Bm8563::set_time::ec"],[70,4,1,"_CPPv4N4espp6Bm85638set_timeERK4TimeRNSt10error_codeE","espp::Bm8563::set_time::t"],[70,8,1,"_CPPv4N4espp6Bm85638write_fnE","espp::Bm8563::write_fn"],[26,2,1,"_CPPv4I_6size_t0EN4espp17ButterworthFilterE","espp::ButterworthFilter"],[26,3,1,"_CPPv4N4espp17ButterworthFilter17ButterworthFilterERK6Config","espp::ButterworthFilter::ButterworthFilter"],[26,4,1,"_CPPv4N4espp17ButterworthFilter17ButterworthFilterERK6Config","espp::ButterworthFilter::ButterworthFilter::config"],[26,2,1,"_CPPv4N4espp17ButterworthFilter6ConfigE","espp::ButterworthFilter::Config"],[26,1,1,"_CPPv4N4espp17ButterworthFilter6Config27normalized_cutoff_frequencyE","espp::ButterworthFilter::Config::normalized_cutoff_frequency"],[26,5,1,"_CPPv4I_6size_t0EN4espp17ButterworthFilterE","espp::ButterworthFilter::Impl"],[26,5,1,"_CPPv4I_6size_t0EN4espp17ButterworthFilterE","espp::ButterworthFilter::ORDER"],[26,3,1,"_CPPv4N4espp17ButterworthFilterclEf","espp::ButterworthFilter::operator()"],[26,4,1,"_CPPv4N4espp17ButterworthFilterclEf","espp::ButterworthFilter::operator()::input"],[26,3,1,"_CPPv4N4espp17ButterworthFilter6updateEf","espp::ButterworthFilter::update"],[26,4,1,"_CPPv4N4espp17ButterworthFilter6updateEf","espp::ButterworthFilter::update::input"],[10,2,1,"_CPPv4N4espp6ButtonE","espp::Button"],[10,6,1,"_CPPv4N4espp6Button11ActiveLevelE","espp::Button::ActiveLevel"],[10,7,1,"_CPPv4N4espp6Button11ActiveLevel4HIGHE","espp::Button::ActiveLevel::HIGH"],[10,7,1,"_CPPv4N4espp6Button11ActiveLevel3LOWE","espp::Button::ActiveLevel::LOW"],[10,3,1,"_CPPv4N4espp6Button6ButtonERK6Config","espp::Button::Button"],[10,4,1,"_CPPv4N4espp6Button6ButtonERK6Config","espp::Button::Button::config"],[10,2,1,"_CPPv4N4espp6Button6ConfigE","espp::Button::Config"],[10,1,1,"_CPPv4N4espp6Button6Config12active_levelE","espp::Button::Config::active_level"],[10,1,1,"_CPPv4N4espp6Button6Config8callbackE","espp::Button::Config::callback"],[10,1,1,"_CPPv4N4espp6Button6Config7core_idE","espp::Button::Config::core_id"],[10,1,1,"_CPPv4N4espp6Button6Config8gpio_numE","espp::Button::Config::gpio_num"],[10,1,1,"_CPPv4N4espp6Button6Config14interrupt_typeE","espp::Button::Config::interrupt_type"],[10,1,1,"_CPPv4N4espp6Button6Config9log_levelE","espp::Button::Config::log_level"],[10,1,1,"_CPPv4N4espp6Button6Config4nameE","espp::Button::Config::name"],[10,1,1,"_CPPv4N4espp6Button6Config8priorityE","espp::Button::Config::priority"],[10,1,1,"_CPPv4N4espp6Button6Config16pulldown_enabledE","espp::Button::Config::pulldown_enabled"],[10,1,1,"_CPPv4N4espp6Button6Config14pullup_enabledE","espp::Button::Config::pullup_enabled"],[10,1,1,"_CPPv4N4espp6Button6Config21task_stack_size_bytesE","espp::Button::Config::task_stack_size_bytes"],[10,2,1,"_CPPv4N4espp6Button5EventE","espp::Button::Event"],[10,1,1,"_CPPv4N4espp6Button5Event8gpio_numE","espp::Button::Event::gpio_num"],[10,1,1,"_CPPv4N4espp6Button5Event7pressedE","espp::Button::Event::pressed"],[10,6,1,"_CPPv4N4espp6Button13InterruptTypeE","espp::Button::InterruptType"],[10,7,1,"_CPPv4N4espp6Button13InterruptType8ANY_EDGEE","espp::Button::InterruptType::ANY_EDGE"],[10,7,1,"_CPPv4N4espp6Button13InterruptType12FALLING_EDGEE","espp::Button::InterruptType::FALLING_EDGE"],[10,7,1,"_CPPv4N4espp6Button13InterruptType10HIGH_LEVELE","espp::Button::InterruptType::HIGH_LEVEL"],[10,7,1,"_CPPv4N4espp6Button13InterruptType9LOW_LEVELE","espp::Button::InterruptType::LOW_LEVEL"],[10,7,1,"_CPPv4N4espp6Button13InterruptType11RISING_EDGEE","espp::Button::InterruptType::RISING_EDGE"],[10,8,1,"_CPPv4N4espp6Button17event_callback_fnE","espp::Button::event_callback_fn"],[10,3,1,"_CPPv4NK4espp6Button10is_pressedEv","espp::Button::is_pressed"],[10,3,1,"_CPPv4N4espp6ButtonD0Ev","espp::Button::~Button"],[11,2,1,"_CPPv4N4espp3CliE","espp::Cli"],[11,3,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli"],[11,4,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli::_cli"],[11,4,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli::_in"],[11,4,1,"_CPPv4N4espp3Cli3CliERN3cli3CliERNSt7istreamERNSt7ostreamE","espp::Cli::Cli::_out"],[11,3,1,"_CPPv4NK4espp3Cli15GetInputHistoryEv","espp::Cli::GetInputHistory"],[11,3,1,"_CPPv4N4espp3Cli15SetHandleResizeEb","espp::Cli::SetHandleResize"],[11,4,1,"_CPPv4N4espp3Cli15SetHandleResizeEb","espp::Cli::SetHandleResize::handle_resize"],[11,3,1,"_CPPv4N4espp3Cli15SetInputHistoryERKN9LineInput7HistoryE","espp::Cli::SetInputHistory"],[11,4,1,"_CPPv4N4espp3Cli15SetInputHistoryERKN9LineInput7HistoryE","espp::Cli::SetInputHistory::history"],[11,3,1,"_CPPv4N4espp3Cli19SetInputHistorySizeE6size_t","espp::Cli::SetInputHistorySize"],[11,4,1,"_CPPv4N4espp3Cli19SetInputHistorySizeE6size_t","espp::Cli::SetInputHistorySize::history_size"],[11,3,1,"_CPPv4N4espp3Cli5StartEv","espp::Cli::Start"],[11,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"],[13,2,1,"_CPPv4N4espp10ControllerE","espp::Controller"],[13,2,1,"_CPPv4N4espp10Controller20AnalogJoystickConfigE","espp::Controller::AnalogJoystickConfig"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig10active_lowE","espp::Controller::AnalogJoystickConfig::active_low"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_aE","espp::Controller::AnalogJoystickConfig::gpio_a"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_bE","espp::Controller::AnalogJoystickConfig::gpio_b"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig20gpio_joystick_selectE","espp::Controller::AnalogJoystickConfig::gpio_joystick_select"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig11gpio_selectE","espp::Controller::AnalogJoystickConfig::gpio_select"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig10gpio_startE","espp::Controller::AnalogJoystickConfig::gpio_start"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_xE","espp::Controller::AnalogJoystickConfig::gpio_x"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig6gpio_yE","espp::Controller::AnalogJoystickConfig::gpio_y"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig15joystick_configE","espp::Controller::AnalogJoystickConfig::joystick_config"],[13,1,1,"_CPPv4N4espp10Controller20AnalogJoystickConfig9log_levelE","espp::Controller::AnalogJoystickConfig::log_level"],[13,6,1,"_CPPv4N4espp10Controller6ButtonE","espp::Controller::Button"],[13,7,1,"_CPPv4N4espp10Controller6Button1AE","espp::Controller::Button::A"],[13,7,1,"_CPPv4N4espp10Controller6Button1BE","espp::Controller::Button::B"],[13,7,1,"_CPPv4N4espp10Controller6Button4DOWNE","espp::Controller::Button::DOWN"],[13,7,1,"_CPPv4N4espp10Controller6Button15JOYSTICK_SELECTE","espp::Controller::Button::JOYSTICK_SELECT"],[13,7,1,"_CPPv4N4espp10Controller6Button11LAST_UNUSEDE","espp::Controller::Button::LAST_UNUSED"],[13,7,1,"_CPPv4N4espp10Controller6Button4LEFTE","espp::Controller::Button::LEFT"],[13,7,1,"_CPPv4N4espp10Controller6Button5RIGHTE","espp::Controller::Button::RIGHT"],[13,7,1,"_CPPv4N4espp10Controller6Button6SELECTE","espp::Controller::Button::SELECT"],[13,7,1,"_CPPv4N4espp10Controller6Button5STARTE","espp::Controller::Button::START"],[13,7,1,"_CPPv4N4espp10Controller6Button2UPE","espp::Controller::Button::UP"],[13,7,1,"_CPPv4N4espp10Controller6Button1XE","espp::Controller::Button::X"],[13,7,1,"_CPPv4N4espp10Controller6Button1YE","espp::Controller::Button::Y"],[13,3,1,"_CPPv4N4espp10Controller10ControllerERK10DualConfig","espp::Controller::Controller"],[13,3,1,"_CPPv4N4espp10Controller10ControllerERK13DigitalConfig","espp::Controller::Controller"],[13,3,1,"_CPPv4N4espp10Controller10ControllerERK20AnalogJoystickConfig","espp::Controller::Controller"],[13,4,1,"_CPPv4N4espp10Controller10ControllerERK10DualConfig","espp::Controller::Controller::config"],[13,4,1,"_CPPv4N4espp10Controller10ControllerERK13DigitalConfig","espp::Controller::Controller::config"],[13,4,1,"_CPPv4N4espp10Controller10ControllerERK20AnalogJoystickConfig","espp::Controller::Controller::config"],[13,2,1,"_CPPv4N4espp10Controller13DigitalConfigE","espp::Controller::DigitalConfig"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig10active_lowE","espp::Controller::DigitalConfig::active_low"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_aE","espp::Controller::DigitalConfig::gpio_a"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_bE","espp::Controller::DigitalConfig::gpio_b"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig9gpio_downE","espp::Controller::DigitalConfig::gpio_down"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig9gpio_leftE","espp::Controller::DigitalConfig::gpio_left"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig10gpio_rightE","espp::Controller::DigitalConfig::gpio_right"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig11gpio_selectE","espp::Controller::DigitalConfig::gpio_select"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig10gpio_startE","espp::Controller::DigitalConfig::gpio_start"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig7gpio_upE","espp::Controller::DigitalConfig::gpio_up"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_xE","espp::Controller::DigitalConfig::gpio_x"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig6gpio_yE","espp::Controller::DigitalConfig::gpio_y"],[13,1,1,"_CPPv4N4espp10Controller13DigitalConfig9log_levelE","espp::Controller::DigitalConfig::log_level"],[13,2,1,"_CPPv4N4espp10Controller10DualConfigE","espp::Controller::DualConfig"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig10active_lowE","espp::Controller::DualConfig::active_low"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_aE","espp::Controller::DualConfig::gpio_a"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_bE","espp::Controller::DualConfig::gpio_b"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig9gpio_downE","espp::Controller::DualConfig::gpio_down"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig20gpio_joystick_selectE","espp::Controller::DualConfig::gpio_joystick_select"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig9gpio_leftE","espp::Controller::DualConfig::gpio_left"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig10gpio_rightE","espp::Controller::DualConfig::gpio_right"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig11gpio_selectE","espp::Controller::DualConfig::gpio_select"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig10gpio_startE","espp::Controller::DualConfig::gpio_start"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig7gpio_upE","espp::Controller::DualConfig::gpio_up"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_xE","espp::Controller::DualConfig::gpio_x"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig6gpio_yE","espp::Controller::DualConfig::gpio_y"],[13,1,1,"_CPPv4N4espp10Controller10DualConfig9log_levelE","espp::Controller::DualConfig::log_level"],[13,2,1,"_CPPv4N4espp10Controller5StateE","espp::Controller::State"],[13,1,1,"_CPPv4N4espp10Controller5State1aE","espp::Controller::State::a"],[13,1,1,"_CPPv4N4espp10Controller5State1bE","espp::Controller::State::b"],[13,1,1,"_CPPv4N4espp10Controller5State4downE","espp::Controller::State::down"],[13,1,1,"_CPPv4N4espp10Controller5State15joystick_selectE","espp::Controller::State::joystick_select"],[13,1,1,"_CPPv4N4espp10Controller5State4leftE","espp::Controller::State::left"],[13,1,1,"_CPPv4N4espp10Controller5State5rightE","espp::Controller::State::right"],[13,1,1,"_CPPv4N4espp10Controller5State6selectE","espp::Controller::State::select"],[13,1,1,"_CPPv4N4espp10Controller5State5startE","espp::Controller::State::start"],[13,1,1,"_CPPv4N4espp10Controller5State2upE","espp::Controller::State::up"],[13,1,1,"_CPPv4N4espp10Controller5State1xE","espp::Controller::State::x"],[13,1,1,"_CPPv4N4espp10Controller5State1yE","espp::Controller::State::y"],[13,3,1,"_CPPv4N4espp10Controller9get_stateEv","espp::Controller::get_state"],[13,3,1,"_CPPv4N4espp10Controller10is_pressedEK6Button","espp::Controller::is_pressed"],[13,4,1,"_CPPv4N4espp10Controller10is_pressedEK6Button","espp::Controller::is_pressed::input"],[13,3,1,"_CPPv4N4espp10Controller6updateEv","espp::Controller::update"],[13,3,1,"_CPPv4N4espp10ControllerD0Ev","espp::Controller::~Controller"],[15,2,1,"_CPPv4N4espp7DisplayE","espp::Display"],[15,2,1,"_CPPv4N4espp7Display16AllocatingConfigE","espp::Display::AllocatingConfig"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig16allocation_flagsE","espp::Display::AllocatingConfig::allocation_flags"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig18backlight_on_valueE","espp::Display::AllocatingConfig::backlight_on_value"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig13backlight_pinE","espp::Display::AllocatingConfig::backlight_pin"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig15double_bufferedE","espp::Display::AllocatingConfig::double_buffered"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig14flush_callbackE","espp::Display::AllocatingConfig::flush_callback"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig6heightE","espp::Display::AllocatingConfig::height"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig9log_levelE","espp::Display::AllocatingConfig::log_level"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig17pixel_buffer_sizeE","espp::Display::AllocatingConfig::pixel_buffer_size"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig8rotationE","espp::Display::AllocatingConfig::rotation"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig25software_rotation_enabledE","espp::Display::AllocatingConfig::software_rotation_enabled"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig13update_periodE","espp::Display::AllocatingConfig::update_period"],[15,1,1,"_CPPv4N4espp7Display16AllocatingConfig5widthE","espp::Display::AllocatingConfig::width"],[15,3,1,"_CPPv4N4espp7Display7DisplayERK16AllocatingConfig","espp::Display::Display"],[15,3,1,"_CPPv4N4espp7Display7DisplayERK19NonAllocatingConfig","espp::Display::Display"],[15,4,1,"_CPPv4N4espp7Display7DisplayERK16AllocatingConfig","espp::Display::Display::config"],[15,4,1,"_CPPv4N4espp7Display7DisplayERK19NonAllocatingConfig","espp::Display::Display::config"],[15,2,1,"_CPPv4N4espp7Display19NonAllocatingConfigE","espp::Display::NonAllocatingConfig"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig18backlight_on_valueE","espp::Display::NonAllocatingConfig::backlight_on_value"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig13backlight_pinE","espp::Display::NonAllocatingConfig::backlight_pin"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig14flush_callbackE","espp::Display::NonAllocatingConfig::flush_callback"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig6heightE","espp::Display::NonAllocatingConfig::height"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig9log_levelE","espp::Display::NonAllocatingConfig::log_level"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig17pixel_buffer_sizeE","espp::Display::NonAllocatingConfig::pixel_buffer_size"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig8rotationE","espp::Display::NonAllocatingConfig::rotation"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig25software_rotation_enabledE","espp::Display::NonAllocatingConfig::software_rotation_enabled"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig13update_periodE","espp::Display::NonAllocatingConfig::update_period"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig5vram0E","espp::Display::NonAllocatingConfig::vram0"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig5vram1E","espp::Display::NonAllocatingConfig::vram1"],[15,1,1,"_CPPv4N4espp7Display19NonAllocatingConfig5widthE","espp::Display::NonAllocatingConfig::width"],[15,6,1,"_CPPv4N4espp7Display8RotationE","espp::Display::Rotation"],[15,7,1,"_CPPv4N4espp7Display8Rotation9LANDSCAPEE","espp::Display::Rotation::LANDSCAPE"],[15,7,1,"_CPPv4N4espp7Display8Rotation18LANDSCAPE_INVERTEDE","espp::Display::Rotation::LANDSCAPE_INVERTED"],[15,7,1,"_CPPv4N4espp7Display8Rotation8PORTRAITE","espp::Display::Rotation::PORTRAIT"],[15,7,1,"_CPPv4N4espp7Display8Rotation17PORTRAIT_INVERTEDE","espp::Display::Rotation::PORTRAIT_INVERTED"],[15,6,1,"_CPPv4N4espp7Display6SignalE","espp::Display::Signal"],[15,7,1,"_CPPv4N4espp7Display6Signal5FLUSHE","espp::Display::Signal::FLUSH"],[15,7,1,"_CPPv4N4espp7Display6Signal4NONEE","espp::Display::Signal::NONE"],[15,8,1,"_CPPv4N4espp7Display8flush_fnE","espp::Display::flush_fn"],[15,3,1,"_CPPv4NK4espp7Display13force_refreshEv","espp::Display::force_refresh"],[15,3,1,"_CPPv4NK4espp7Display14get_brightnessEv","espp::Display::get_brightness"],[15,3,1,"_CPPv4NK4espp7Display6heightEv","espp::Display::height"],[15,3,1,"_CPPv4N4espp7Display5pauseEv","espp::Display::pause"],[15,3,1,"_CPPv4N4espp7Display6resumeEv","espp::Display::resume"],[15,3,1,"_CPPv4N4espp7Display14set_brightnessEf","espp::Display::set_brightness"],[15,4,1,"_CPPv4N4espp7Display14set_brightnessEf","espp::Display::set_brightness::brightness"],[15,3,1,"_CPPv4N4espp7Display5vram0Ev","espp::Display::vram0"],[15,3,1,"_CPPv4N4espp7Display5vram1Ev","espp::Display::vram1"],[15,3,1,"_CPPv4NK4espp7Display15vram_size_bytesEv","espp::Display::vram_size_bytes"],[15,3,1,"_CPPv4NK4espp7Display12vram_size_pxEv","espp::Display::vram_size_px"],[15,3,1,"_CPPv4NK4espp7Display5widthEv","espp::Display::width"],[15,3,1,"_CPPv4N4espp7DisplayD0Ev","espp::Display::~Display"],[34,2,1,"_CPPv4N4espp7Drv2605E","espp::Drv2605"],[34,2,1,"_CPPv4N4espp7Drv26056ConfigE","espp::Drv2605::Config"],[34,1,1,"_CPPv4N4espp7Drv26056Config9auto_initE","espp::Drv2605::Config::auto_init"],[34,1,1,"_CPPv4N4espp7Drv26056Config14device_addressE","espp::Drv2605::Config::device_address"],[34,1,1,"_CPPv4N4espp7Drv26056Config9log_levelE","espp::Drv2605::Config::log_level"],[34,1,1,"_CPPv4N4espp7Drv26056Config10motor_typeE","espp::Drv2605::Config::motor_type"],[34,1,1,"_CPPv4N4espp7Drv26056Config4readE","espp::Drv2605::Config::read"],[34,1,1,"_CPPv4N4espp7Drv26056Config5writeE","espp::Drv2605::Config::write"],[34,3,1,"_CPPv4N4espp7Drv26057Drv2605ERK6Config","espp::Drv2605::Drv2605"],[34,4,1,"_CPPv4N4espp7Drv26057Drv2605ERK6Config","espp::Drv2605::Drv2605::config"],[34,6,1,"_CPPv4N4espp7Drv26057LibraryE","espp::Drv2605::Library"],[34,7,1,"_CPPv4N4espp7Drv26057Library5EMPTYE","espp::Drv2605::Library::EMPTY"],[34,7,1,"_CPPv4N4espp7Drv26057Library5ERM_0E","espp::Drv2605::Library::ERM_0"],[34,7,1,"_CPPv4N4espp7Drv26057Library5ERM_1E","espp::Drv2605::Library::ERM_1"],[34,7,1,"_CPPv4N4espp7Drv26057Library5ERM_2E","espp::Drv2605::Library::ERM_2"],[34,7,1,"_CPPv4N4espp7Drv26057Library5ERM_3E","espp::Drv2605::Library::ERM_3"],[34,7,1,"_CPPv4N4espp7Drv26057Library5ERM_4E","espp::Drv2605::Library::ERM_4"],[34,7,1,"_CPPv4N4espp7Drv26057Library3LRAE","espp::Drv2605::Library::LRA"],[34,6,1,"_CPPv4N4espp7Drv26054ModeE","espp::Drv2605::Mode"],[34,7,1,"_CPPv4N4espp7Drv26054Mode9AUDIOVIBEE","espp::Drv2605::Mode::AUDIOVIBE"],[34,7,1,"_CPPv4N4espp7Drv26054Mode7AUTOCALE","espp::Drv2605::Mode::AUTOCAL"],[34,7,1,"_CPPv4N4espp7Drv26054Mode7DIAGNOSE","espp::Drv2605::Mode::DIAGNOS"],[34,7,1,"_CPPv4N4espp7Drv26054Mode11EXTTRIGEDGEE","espp::Drv2605::Mode::EXTTRIGEDGE"],[34,7,1,"_CPPv4N4espp7Drv26054Mode10EXTTRIGLVLE","espp::Drv2605::Mode::EXTTRIGLVL"],[34,7,1,"_CPPv4N4espp7Drv26054Mode7INTTRIGE","espp::Drv2605::Mode::INTTRIG"],[34,7,1,"_CPPv4N4espp7Drv26054Mode9PWMANALOGE","espp::Drv2605::Mode::PWMANALOG"],[34,7,1,"_CPPv4N4espp7Drv26054Mode8REALTIMEE","espp::Drv2605::Mode::REALTIME"],[34,6,1,"_CPPv4N4espp7Drv26059MotorTypeE","espp::Drv2605::MotorType"],[34,7,1,"_CPPv4N4espp7Drv26059MotorType3ERME","espp::Drv2605::MotorType::ERM"],[34,7,1,"_CPPv4N4espp7Drv26059MotorType3LRAE","espp::Drv2605::MotorType::LRA"],[34,6,1,"_CPPv4N4espp7Drv26058WaveformE","espp::Drv2605::Waveform"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform12ALERT_1000MSE","espp::Drv2605::Waveform::ALERT_1000MS"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform11ALERT_750MSE","espp::Drv2605::Waveform::ALERT_750MS"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ1E","espp::Drv2605::Waveform::BUZZ1"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ2E","espp::Drv2605::Waveform::BUZZ2"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ3E","espp::Drv2605::Waveform::BUZZ3"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ4E","espp::Drv2605::Waveform::BUZZ4"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform5BUZZ5E","espp::Drv2605::Waveform::BUZZ5"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform12DOUBLE_CLICKE","espp::Drv2605::Waveform::DOUBLE_CLICK"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform3ENDE","espp::Drv2605::Waveform::END"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform3MAXE","espp::Drv2605::Waveform::MAX"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform16PULSING_STRONG_1E","espp::Drv2605::Waveform::PULSING_STRONG_1"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform16PULSING_STRONG_2E","espp::Drv2605::Waveform::PULSING_STRONG_2"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform11SHARP_CLICKE","espp::Drv2605::Waveform::SHARP_CLICK"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform9SOFT_BUMPE","espp::Drv2605::Waveform::SOFT_BUMP"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform9SOFT_FUZZE","espp::Drv2605::Waveform::SOFT_FUZZ"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform11STRONG_BUZZE","espp::Drv2605::Waveform::STRONG_BUZZ"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform12STRONG_CLICKE","espp::Drv2605::Waveform::STRONG_CLICK"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform18TRANSITION_CLICK_1E","espp::Drv2605::Waveform::TRANSITION_CLICK_1"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform16TRANSITION_HUM_1E","espp::Drv2605::Waveform::TRANSITION_HUM_1"],[34,7,1,"_CPPv4N4espp7Drv26058Waveform12TRIPLE_CLICKE","espp::Drv2605::Waveform::TRIPLE_CLICK"],[34,3,1,"_CPPv4N4espp7Drv26059initalizeERNSt10error_codeE","espp::Drv2605::initalize"],[34,4,1,"_CPPv4N4espp7Drv26059initalizeERNSt10error_codeE","espp::Drv2605::initalize::ec"],[34,8,1,"_CPPv4N4espp7Drv26057read_fnE","espp::Drv2605::read_fn"],[34,3,1,"_CPPv4N4espp7Drv260514select_libraryE7LibraryRNSt10error_codeE","espp::Drv2605::select_library"],[34,4,1,"_CPPv4N4espp7Drv260514select_libraryE7LibraryRNSt10error_codeE","espp::Drv2605::select_library::ec"],[34,4,1,"_CPPv4N4espp7Drv260514select_libraryE7LibraryRNSt10error_codeE","espp::Drv2605::select_library::lib"],[34,3,1,"_CPPv4N4espp7Drv26058set_modeE4ModeRNSt10error_codeE","espp::Drv2605::set_mode"],[34,4,1,"_CPPv4N4espp7Drv26058set_modeE4ModeRNSt10error_codeE","espp::Drv2605::set_mode::ec"],[34,4,1,"_CPPv4N4espp7Drv26058set_modeE4ModeRNSt10error_codeE","espp::Drv2605::set_mode::mode"],[34,3,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8WaveformRNSt10error_codeE","espp::Drv2605::set_waveform"],[34,4,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8WaveformRNSt10error_codeE","espp::Drv2605::set_waveform::ec"],[34,4,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8WaveformRNSt10error_codeE","espp::Drv2605::set_waveform::slot"],[34,4,1,"_CPPv4N4espp7Drv260512set_waveformE7uint8_t8WaveformRNSt10error_codeE","espp::Drv2605::set_waveform::w"],[34,3,1,"_CPPv4N4espp7Drv26055startERNSt10error_codeE","espp::Drv2605::start"],[34,4,1,"_CPPv4N4espp7Drv26055startERNSt10error_codeE","espp::Drv2605::start::ec"],[34,3,1,"_CPPv4N4espp7Drv26054stopERNSt10error_codeE","espp::Drv2605::stop"],[34,4,1,"_CPPv4N4espp7Drv26054stopERNSt10error_codeE","espp::Drv2605::stop::ec"],[34,8,1,"_CPPv4N4espp7Drv26058write_fnE","espp::Drv2605::write_fn"],[38,2,1,"_CPPv4N4espp12EncoderInputE","espp::EncoderInput"],[38,2,1,"_CPPv4N4espp12EncoderInput6ConfigE","espp::EncoderInput::Config"],[38,1,1,"_CPPv4N4espp12EncoderInput6Config9log_levelE","espp::EncoderInput::Config::log_level"],[38,1,1,"_CPPv4N4espp12EncoderInput6Config4readE","espp::EncoderInput::Config::read"],[38,3,1,"_CPPv4N4espp12EncoderInput12EncoderInputERK6Config","espp::EncoderInput::EncoderInput"],[38,4,1,"_CPPv4N4espp12EncoderInput12EncoderInputERK6Config","espp::EncoderInput::EncoderInput::config"],[38,3,1,"_CPPv4N4espp12EncoderInput23get_button_input_deviceEv","espp::EncoderInput::get_button_input_device"],[38,3,1,"_CPPv4N4espp12EncoderInput24get_encoder_input_deviceEv","espp::EncoderInput::get_encoder_input_device"],[38,3,1,"_CPPv4N4espp12EncoderInputD0Ev","espp::EncoderInput::~EncoderInput"],[23,2,1,"_CPPv4N4espp12EventManagerE","espp::EventManager"],[23,3,1,"_CPPv4N4espp12EventManager13add_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::add_publisher"],[23,4,1,"_CPPv4N4espp12EventManager13add_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::add_publisher::component"],[23,4,1,"_CPPv4N4espp12EventManager13add_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::add_publisher::topic"],[23,3,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fnK6size_t","espp::EventManager::add_subscriber"],[23,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fnK6size_t","espp::EventManager::add_subscriber::callback"],[23,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fnK6size_t","espp::EventManager::add_subscriber::component"],[23,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fnK6size_t","espp::EventManager::add_subscriber::stack_size_bytes"],[23,4,1,"_CPPv4N4espp12EventManager14add_subscriberERKNSt6stringERKNSt6stringERK17event_callback_fnK6size_t","espp::EventManager::add_subscriber::topic"],[23,8,1,"_CPPv4N4espp12EventManager17event_callback_fnE","espp::EventManager::event_callback_fn"],[23,3,1,"_CPPv4N4espp12EventManager3getEv","espp::EventManager::get"],[23,3,1,"_CPPv4N4espp12EventManager7publishERKNSt6stringERKNSt6vectorI7uint8_tEE","espp::EventManager::publish"],[23,4,1,"_CPPv4N4espp12EventManager7publishERKNSt6stringERKNSt6vectorI7uint8_tEE","espp::EventManager::publish::data"],[23,4,1,"_CPPv4N4espp12EventManager7publishERKNSt6stringERKNSt6vectorI7uint8_tEE","espp::EventManager::publish::topic"],[23,3,1,"_CPPv4N4espp12EventManager16remove_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::remove_publisher"],[23,4,1,"_CPPv4N4espp12EventManager16remove_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::remove_publisher::component"],[23,4,1,"_CPPv4N4espp12EventManager16remove_publisherERKNSt6stringERKNSt6stringE","espp::EventManager::remove_publisher::topic"],[23,3,1,"_CPPv4N4espp12EventManager17remove_subscriberERKNSt6stringERKNSt6stringE","espp::EventManager::remove_subscriber"],[23,4,1,"_CPPv4N4espp12EventManager17remove_subscriberERKNSt6stringERKNSt6stringE","espp::EventManager::remove_subscriber::component"],[23,4,1,"_CPPv4N4espp12EventManager17remove_subscriberERKNSt6stringERKNSt6stringE","espp::EventManager::remove_subscriber::topic"],[23,3,1,"_CPPv4N4espp12EventManager13set_log_levelEN6Logger9VerbosityE","espp::EventManager::set_log_level"],[23,4,1,"_CPPv4N4espp12EventManager13set_log_levelEN6Logger9VerbosityE","espp::EventManager::set_log_level::level"],[24,2,1,"_CPPv4N4espp10FileSystemE","espp::FileSystem"],[24,2,1,"_CPPv4N4espp10FileSystem10ListConfigE","espp::FileSystem::ListConfig"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig9date_timeE","espp::FileSystem::ListConfig::date_time"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig5groupE","espp::FileSystem::ListConfig::group"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig15number_of_linksE","espp::FileSystem::ListConfig::number_of_links"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig5ownerE","espp::FileSystem::ListConfig::owner"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig11permissionsE","espp::FileSystem::ListConfig::permissions"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig9recursiveE","espp::FileSystem::ListConfig::recursive"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig4sizeE","espp::FileSystem::ListConfig::size"],[24,1,1,"_CPPv4N4espp10FileSystem10ListConfig4typeE","espp::FileSystem::ListConfig::type"],[24,3,1,"_CPPv4N4espp10FileSystem3getEv","espp::FileSystem::get"],[24,3,1,"_CPPv4N4espp10FileSystem14get_free_spaceEv","espp::FileSystem::get_free_space"],[24,3,1,"_CPPv4N4espp10FileSystem15get_mount_pointEv","espp::FileSystem::get_mount_point"],[24,3,1,"_CPPv4N4espp10FileSystem19get_partition_labelEv","espp::FileSystem::get_partition_label"],[24,3,1,"_CPPv4N4espp10FileSystem13get_root_pathEv","espp::FileSystem::get_root_path"],[24,3,1,"_CPPv4N4espp10FileSystem15get_total_spaceEv","espp::FileSystem::get_total_space"],[24,3,1,"_CPPv4N4espp10FileSystem14get_used_spaceEv","espp::FileSystem::get_used_space"],[24,3,1,"_CPPv4N4espp10FileSystem14human_readableE6size_t","espp::FileSystem::human_readable"],[24,4,1,"_CPPv4N4espp10FileSystem14human_readableE6size_t","espp::FileSystem::human_readable::bytes"],[24,3,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory"],[24,3,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory"],[24,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::config"],[24,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::config"],[24,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::path"],[24,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::path"],[24,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt10filesystem4pathERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::prefix"],[24,4,1,"_CPPv4N4espp10FileSystem14list_directoryERKNSt6stringERK10ListConfigRKNSt6stringE","espp::FileSystem::list_directory::prefix"],[24,3,1,"_CPPv4I0EN4espp10FileSystem9to_time_tENSt6time_tE2TP","espp::FileSystem::to_time_t"],[24,5,1,"_CPPv4I0EN4espp10FileSystem9to_time_tENSt6time_tE2TP","espp::FileSystem::to_time_t::TP"],[24,4,1,"_CPPv4I0EN4espp10FileSystem9to_time_tENSt6time_tE2TP","espp::FileSystem::to_time_t::tp"],[39,2,1,"_CPPv4N4espp6Ft5x06E","espp::Ft5x06"],[39,2,1,"_CPPv4N4espp6Ft5x066ConfigE","espp::Ft5x06::Config"],[39,1,1,"_CPPv4N4espp6Ft5x066Config9log_levelE","espp::Ft5x06::Config::log_level"],[39,1,1,"_CPPv4N4espp6Ft5x066Config16read_at_registerE","espp::Ft5x06::Config::read_at_register"],[39,1,1,"_CPPv4N4espp6Ft5x066Config5writeE","espp::Ft5x06::Config::write"],[39,1,1,"_CPPv4N4espp6Ft5x0615DEFAULT_ADDRESSE","espp::Ft5x06::DEFAULT_ADDRESS"],[39,3,1,"_CPPv4N4espp6Ft5x066Ft5x06ERK6Config","espp::Ft5x06::Ft5x06"],[39,4,1,"_CPPv4N4espp6Ft5x066Ft5x06ERK6Config","espp::Ft5x06::Ft5x06::config"],[39,6,1,"_CPPv4N4espp6Ft5x067GestureE","espp::Ft5x06::Gesture"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture9MOVE_DOWNE","espp::Ft5x06::Gesture::MOVE_DOWN"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture9MOVE_LEFTE","espp::Ft5x06::Gesture::MOVE_LEFT"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture10MOVE_RIGHTE","espp::Ft5x06::Gesture::MOVE_RIGHT"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture7MOVE_UPE","espp::Ft5x06::Gesture::MOVE_UP"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture4NONEE","espp::Ft5x06::Gesture::NONE"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture7ZOOM_INE","espp::Ft5x06::Gesture::ZOOM_IN"],[39,7,1,"_CPPv4N4espp6Ft5x067Gesture8ZOOM_OUTE","espp::Ft5x06::Gesture::ZOOM_OUT"],[39,3,1,"_CPPv4N4espp6Ft5x0620get_num_touch_pointsERNSt10error_codeE","espp::Ft5x06::get_num_touch_points"],[39,4,1,"_CPPv4N4espp6Ft5x0620get_num_touch_pointsERNSt10error_codeE","espp::Ft5x06::get_num_touch_points::ec"],[39,3,1,"_CPPv4N4espp6Ft5x0615get_touch_pointEP7uint8_tP8uint16_tP8uint16_tRNSt10error_codeE","espp::Ft5x06::get_touch_point"],[39,4,1,"_CPPv4N4espp6Ft5x0615get_touch_pointEP7uint8_tP8uint16_tP8uint16_tRNSt10error_codeE","espp::Ft5x06::get_touch_point::ec"],[39,4,1,"_CPPv4N4espp6Ft5x0615get_touch_pointEP7uint8_tP8uint16_tP8uint16_tRNSt10error_codeE","espp::Ft5x06::get_touch_point::num_touch_points"],[39,4,1,"_CPPv4N4espp6Ft5x0615get_touch_pointEP7uint8_tP8uint16_tP8uint16_tRNSt10error_codeE","espp::Ft5x06::get_touch_point::x"],[39,4,1,"_CPPv4N4espp6Ft5x0615get_touch_pointEP7uint8_tP8uint16_tP8uint16_tRNSt10error_codeE","espp::Ft5x06::get_touch_point::y"],[39,8,1,"_CPPv4N4espp6Ft5x0619read_at_register_fnE","espp::Ft5x06::read_at_register_fn"],[39,3,1,"_CPPv4N4espp6Ft5x0612read_gestureERNSt10error_codeE","espp::Ft5x06::read_gesture"],[39,4,1,"_CPPv4N4espp6Ft5x0612read_gestureERNSt10error_codeE","espp::Ft5x06::read_gesture::ec"],[39,8,1,"_CPPv4N4espp6Ft5x068write_fnE","espp::Ft5x06::write_fn"],[31,2,1,"_CPPv4N4espp16FtpClientSessionE","espp::FtpClientSession"],[31,3,1,"_CPPv4NK4espp16FtpClientSession17current_directoryEv","espp::FtpClientSession::current_directory"],[31,3,1,"_CPPv4NK4espp16FtpClientSession2idEv","espp::FtpClientSession::id"],[31,3,1,"_CPPv4NK4espp16FtpClientSession8is_aliveEv","espp::FtpClientSession::is_alive"],[31,3,1,"_CPPv4NK4espp16FtpClientSession12is_connectedEv","espp::FtpClientSession::is_connected"],[31,3,1,"_CPPv4NK4espp16FtpClientSession26is_passive_data_connectionEv","espp::FtpClientSession::is_passive_data_connection"],[31,2,1,"_CPPv4N4espp9FtpServerE","espp::FtpServer"],[31,3,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer"],[31,4,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer::ip_address"],[31,4,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer::port"],[31,4,1,"_CPPv4N4espp9FtpServer9FtpServerENSt11string_viewE8uint16_tRKNSt10filesystem4pathE","espp::FtpServer::FtpServer::root"],[31,3,1,"_CPPv4N4espp9FtpServer5startEv","espp::FtpServer::start"],[31,3,1,"_CPPv4N4espp9FtpServer4stopEv","espp::FtpServer::stop"],[31,3,1,"_CPPv4N4espp9FtpServerD0Ev","espp::FtpServer::~FtpServer"],[55,2,1,"_CPPv4N4espp8GaussianE","espp::Gaussian"],[55,2,1,"_CPPv4N4espp8Gaussian6ConfigE","espp::Gaussian::Config"],[55,1,1,"_CPPv4N4espp8Gaussian6Config5alphaE","espp::Gaussian::Config::alpha"],[55,1,1,"_CPPv4N4espp8Gaussian6Config4betaE","espp::Gaussian::Config::beta"],[55,1,1,"_CPPv4N4espp8Gaussian6Config5gammaE","espp::Gaussian::Config::gamma"],[55,3,1,"_CPPv4N4espp8Gaussian8GaussianERK6Config","espp::Gaussian::Gaussian"],[55,4,1,"_CPPv4N4espp8Gaussian8GaussianERK6Config","espp::Gaussian::Gaussian::config"],[55,3,1,"_CPPv4N4espp8Gaussian5alphaEf","espp::Gaussian::alpha"],[55,3,1,"_CPPv4NK4espp8Gaussian5alphaEv","espp::Gaussian::alpha"],[55,4,1,"_CPPv4N4espp8Gaussian5alphaEf","espp::Gaussian::alpha::a"],[55,3,1,"_CPPv4NK4espp8Gaussian2atEf","espp::Gaussian::at"],[55,4,1,"_CPPv4NK4espp8Gaussian2atEf","espp::Gaussian::at::t"],[55,3,1,"_CPPv4N4espp8Gaussian4betaEf","espp::Gaussian::beta"],[55,3,1,"_CPPv4NK4espp8Gaussian4betaEv","espp::Gaussian::beta"],[55,4,1,"_CPPv4N4espp8Gaussian4betaEf","espp::Gaussian::beta::b"],[55,3,1,"_CPPv4N4espp8Gaussian5gammaEf","espp::Gaussian::gamma"],[55,3,1,"_CPPv4NK4espp8Gaussian5gammaEv","espp::Gaussian::gamma"],[55,4,1,"_CPPv4N4espp8Gaussian5gammaEf","espp::Gaussian::gamma::g"],[55,3,1,"_CPPv4NK4espp8GaussianclEf","espp::Gaussian::operator()"],[55,4,1,"_CPPv4NK4espp8GaussianclEf","espp::Gaussian::operator()::t"],[40,2,1,"_CPPv4N4espp5Gt911E","espp::Gt911"],[40,2,1,"_CPPv4N4espp5Gt9116ConfigE","espp::Gt911::Config"],[40,1,1,"_CPPv4N4espp5Gt9116Config7addressE","espp::Gt911::Config::address"],[40,1,1,"_CPPv4N4espp5Gt9116Config9log_levelE","espp::Gt911::Config::log_level"],[40,1,1,"_CPPv4N4espp5Gt9116Config5writeE","espp::Gt911::Config::write"],[40,1,1,"_CPPv4N4espp5Gt9116Config10write_readE","espp::Gt911::Config::write_read"],[40,1,1,"_CPPv4N4espp5Gt91117DEFAULT_ADDRESS_1E","espp::Gt911::DEFAULT_ADDRESS_1"],[40,1,1,"_CPPv4N4espp5Gt91117DEFAULT_ADDRESS_2E","espp::Gt911::DEFAULT_ADDRESS_2"],[40,3,1,"_CPPv4N4espp5Gt9115Gt911ERK6Config","espp::Gt911::Gt911"],[40,4,1,"_CPPv4N4espp5Gt9115Gt911ERK6Config","espp::Gt911::Gt911::config"],[40,3,1,"_CPPv4NK4espp5Gt91121get_home_button_stateEv","espp::Gt911::get_home_button_state"],[40,3,1,"_CPPv4NK4espp5Gt91120get_num_touch_pointsEv","espp::Gt911::get_num_touch_points"],[40,3,1,"_CPPv4NK4espp5Gt91115get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Gt911::get_touch_point"],[40,4,1,"_CPPv4NK4espp5Gt91115get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Gt911::get_touch_point::num_touch_points"],[40,4,1,"_CPPv4NK4espp5Gt91115get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Gt911::get_touch_point::x"],[40,4,1,"_CPPv4NK4espp5Gt91115get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Gt911::get_touch_point::y"],[40,3,1,"_CPPv4N4espp5Gt9116updateERNSt10error_codeE","espp::Gt911::update"],[40,4,1,"_CPPv4N4espp5Gt9116updateERNSt10error_codeE","espp::Gt911::update::ec"],[40,8,1,"_CPPv4N4espp5Gt9118write_fnE","espp::Gt911::write_fn"],[40,8,1,"_CPPv4N4espp5Gt91113write_read_fnE","espp::Gt911::write_read_fn"],[12,2,1,"_CPPv4N4espp3HsvE","espp::Hsv"],[12,3,1,"_CPPv4N4espp3Hsv3HsvERK3Hsv","espp::Hsv::Hsv"],[12,3,1,"_CPPv4N4espp3Hsv3HsvERK3Rgb","espp::Hsv::Hsv"],[12,3,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv"],[12,4,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv::h"],[12,4,1,"_CPPv4N4espp3Hsv3HsvERK3Hsv","espp::Hsv::Hsv::hsv"],[12,4,1,"_CPPv4N4espp3Hsv3HsvERK3Rgb","espp::Hsv::Hsv::rgb"],[12,4,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv::s"],[12,4,1,"_CPPv4N4espp3Hsv3HsvERKfRKfRKf","espp::Hsv::Hsv::v"],[12,1,1,"_CPPv4N4espp3Hsv1hE","espp::Hsv::h"],[12,3,1,"_CPPv4NK4espp3Hsv3rgbEv","espp::Hsv::rgb"],[12,1,1,"_CPPv4N4espp3Hsv1sE","espp::Hsv::s"],[12,1,1,"_CPPv4N4espp3Hsv1vE","espp::Hsv::v"],[36,2,1,"_CPPv4N4espp3I2cE","espp::I2c"],[36,2,1,"_CPPv4N4espp3I2c6ConfigE","espp::I2c::Config"],[36,1,1,"_CPPv4N4espp3I2c6Config9auto_initE","espp::I2c::Config::auto_init"],[36,1,1,"_CPPv4N4espp3I2c6Config9clk_speedE","espp::I2c::Config::clk_speed"],[36,1,1,"_CPPv4N4espp3I2c6Config9log_levelE","espp::I2c::Config::log_level"],[36,1,1,"_CPPv4N4espp3I2c6Config4portE","espp::I2c::Config::port"],[36,1,1,"_CPPv4N4espp3I2c6Config10scl_io_numE","espp::I2c::Config::scl_io_num"],[36,1,1,"_CPPv4N4espp3I2c6Config13scl_pullup_enE","espp::I2c::Config::scl_pullup_en"],[36,1,1,"_CPPv4N4espp3I2c6Config10sda_io_numE","espp::I2c::Config::sda_io_num"],[36,1,1,"_CPPv4N4espp3I2c6Config13sda_pullup_enE","espp::I2c::Config::sda_pullup_en"],[36,1,1,"_CPPv4N4espp3I2c6Config10timeout_msE","espp::I2c::Config::timeout_ms"],[36,3,1,"_CPPv4N4espp3I2c3I2cERK6Config","espp::I2c::I2c"],[36,4,1,"_CPPv4N4espp3I2c3I2cERK6Config","espp::I2c::I2c::config"],[36,3,1,"_CPPv4N4espp3I2c6deinitERNSt10error_codeE","espp::I2c::deinit"],[36,4,1,"_CPPv4N4espp3I2c6deinitERNSt10error_codeE","espp::I2c::deinit::ec"],[36,3,1,"_CPPv4N4espp3I2c4initERNSt10error_codeE","espp::I2c::init"],[36,4,1,"_CPPv4N4espp3I2c4initERNSt10error_codeE","espp::I2c::init::ec"],[36,3,1,"_CPPv4N4espp3I2c12probe_deviceE7uint8_t","espp::I2c::probe_device"],[36,4,1,"_CPPv4N4espp3I2c12probe_deviceE7uint8_t","espp::I2c::probe_device::dev_addr"],[36,3,1,"_CPPv4N4espp3I2c4readE7uint8_tP7uint8_t6size_t","espp::I2c::read"],[36,4,1,"_CPPv4N4espp3I2c4readE7uint8_tP7uint8_t6size_t","espp::I2c::read::data"],[36,4,1,"_CPPv4N4espp3I2c4readE7uint8_tP7uint8_t6size_t","espp::I2c::read::data_len"],[36,4,1,"_CPPv4N4espp3I2c4readE7uint8_tP7uint8_t6size_t","espp::I2c::read::dev_addr"],[36,3,1,"_CPPv4N4espp3I2c16read_at_registerE7uint8_t7uint8_tP7uint8_t6size_t","espp::I2c::read_at_register"],[36,4,1,"_CPPv4N4espp3I2c16read_at_registerE7uint8_t7uint8_tP7uint8_t6size_t","espp::I2c::read_at_register::data"],[36,4,1,"_CPPv4N4espp3I2c16read_at_registerE7uint8_t7uint8_tP7uint8_t6size_t","espp::I2c::read_at_register::data_len"],[36,4,1,"_CPPv4N4espp3I2c16read_at_registerE7uint8_t7uint8_tP7uint8_t6size_t","espp::I2c::read_at_register::dev_addr"],[36,4,1,"_CPPv4N4espp3I2c16read_at_registerE7uint8_t7uint8_tP7uint8_t6size_t","espp::I2c::read_at_register::reg_addr"],[36,3,1,"_CPPv4N4espp3I2c5writeE7uint8_tP7uint8_t6size_t","espp::I2c::write"],[36,4,1,"_CPPv4N4espp3I2c5writeE7uint8_tP7uint8_t6size_t","espp::I2c::write::data"],[36,4,1,"_CPPv4N4espp3I2c5writeE7uint8_tP7uint8_t6size_t","espp::I2c::write::data_len"],[36,4,1,"_CPPv4N4espp3I2c5writeE7uint8_tP7uint8_t6size_t","espp::I2c::write::dev_addr"],[36,3,1,"_CPPv4N4espp3I2c10write_readE7uint8_tP7uint8_t6size_tP7uint8_t6size_t","espp::I2c::write_read"],[36,4,1,"_CPPv4N4espp3I2c10write_readE7uint8_tP7uint8_t6size_tP7uint8_t6size_t","espp::I2c::write_read::dev_addr"],[36,4,1,"_CPPv4N4espp3I2c10write_readE7uint8_tP7uint8_t6size_tP7uint8_t6size_t","espp::I2c::write_read::read_data"],[36,4,1,"_CPPv4N4espp3I2c10write_readE7uint8_tP7uint8_t6size_tP7uint8_t6size_t","espp::I2c::write_read::read_size"],[36,4,1,"_CPPv4N4espp3I2c10write_readE7uint8_tP7uint8_t6size_tP7uint8_t6size_t","espp::I2c::write_read::write_data"],[36,4,1,"_CPPv4N4espp3I2c10write_readE7uint8_tP7uint8_t6size_tP7uint8_t6size_t","espp::I2c::write_read::write_size"],[16,2,1,"_CPPv4N4espp7Ili9341E","espp::Ili9341"],[16,3,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear"],[16,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::color"],[16,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::height"],[16,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::width"],[16,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::x"],[16,4,1,"_CPPv4N4espp7Ili93415clearE6size_t6size_t6size_t6size_t8uint16_t","espp::Ili9341::clear::y"],[16,3,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill"],[16,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::area"],[16,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::color_map"],[16,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::drv"],[16,4,1,"_CPPv4N4espp7Ili93414fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::Ili9341::fill::flags"],[16,3,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush"],[16,4,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush::area"],[16,4,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush::color_map"],[16,4,1,"_CPPv4N4espp7Ili93415flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::Ili9341::flush::drv"],[16,3,1,"_CPPv4N4espp7Ili934110get_offsetERiRi","espp::Ili9341::get_offset"],[16,4,1,"_CPPv4N4espp7Ili934110get_offsetERiRi","espp::Ili9341::get_offset::x"],[16,4,1,"_CPPv4N4espp7Ili934110get_offsetERiRi","espp::Ili9341::get_offset::y"],[16,3,1,"_CPPv4N4espp7Ili934110initializeERKN15display_drivers6ConfigE","espp::Ili9341::initialize"],[16,4,1,"_CPPv4N4espp7Ili934110initializeERKN15display_drivers6ConfigE","espp::Ili9341::initialize::config"],[16,3,1,"_CPPv4N4espp7Ili934112send_commandE7uint8_t","espp::Ili9341::send_command"],[16,4,1,"_CPPv4N4espp7Ili934112send_commandE7uint8_t","espp::Ili9341::send_command::command"],[16,3,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data"],[16,4,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data::data"],[16,4,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data::flags"],[16,4,1,"_CPPv4N4espp7Ili93419send_dataEPK7uint8_t6size_t8uint32_t","espp::Ili9341::send_data::length"],[16,3,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area"],[16,3,1,"_CPPv4N4espp7Ili934116set_drawing_areaEPK9lv_area_t","espp::Ili9341::set_drawing_area"],[16,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaEPK9lv_area_t","espp::Ili9341::set_drawing_area::area"],[16,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::xe"],[16,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::xs"],[16,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::ye"],[16,4,1,"_CPPv4N4espp7Ili934116set_drawing_areaE6size_t6size_t6size_t6size_t","espp::Ili9341::set_drawing_area::ys"],[16,3,1,"_CPPv4N4espp7Ili934110set_offsetEii","espp::Ili9341::set_offset"],[16,4,1,"_CPPv4N4espp7Ili934110set_offsetEii","espp::Ili9341::set_offset::x"],[16,4,1,"_CPPv4N4espp7Ili934110set_offsetEii","espp::Ili9341::set_offset::y"],[49,2,1,"_CPPv4N4espp8JoystickE","espp::Joystick"],[49,2,1,"_CPPv4N4espp8Joystick6ConfigE","espp::Joystick::Config"],[49,1,1,"_CPPv4N4espp8Joystick6Config8deadzoneE","espp::Joystick::Config::deadzone"],[49,1,1,"_CPPv4N4espp8Joystick6Config15deadzone_radiusE","espp::Joystick::Config::deadzone_radius"],[49,1,1,"_CPPv4N4espp8Joystick6Config10get_valuesE","espp::Joystick::Config::get_values"],[49,1,1,"_CPPv4N4espp8Joystick6Config9log_levelE","espp::Joystick::Config::log_level"],[49,1,1,"_CPPv4N4espp8Joystick6Config13x_calibrationE","espp::Joystick::Config::x_calibration"],[49,1,1,"_CPPv4N4espp8Joystick6Config13y_calibrationE","espp::Joystick::Config::y_calibration"],[49,6,1,"_CPPv4N4espp8Joystick8DeadzoneE","espp::Joystick::Deadzone"],[49,7,1,"_CPPv4N4espp8Joystick8Deadzone8CIRCULARE","espp::Joystick::Deadzone::CIRCULAR"],[49,7,1,"_CPPv4N4espp8Joystick8Deadzone11RECTANGULARE","espp::Joystick::Deadzone::RECTANGULAR"],[49,3,1,"_CPPv4N4espp8Joystick8JoystickERK6Config","espp::Joystick::Joystick"],[49,4,1,"_CPPv4N4espp8Joystick8JoystickERK6Config","espp::Joystick::Joystick::config"],[49,8,1,"_CPPv4N4espp8Joystick13get_values_fnE","espp::Joystick::get_values_fn"],[49,3,1,"_CPPv4NK4espp8Joystick8positionEv","espp::Joystick::position"],[49,3,1,"_CPPv4NK4espp8Joystick3rawEv","espp::Joystick::raw"],[49,3,1,"_CPPv4N4espp8Joystick15set_calibrationERKN16FloatRangeMapper6ConfigERKN16FloatRangeMapper6ConfigE","espp::Joystick::set_calibration"],[49,4,1,"_CPPv4N4espp8Joystick15set_calibrationERKN16FloatRangeMapper6ConfigERKN16FloatRangeMapper6ConfigE","espp::Joystick::set_calibration::x_calibration"],[49,4,1,"_CPPv4N4espp8Joystick15set_calibrationERKN16FloatRangeMapper6ConfigERKN16FloatRangeMapper6ConfigE","espp::Joystick::set_calibration::y_calibration"],[49,3,1,"_CPPv4N4espp8Joystick12set_deadzoneE8Deadzonef","espp::Joystick::set_deadzone"],[49,4,1,"_CPPv4N4espp8Joystick12set_deadzoneE8Deadzonef","espp::Joystick::set_deadzone::deadzone"],[49,4,1,"_CPPv4N4espp8Joystick12set_deadzoneE8Deadzonef","espp::Joystick::set_deadzone::radius"],[49,3,1,"_CPPv4N4espp8Joystick6updateEv","espp::Joystick::update"],[49,3,1,"_CPPv4NK4espp8Joystick1xEv","espp::Joystick::x"],[49,3,1,"_CPPv4NK4espp8Joystick1yEv","espp::Joystick::y"],[72,2,1,"_CPPv4N4espp9JpegFrameE","espp::JpegFrame"],[72,3,1,"_CPPv4N4espp9JpegFrame9JpegFrameEPKc6size_t","espp::JpegFrame::JpegFrame"],[72,3,1,"_CPPv4N4espp9JpegFrame9JpegFrameERK13RtpJpegPacket","espp::JpegFrame::JpegFrame"],[72,4,1,"_CPPv4N4espp9JpegFrame9JpegFrameEPKc6size_t","espp::JpegFrame::JpegFrame::data"],[72,4,1,"_CPPv4N4espp9JpegFrame9JpegFrameERK13RtpJpegPacket","espp::JpegFrame::JpegFrame::packet"],[72,4,1,"_CPPv4N4espp9JpegFrame9JpegFrameEPKc6size_t","espp::JpegFrame::JpegFrame::size"],[72,3,1,"_CPPv4N4espp9JpegFrame8add_scanERK13RtpJpegPacket","espp::JpegFrame::add_scan"],[72,4,1,"_CPPv4N4espp9JpegFrame8add_scanERK13RtpJpegPacket","espp::JpegFrame::add_scan::packet"],[72,3,1,"_CPPv4N4espp9JpegFrame6appendERK13RtpJpegPacket","espp::JpegFrame::append"],[72,4,1,"_CPPv4N4espp9JpegFrame6appendERK13RtpJpegPacket","espp::JpegFrame::append::packet"],[72,3,1,"_CPPv4NK4espp9JpegFrame8get_dataEv","espp::JpegFrame::get_data"],[72,3,1,"_CPPv4NK4espp9JpegFrame10get_headerEv","espp::JpegFrame::get_header"],[72,3,1,"_CPPv4NK4espp9JpegFrame10get_heightEv","espp::JpegFrame::get_height"],[72,3,1,"_CPPv4NK4espp9JpegFrame13get_scan_dataEv","espp::JpegFrame::get_scan_data"],[72,3,1,"_CPPv4NK4espp9JpegFrame9get_widthEv","espp::JpegFrame::get_width"],[72,3,1,"_CPPv4NK4espp9JpegFrame11is_completeEv","espp::JpegFrame::is_complete"],[72,2,1,"_CPPv4N4espp10JpegHeaderE","espp::JpegHeader"],[72,3,1,"_CPPv4N4espp10JpegHeader10JpegHeaderENSt11string_viewE","espp::JpegHeader::JpegHeader"],[72,3,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader"],[72,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderENSt11string_viewE","espp::JpegHeader::JpegHeader::data"],[72,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::height"],[72,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::q0_table"],[72,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::q1_table"],[72,4,1,"_CPPv4N4espp10JpegHeader10JpegHeaderEiiNSt11string_viewENSt11string_viewE","espp::JpegHeader::JpegHeader::width"],[72,3,1,"_CPPv4NK4espp10JpegHeader8get_dataEv","espp::JpegHeader::get_data"],[72,3,1,"_CPPv4NK4espp10JpegHeader10get_heightEv","espp::JpegHeader::get_height"],[72,3,1,"_CPPv4NK4espp10JpegHeader22get_quantization_tableEi","espp::JpegHeader::get_quantization_table"],[72,4,1,"_CPPv4NK4espp10JpegHeader22get_quantization_tableEi","espp::JpegHeader::get_quantization_table::index"],[72,3,1,"_CPPv4NK4espp10JpegHeader9get_widthEv","espp::JpegHeader::get_width"],[42,2,1,"_CPPv4N4espp11KeypadInputE","espp::KeypadInput"],[42,2,1,"_CPPv4N4espp11KeypadInput6ConfigE","espp::KeypadInput::Config"],[42,1,1,"_CPPv4N4espp11KeypadInput6Config9log_levelE","espp::KeypadInput::Config::log_level"],[42,1,1,"_CPPv4N4espp11KeypadInput6Config4readE","espp::KeypadInput::Config::read"],[42,3,1,"_CPPv4N4espp11KeypadInput11KeypadInputERK6Config","espp::KeypadInput::KeypadInput"],[42,4,1,"_CPPv4N4espp11KeypadInput11KeypadInputERK6Config","espp::KeypadInput::KeypadInput::config"],[42,3,1,"_CPPv4N4espp11KeypadInput16get_input_deviceEv","espp::KeypadInput::get_input_device"],[42,3,1,"_CPPv4N4espp11KeypadInputD0Ev","espp::KeypadInput::~KeypadInput"],[50,2,1,"_CPPv4N4espp3LedE","espp::Led"],[50,2,1,"_CPPv4N4espp3Led13ChannelConfigE","espp::Led::ChannelConfig"],[50,1,1,"_CPPv4N4espp3Led13ChannelConfig7channelE","espp::Led::ChannelConfig::channel"],[50,1,1,"_CPPv4N4espp3Led13ChannelConfig4dutyE","espp::Led::ChannelConfig::duty"],[50,1,1,"_CPPv4N4espp3Led13ChannelConfig4gpioE","espp::Led::ChannelConfig::gpio"],[50,1,1,"_CPPv4N4espp3Led13ChannelConfig13output_invertE","espp::Led::ChannelConfig::output_invert"],[50,1,1,"_CPPv4N4espp3Led13ChannelConfig10speed_modeE","espp::Led::ChannelConfig::speed_mode"],[50,1,1,"_CPPv4N4espp3Led13ChannelConfig5timerE","espp::Led::ChannelConfig::timer"],[50,2,1,"_CPPv4N4espp3Led6ConfigE","espp::Led::Config"],[50,1,1,"_CPPv4N4espp3Led6Config8channelsE","espp::Led::Config::channels"],[50,1,1,"_CPPv4N4espp3Led6Config15duty_resolutionE","espp::Led::Config::duty_resolution"],[50,1,1,"_CPPv4N4espp3Led6Config12frequency_hzE","espp::Led::Config::frequency_hz"],[50,1,1,"_CPPv4N4espp3Led6Config9log_levelE","espp::Led::Config::log_level"],[50,1,1,"_CPPv4N4espp3Led6Config10speed_modeE","espp::Led::Config::speed_mode"],[50,1,1,"_CPPv4N4espp3Led6Config5timerE","espp::Led::Config::timer"],[50,3,1,"_CPPv4N4espp3Led3LedERK6Config","espp::Led::Led"],[50,4,1,"_CPPv4N4espp3Led3LedERK6Config","espp::Led::Led::config"],[50,3,1,"_CPPv4N4espp3Led10can_changeE14ledc_channel_t","espp::Led::can_change"],[50,4,1,"_CPPv4N4espp3Led10can_changeE14ledc_channel_t","espp::Led::can_change::channel"],[50,3,1,"_CPPv4NK4espp3Led8get_dutyE14ledc_channel_t","espp::Led::get_duty"],[50,4,1,"_CPPv4NK4espp3Led8get_dutyE14ledc_channel_t","espp::Led::get_duty::channel"],[50,3,1,"_CPPv4N4espp3Led8set_dutyE14ledc_channel_tf","espp::Led::set_duty"],[50,4,1,"_CPPv4N4espp3Led8set_dutyE14ledc_channel_tf","espp::Led::set_duty::channel"],[50,4,1,"_CPPv4N4espp3Led8set_dutyE14ledc_channel_tf","espp::Led::set_duty::duty_percent"],[50,3,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time"],[50,4,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time::channel"],[50,4,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time::duty_percent"],[50,4,1,"_CPPv4N4espp3Led18set_fade_with_timeE14ledc_channel_tf8uint32_t","espp::Led::set_fade_with_time::fade_time_ms"],[50,3,1,"_CPPv4N4espp3LedD0Ev","espp::Led::~Led"],[51,2,1,"_CPPv4N4espp8LedStripE","espp::LedStrip"],[51,1,1,"_CPPv4N4espp8LedStrip18APA102_START_FRAMEE","espp::LedStrip::APA102_START_FRAME"],[51,6,1,"_CPPv4N4espp8LedStrip9ByteOrderE","espp::LedStrip::ByteOrder"],[51,7,1,"_CPPv4N4espp8LedStrip9ByteOrder3BGRE","espp::LedStrip::ByteOrder::BGR"],[51,7,1,"_CPPv4N4espp8LedStrip9ByteOrder3GRBE","espp::LedStrip::ByteOrder::GRB"],[51,7,1,"_CPPv4N4espp8LedStrip9ByteOrder3RGBE","espp::LedStrip::ByteOrder::RGB"],[51,2,1,"_CPPv4N4espp8LedStrip6ConfigE","espp::LedStrip::Config"],[51,1,1,"_CPPv4N4espp8LedStrip6Config10byte_orderE","espp::LedStrip::Config::byte_order"],[51,1,1,"_CPPv4N4espp8LedStrip6Config9end_frameE","espp::LedStrip::Config::end_frame"],[51,1,1,"_CPPv4N4espp8LedStrip6Config9log_levelE","espp::LedStrip::Config::log_level"],[51,1,1,"_CPPv4N4espp8LedStrip6Config8num_ledsE","espp::LedStrip::Config::num_leds"],[51,1,1,"_CPPv4N4espp8LedStrip6Config15send_brightnessE","espp::LedStrip::Config::send_brightness"],[51,1,1,"_CPPv4N4espp8LedStrip6Config11start_frameE","espp::LedStrip::Config::start_frame"],[51,1,1,"_CPPv4N4espp8LedStrip6Config5writeE","espp::LedStrip::Config::write"],[51,3,1,"_CPPv4N4espp8LedStrip8LedStripERK6Config","espp::LedStrip::LedStrip"],[51,4,1,"_CPPv4N4espp8LedStrip8LedStripERK6Config","espp::LedStrip::LedStrip::config"],[51,3,1,"_CPPv4NK4espp8LedStrip10byte_orderEv","espp::LedStrip::byte_order"],[51,3,1,"_CPPv4NK4espp8LedStrip8num_ledsEv","espp::LedStrip::num_leds"],[51,3,1,"_CPPv4N4espp8LedStrip7set_allE3Hsvf","espp::LedStrip::set_all"],[51,3,1,"_CPPv4N4espp8LedStrip7set_allE3Rgbf","espp::LedStrip::set_all"],[51,3,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::b"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE3Hsvf","espp::LedStrip::set_all::brightness"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE3Rgbf","espp::LedStrip::set_all::brightness"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::brightness"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::g"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE3Hsvf","espp::LedStrip::set_all::hsv"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_all::r"],[51,4,1,"_CPPv4N4espp8LedStrip7set_allE3Rgbf","espp::LedStrip::set_all::rgb"],[51,3,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel"],[51,3,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel"],[51,3,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::b"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel::brightness"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel::brightness"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::brightness"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::g"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel::hsv"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Hsvf","espp::LedStrip::set_pixel::index"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel::index"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::index"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi7uint8_t7uint8_t7uint8_t7uint8_t","espp::LedStrip::set_pixel::r"],[51,4,1,"_CPPv4N4espp8LedStrip9set_pixelEi3Rgbf","espp::LedStrip::set_pixel::rgb"],[51,3,1,"_CPPv4N4espp8LedStrip10shift_leftEi","espp::LedStrip::shift_left"],[51,4,1,"_CPPv4N4espp8LedStrip10shift_leftEi","espp::LedStrip::shift_left::shift_by"],[51,3,1,"_CPPv4N4espp8LedStrip11shift_rightEi","espp::LedStrip::shift_right"],[51,4,1,"_CPPv4N4espp8LedStrip11shift_rightEi","espp::LedStrip::shift_right::shift_by"],[51,3,1,"_CPPv4N4espp8LedStrip4showEv","espp::LedStrip::show"],[51,8,1,"_CPPv4N4espp8LedStrip8write_fnE","espp::LedStrip::write_fn"],[11,2,1,"_CPPv4N4espp9LineInputE","espp::LineInput"],[11,8,1,"_CPPv4N4espp9LineInput7HistoryE","espp::LineInput::History"],[11,3,1,"_CPPv4N4espp9LineInput9LineInputEv","espp::LineInput::LineInput"],[11,3,1,"_CPPv4N4espp9LineInput10clear_lineEv","espp::LineInput::clear_line"],[11,3,1,"_CPPv4N4espp9LineInput12clear_screenEv","espp::LineInput::clear_screen"],[11,3,1,"_CPPv4N4espp9LineInput20clear_to_end_of_lineEv","espp::LineInput::clear_to_end_of_line"],[11,3,1,"_CPPv4N4espp9LineInput22clear_to_start_of_lineEv","espp::LineInput::clear_to_start_of_line"],[11,3,1,"_CPPv4NK4espp9LineInput11get_historyEv","espp::LineInput::get_history"],[11,3,1,"_CPPv4N4espp9LineInput17get_terminal_sizeERiRi","espp::LineInput::get_terminal_size"],[11,4,1,"_CPPv4N4espp9LineInput17get_terminal_sizeERiRi","espp::LineInput::get_terminal_size::height"],[11,4,1,"_CPPv4N4espp9LineInput17get_terminal_sizeERiRi","espp::LineInput::get_terminal_size::width"],[11,3,1,"_CPPv4N4espp9LineInput14get_user_inputERNSt7istreamE9prompt_fn","espp::LineInput::get_user_input"],[11,4,1,"_CPPv4N4espp9LineInput14get_user_inputERNSt7istreamE9prompt_fn","espp::LineInput::get_user_input::is"],[11,4,1,"_CPPv4N4espp9LineInput14get_user_inputERNSt7istreamE9prompt_fn","espp::LineInput::get_user_input::prompt"],[11,8,1,"_CPPv4N4espp9LineInput9prompt_fnE","espp::LineInput::prompt_fn"],[11,3,1,"_CPPv4N4espp9LineInput17set_handle_resizeEb","espp::LineInput::set_handle_resize"],[11,4,1,"_CPPv4N4espp9LineInput17set_handle_resizeEb","espp::LineInput::set_handle_resize::handle_resize"],[11,3,1,"_CPPv4N4espp9LineInput11set_historyERK7History","espp::LineInput::set_history"],[11,4,1,"_CPPv4N4espp9LineInput11set_historyERK7History","espp::LineInput::set_history::history"],[11,3,1,"_CPPv4N4espp9LineInput16set_history_sizeE6size_t","espp::LineInput::set_history_size"],[11,4,1,"_CPPv4N4espp9LineInput16set_history_sizeE6size_t","espp::LineInput::set_history_size::new_size"],[11,3,1,"_CPPv4N4espp9LineInputD0Ev","espp::LineInput::~LineInput"],[52,2,1,"_CPPv4N4espp6LoggerE","espp::Logger"],[52,2,1,"_CPPv4N4espp6Logger6ConfigE","espp::Logger::Config"],[52,1,1,"_CPPv4N4espp6Logger6Config5levelE","espp::Logger::Config::level"],[52,1,1,"_CPPv4N4espp6Logger6Config10rate_limitE","espp::Logger::Config::rate_limit"],[52,1,1,"_CPPv4N4espp6Logger6Config3tagE","espp::Logger::Config::tag"],[52,3,1,"_CPPv4N4espp6Logger6LoggerERK6Config","espp::Logger::Logger"],[52,4,1,"_CPPv4N4espp6Logger6LoggerERK6Config","espp::Logger::Logger::config"],[52,6,1,"_CPPv4N4espp6Logger9VerbosityE","espp::Logger::Verbosity"],[52,7,1,"_CPPv4N4espp6Logger9Verbosity5DEBUGE","espp::Logger::Verbosity::DEBUG"],[52,7,1,"_CPPv4N4espp6Logger9Verbosity5ERRORE","espp::Logger::Verbosity::ERROR"],[52,7,1,"_CPPv4N4espp6Logger9Verbosity4INFOE","espp::Logger::Verbosity::INFO"],[52,7,1,"_CPPv4N4espp6Logger9Verbosity4NONEE","espp::Logger::Verbosity::NONE"],[52,7,1,"_CPPv4N4espp6Logger9Verbosity4WARNE","espp::Logger::Verbosity::WARN"],[52,3,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug"],[52,5,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger5debugEvNSt11string_viewEDpRR4Args","espp::Logger::debug::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited"],[52,5,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger18debug_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::debug_rate_limited::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error"],[52,5,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger5errorEvNSt11string_viewEDpRR4Args","espp::Logger::error::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited"],[52,5,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger18error_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::error_rate_limited::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format"],[52,5,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger6formatENSt6stringENSt11string_viewEDpRR4Args","espp::Logger::format::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info"],[52,5,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger4infoEvNSt11string_viewEDpRR4Args","espp::Logger::info::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited"],[52,5,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger17info_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::info_rate_limited::rt_fmt_str"],[52,3,1,"_CPPv4N4espp6Logger7set_tagEKNSt11string_viewE","espp::Logger::set_tag"],[52,4,1,"_CPPv4N4espp6Logger7set_tagEKNSt11string_viewE","espp::Logger::set_tag::tag"],[52,3,1,"_CPPv4N4espp6Logger13set_verbosityEK9Verbosity","espp::Logger::set_verbosity"],[52,4,1,"_CPPv4N4espp6Logger13set_verbosityEK9Verbosity","espp::Logger::set_verbosity::level"],[52,3,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn"],[52,5,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger4warnEvNSt11string_viewEDpRR4Args","espp::Logger::warn::rt_fmt_str"],[52,3,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited"],[52,5,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited::Args"],[52,4,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited::args"],[52,4,1,"_CPPv4IDpEN4espp6Logger17warn_rate_limitedEvNSt11string_viewEDpRR4Args","espp::Logger::warn_rate_limited::rt_fmt_str"],[28,2,1,"_CPPv4N4espp13LowpassFilterE","espp::LowpassFilter"],[28,2,1,"_CPPv4N4espp13LowpassFilter6ConfigE","espp::LowpassFilter::Config"],[28,1,1,"_CPPv4N4espp13LowpassFilter6Config27normalized_cutoff_frequencyE","espp::LowpassFilter::Config::normalized_cutoff_frequency"],[28,1,1,"_CPPv4N4espp13LowpassFilter6Config8q_factorE","espp::LowpassFilter::Config::q_factor"],[28,3,1,"_CPPv4N4espp13LowpassFilter13LowpassFilterERK6Config","espp::LowpassFilter::LowpassFilter"],[28,4,1,"_CPPv4N4espp13LowpassFilter13LowpassFilterERK6Config","espp::LowpassFilter::LowpassFilter::config"],[28,3,1,"_CPPv4N4espp13LowpassFilterclEf","espp::LowpassFilter::operator()"],[28,4,1,"_CPPv4N4espp13LowpassFilterclEf","espp::LowpassFilter::operator()::input"],[28,3,1,"_CPPv4N4espp13LowpassFilter6updateEKf","espp::LowpassFilter::update"],[28,3,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update"],[28,4,1,"_CPPv4N4espp13LowpassFilter6updateEKf","espp::LowpassFilter::update::input"],[28,4,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update::input"],[28,4,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update::length"],[28,4,1,"_CPPv4N4espp13LowpassFilter6updateEPKfPf6size_t","espp::LowpassFilter::update::output"],[48,2,1,"_CPPv4N4espp8Mcp23x17E","espp::Mcp23x17"],[48,2,1,"_CPPv4N4espp8Mcp23x176ConfigE","espp::Mcp23x17::Config"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config9auto_initE","espp::Mcp23x17::Config::auto_init"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config14device_addressE","espp::Mcp23x17::Config::device_address"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config9log_levelE","espp::Mcp23x17::Config::log_level"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config21port_0_direction_maskE","espp::Mcp23x17::Config::port_0_direction_mask"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config21port_0_interrupt_maskE","espp::Mcp23x17::Config::port_0_interrupt_mask"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config21port_1_direction_maskE","espp::Mcp23x17::Config::port_1_direction_mask"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config21port_1_interrupt_maskE","espp::Mcp23x17::Config::port_1_interrupt_mask"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config4readE","espp::Mcp23x17::Config::read"],[48,1,1,"_CPPv4N4espp8Mcp23x176Config5writeE","espp::Mcp23x17::Config::write"],[48,1,1,"_CPPv4N4espp8Mcp23x1715DEFAULT_ADDRESSE","espp::Mcp23x17::DEFAULT_ADDRESS"],[48,3,1,"_CPPv4N4espp8Mcp23x178Mcp23x17ERK6Config","espp::Mcp23x17::Mcp23x17"],[48,4,1,"_CPPv4N4espp8Mcp23x178Mcp23x17ERK6Config","espp::Mcp23x17::Mcp23x17::config"],[48,6,1,"_CPPv4N4espp8Mcp23x174PortE","espp::Mcp23x17::Port"],[48,7,1,"_CPPv4N4espp8Mcp23x174Port5PORT0E","espp::Mcp23x17::Port::PORT0"],[48,7,1,"_CPPv4N4espp8Mcp23x174Port5PORT1E","espp::Mcp23x17::Port::PORT1"],[48,3,1,"_CPPv4N4espp8Mcp23x1721get_interrupt_captureE4PortRNSt10error_codeE","espp::Mcp23x17::get_interrupt_capture"],[48,4,1,"_CPPv4N4espp8Mcp23x1721get_interrupt_captureE4PortRNSt10error_codeE","espp::Mcp23x17::get_interrupt_capture::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1721get_interrupt_captureE4PortRNSt10error_codeE","espp::Mcp23x17::get_interrupt_capture::port"],[48,3,1,"_CPPv4N4espp8Mcp23x178get_pinsE4PortRNSt10error_codeE","espp::Mcp23x17::get_pins"],[48,3,1,"_CPPv4N4espp8Mcp23x178get_pinsERNSt10error_codeE","espp::Mcp23x17::get_pins"],[48,4,1,"_CPPv4N4espp8Mcp23x178get_pinsE4PortRNSt10error_codeE","espp::Mcp23x17::get_pins::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x178get_pinsERNSt10error_codeE","espp::Mcp23x17::get_pins::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x178get_pinsE4PortRNSt10error_codeE","espp::Mcp23x17::get_pins::port"],[48,3,1,"_CPPv4N4espp8Mcp23x1710initializeERNSt10error_codeE","espp::Mcp23x17::initialize"],[48,4,1,"_CPPv4N4espp8Mcp23x1710initializeERNSt10error_codeE","espp::Mcp23x17::initialize::ec"],[48,8,1,"_CPPv4N4espp8Mcp23x177read_fnE","espp::Mcp23x17::read_fn"],[48,3,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_direction"],[48,4,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_direction::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_direction::mask"],[48,4,1,"_CPPv4N4espp8Mcp23x1713set_directionE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_direction::port"],[48,3,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_input_polarity"],[48,4,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_input_polarity::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_input_polarity::mask"],[48,4,1,"_CPPv4N4espp8Mcp23x1718set_input_polarityE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_input_polarity::port"],[48,3,1,"_CPPv4N4espp8Mcp23x1720set_interrupt_mirrorEbRNSt10error_codeE","espp::Mcp23x17::set_interrupt_mirror"],[48,4,1,"_CPPv4N4espp8Mcp23x1720set_interrupt_mirrorEbRNSt10error_codeE","espp::Mcp23x17::set_interrupt_mirror::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1720set_interrupt_mirrorEbRNSt10error_codeE","espp::Mcp23x17::set_interrupt_mirror::mirror"],[48,3,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_change"],[48,4,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_change::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_change::mask"],[48,4,1,"_CPPv4N4espp8Mcp23x1723set_interrupt_on_changeE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_change::port"],[48,3,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_value"],[48,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_value::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_value::pin_mask"],[48,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_value::port"],[48,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_on_valueE4Port7uint8_t7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_interrupt_on_value::val_mask"],[48,3,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_polarityEbRNSt10error_codeE","espp::Mcp23x17::set_interrupt_polarity"],[48,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_polarityEbRNSt10error_codeE","espp::Mcp23x17::set_interrupt_polarity::active_high"],[48,4,1,"_CPPv4N4espp8Mcp23x1722set_interrupt_polarityEbRNSt10error_codeE","espp::Mcp23x17::set_interrupt_polarity::ec"],[48,3,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pins"],[48,4,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pins::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pins::output"],[48,4,1,"_CPPv4N4espp8Mcp23x178set_pinsE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pins::port"],[48,3,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pull_up"],[48,4,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pull_up::ec"],[48,4,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pull_up::mask"],[48,4,1,"_CPPv4N4espp8Mcp23x1711set_pull_upE4Port7uint8_tRNSt10error_codeE","espp::Mcp23x17::set_pull_up::port"],[48,8,1,"_CPPv4N4espp8Mcp23x178write_fnE","espp::Mcp23x17::write_fn"],[22,2,1,"_CPPv4N4espp6Mt6701E","espp::Mt6701"],[22,1,1,"_CPPv4N4espp6Mt670121COUNTS_PER_REVOLUTIONE","espp::Mt6701::COUNTS_PER_REVOLUTION"],[22,1,1,"_CPPv4N4espp6Mt670123COUNTS_PER_REVOLUTION_FE","espp::Mt6701::COUNTS_PER_REVOLUTION_F"],[22,1,1,"_CPPv4N4espp6Mt670117COUNTS_TO_DEGREESE","espp::Mt6701::COUNTS_TO_DEGREES"],[22,1,1,"_CPPv4N4espp6Mt670117COUNTS_TO_RADIANSE","espp::Mt6701::COUNTS_TO_RADIANS"],[22,2,1,"_CPPv4N4espp6Mt67016ConfigE","espp::Mt6701::Config"],[22,1,1,"_CPPv4N4espp6Mt67016Config9auto_initE","espp::Mt6701::Config::auto_init"],[22,1,1,"_CPPv4N4espp6Mt67016Config14device_addressE","espp::Mt6701::Config::device_address"],[22,1,1,"_CPPv4N4espp6Mt67016Config4readE","espp::Mt6701::Config::read"],[22,1,1,"_CPPv4N4espp6Mt67016Config13update_periodE","espp::Mt6701::Config::update_period"],[22,1,1,"_CPPv4N4espp6Mt67016Config15velocity_filterE","espp::Mt6701::Config::velocity_filter"],[22,1,1,"_CPPv4N4espp6Mt67016Config5writeE","espp::Mt6701::Config::write"],[22,1,1,"_CPPv4N4espp6Mt670115DEFAULT_ADDRESSE","espp::Mt6701::DEFAULT_ADDRESS"],[22,3,1,"_CPPv4N4espp6Mt67016Mt6701ERK6Config","espp::Mt6701::Mt6701"],[22,4,1,"_CPPv4N4espp6Mt67016Mt6701ERK6Config","espp::Mt6701::Mt6701::config"],[22,1,1,"_CPPv4N4espp6Mt670118SECONDS_PER_MINUTEE","espp::Mt6701::SECONDS_PER_MINUTE"],[22,3,1,"_CPPv4NK4espp6Mt670115get_accumulatorEv","espp::Mt6701::get_accumulator"],[22,3,1,"_CPPv4NK4espp6Mt67019get_countEv","espp::Mt6701::get_count"],[22,3,1,"_CPPv4NK4espp6Mt670111get_degreesEv","espp::Mt6701::get_degrees"],[22,3,1,"_CPPv4NK4espp6Mt670122get_mechanical_degreesEv","espp::Mt6701::get_mechanical_degrees"],[22,3,1,"_CPPv4NK4espp6Mt670122get_mechanical_radiansEv","espp::Mt6701::get_mechanical_radians"],[22,3,1,"_CPPv4NK4espp6Mt670111get_radiansEv","espp::Mt6701::get_radians"],[22,3,1,"_CPPv4NK4espp6Mt67017get_rpmEv","espp::Mt6701::get_rpm"],[22,3,1,"_CPPv4N4espp6Mt670110initializeERNSt10error_codeE","espp::Mt6701::initialize"],[22,4,1,"_CPPv4N4espp6Mt670110initializeERNSt10error_codeE","espp::Mt6701::initialize::ec"],[22,3,1,"_CPPv4NK4espp6Mt670117needs_zero_searchEv","espp::Mt6701::needs_zero_search"],[22,8,1,"_CPPv4N4espp6Mt67017read_fnE","espp::Mt6701::read_fn"],[22,8,1,"_CPPv4N4espp6Mt670118velocity_filter_fnE","espp::Mt6701::velocity_filter_fn"],[22,8,1,"_CPPv4N4espp6Mt67018write_fnE","espp::Mt6701::write_fn"],[65,2,1,"_CPPv4N4espp4NdefE","espp::Ndef"],[65,6,1,"_CPPv4N4espp4Ndef7BleRoleE","espp::Ndef::BleRole"],[65,7,1,"_CPPv4N4espp4Ndef7BleRole12CENTRAL_ONLYE","espp::Ndef::BleRole::CENTRAL_ONLY"],[65,7,1,"_CPPv4N4espp4Ndef7BleRole18CENTRAL_PERIPHERALE","espp::Ndef::BleRole::CENTRAL_PERIPHERAL"],[65,7,1,"_CPPv4N4espp4Ndef7BleRole18PERIPHERAL_CENTRALE","espp::Ndef::BleRole::PERIPHERAL_CENTRAL"],[65,7,1,"_CPPv4N4espp4Ndef7BleRole15PERIPHERAL_ONLYE","espp::Ndef::BleRole::PERIPHERAL_ONLY"],[65,6,1,"_CPPv4N4espp4Ndef12BtAppearanceE","espp::Ndef::BtAppearance"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance5CLOCKE","espp::Ndef::BtAppearance::CLOCK"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance8COMPUTERE","espp::Ndef::BtAppearance::COMPUTER"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance7DISPLAYE","espp::Ndef::BtAppearance::DISPLAY"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance7GAMEPADE","espp::Ndef::BtAppearance::GAMEPAD"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance6GAMINGE","espp::Ndef::BtAppearance::GAMING"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance11GENERIC_HIDE","espp::Ndef::BtAppearance::GENERIC_HID"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance8JOYSTICKE","espp::Ndef::BtAppearance::JOYSTICK"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance8KEYBOARDE","espp::Ndef::BtAppearance::KEYBOARD"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance5MOUSEE","espp::Ndef::BtAppearance::MOUSE"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance5PHONEE","espp::Ndef::BtAppearance::PHONE"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance14REMOTE_CONTROLE","espp::Ndef::BtAppearance::REMOTE_CONTROL"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance8TOUCHPADE","espp::Ndef::BtAppearance::TOUCHPAD"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance7UNKNOWNE","espp::Ndef::BtAppearance::UNKNOWN"],[65,7,1,"_CPPv4N4espp4Ndef12BtAppearance5WATCHE","espp::Ndef::BtAppearance::WATCH"],[65,6,1,"_CPPv4N4espp4Ndef5BtEirE","espp::Ndef::BtEir"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir10APPEARANCEE","espp::Ndef::BtEir::APPEARANCE"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir15CLASS_OF_DEVICEE","espp::Ndef::BtEir::CLASS_OF_DEVICE"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir5FLAGSE","espp::Ndef::BtEir::FLAGS"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir7LE_ROLEE","espp::Ndef::BtEir::LE_ROLE"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir18LE_SC_CONFIRMATIONE","espp::Ndef::BtEir::LE_SC_CONFIRMATION"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir12LE_SC_RANDOME","espp::Ndef::BtEir::LE_SC_RANDOM"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir15LONG_LOCAL_NAMEE","espp::Ndef::BtEir::LONG_LOCAL_NAME"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir3MACE","espp::Ndef::BtEir::MAC"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir22SECURITY_MANAGER_FLAGSE","espp::Ndef::BtEir::SECURITY_MANAGER_FLAGS"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir19SECURITY_MANAGER_TKE","espp::Ndef::BtEir::SECURITY_MANAGER_TK"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir16SHORT_LOCAL_NAMEE","espp::Ndef::BtEir::SHORT_LOCAL_NAME"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir12SP_HASH_C192E","espp::Ndef::BtEir::SP_HASH_C192"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir12SP_HASH_C256E","espp::Ndef::BtEir::SP_HASH_C256"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir12SP_HASH_R256E","espp::Ndef::BtEir::SP_HASH_R256"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir14SP_RANDOM_R192E","espp::Ndef::BtEir::SP_RANDOM_R192"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir14TX_POWER_LEVELE","espp::Ndef::BtEir::TX_POWER_LEVEL"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir22UUIDS_128_BIT_COMPLETEE","espp::Ndef::BtEir::UUIDS_128_BIT_COMPLETE"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir21UUIDS_128_BIT_PARTIALE","espp::Ndef::BtEir::UUIDS_128_BIT_PARTIAL"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir21UUIDS_16_BIT_COMPLETEE","espp::Ndef::BtEir::UUIDS_16_BIT_COMPLETE"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir20UUIDS_16_BIT_PARTIALE","espp::Ndef::BtEir::UUIDS_16_BIT_PARTIAL"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir21UUIDS_32_BIT_COMPLETEE","espp::Ndef::BtEir::UUIDS_32_BIT_COMPLETE"],[65,7,1,"_CPPv4N4espp4Ndef5BtEir20UUIDS_32_BIT_PARTIALE","espp::Ndef::BtEir::UUIDS_32_BIT_PARTIAL"],[65,6,1,"_CPPv4N4espp4Ndef6BtTypeE","espp::Ndef::BtType"],[65,7,1,"_CPPv4N4espp4Ndef6BtType3BLEE","espp::Ndef::BtType::BLE"],[65,7,1,"_CPPv4N4espp4Ndef6BtType5BREDRE","espp::Ndef::BtType::BREDR"],[65,6,1,"_CPPv4N4espp4Ndef17CarrierPowerStateE","espp::Ndef::CarrierPowerState"],[65,7,1,"_CPPv4N4espp4Ndef17CarrierPowerState10ACTIVATINGE","espp::Ndef::CarrierPowerState::ACTIVATING"],[65,7,1,"_CPPv4N4espp4Ndef17CarrierPowerState6ACTIVEE","espp::Ndef::CarrierPowerState::ACTIVE"],[65,7,1,"_CPPv4N4espp4Ndef17CarrierPowerState8INACTIVEE","espp::Ndef::CarrierPowerState::INACTIVE"],[65,7,1,"_CPPv4N4espp4Ndef17CarrierPowerState7UNKNOWNE","espp::Ndef::CarrierPowerState::UNKNOWN"],[65,1,1,"_CPPv4N4espp4Ndef16HANDOVER_VERSIONE","espp::Ndef::HANDOVER_VERSION"],[65,3,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef"],[65,4,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef::payload"],[65,4,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef::tnf"],[65,4,1,"_CPPv4N4espp4Ndef4NdefE3TNFNSt11string_viewENSt11string_viewE","espp::Ndef::Ndef::type"],[65,6,1,"_CPPv4N4espp4Ndef3TNFE","espp::Ndef::TNF"],[65,7,1,"_CPPv4N4espp4Ndef3TNF12ABSOLUTE_URIE","espp::Ndef::TNF::ABSOLUTE_URI"],[65,7,1,"_CPPv4N4espp4Ndef3TNF5EMPTYE","espp::Ndef::TNF::EMPTY"],[65,7,1,"_CPPv4N4espp4Ndef3TNF13EXTERNAL_TYPEE","espp::Ndef::TNF::EXTERNAL_TYPE"],[65,7,1,"_CPPv4N4espp4Ndef3TNF10MIME_MEDIAE","espp::Ndef::TNF::MIME_MEDIA"],[65,7,1,"_CPPv4N4espp4Ndef3TNF8RESERVEDE","espp::Ndef::TNF::RESERVED"],[65,7,1,"_CPPv4N4espp4Ndef3TNF9UNCHANGEDE","espp::Ndef::TNF::UNCHANGED"],[65,7,1,"_CPPv4N4espp4Ndef3TNF7UNKNOWNE","espp::Ndef::TNF::UNKNOWN"],[65,7,1,"_CPPv4N4espp4Ndef3TNF10WELL_KNOWNE","espp::Ndef::TNF::WELL_KNOWN"],[65,6,1,"_CPPv4N4espp4Ndef3UicE","espp::Ndef::Uic"],[65,7,1,"_CPPv4N4espp4Ndef3Uic6BTGOEPE","espp::Ndef::Uic::BTGOEP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic7BTL2CAPE","espp::Ndef::Uic::BTL2CAP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic5BTSPPE","espp::Ndef::Uic::BTSPP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3DAVE","espp::Ndef::Uic::DAV"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4FILEE","espp::Ndef::Uic::FILE"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3FTPE","espp::Ndef::Uic::FTP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4FTPSE","espp::Ndef::Uic::FTPS"],[65,7,1,"_CPPv4N4espp4Ndef3Uic8FTP_ANONE","espp::Ndef::Uic::FTP_ANON"],[65,7,1,"_CPPv4N4espp4Ndef3Uic7FTP_FTPE","espp::Ndef::Uic::FTP_FTP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4HTTPE","espp::Ndef::Uic::HTTP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic5HTTPSE","espp::Ndef::Uic::HTTPS"],[65,7,1,"_CPPv4N4espp4Ndef3Uic9HTTPS_WWWE","espp::Ndef::Uic::HTTPS_WWW"],[65,7,1,"_CPPv4N4espp4Ndef3Uic8HTTP_WWWE","espp::Ndef::Uic::HTTP_WWW"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4IMAPE","espp::Ndef::Uic::IMAP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic8IRDAOBEXE","espp::Ndef::Uic::IRDAOBEX"],[65,7,1,"_CPPv4N4espp4Ndef3Uic6MAILTOE","espp::Ndef::Uic::MAILTO"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4NEWSE","espp::Ndef::Uic::NEWS"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3NFSE","espp::Ndef::Uic::NFS"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4NONEE","espp::Ndef::Uic::NONE"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3POPE","espp::Ndef::Uic::POP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4RSTPE","espp::Ndef::Uic::RSTP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4SFTPE","espp::Ndef::Uic::SFTP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3SIPE","espp::Ndef::Uic::SIP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4SIPSE","espp::Ndef::Uic::SIPS"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3SMBE","espp::Ndef::Uic::SMB"],[65,7,1,"_CPPv4N4espp4Ndef3Uic7TCPOBEXE","espp::Ndef::Uic::TCPOBEX"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3TELE","espp::Ndef::Uic::TEL"],[65,7,1,"_CPPv4N4espp4Ndef3Uic6TELNETE","espp::Ndef::Uic::TELNET"],[65,7,1,"_CPPv4N4espp4Ndef3Uic4TFTPE","espp::Ndef::Uic::TFTP"],[65,7,1,"_CPPv4N4espp4Ndef3Uic3URNE","espp::Ndef::Uic::URN"],[65,7,1,"_CPPv4N4espp4Ndef3Uic7URN_EPCE","espp::Ndef::Uic::URN_EPC"],[65,7,1,"_CPPv4N4espp4Ndef3Uic10URN_EPC_IDE","espp::Ndef::Uic::URN_EPC_ID"],[65,7,1,"_CPPv4N4espp4Ndef3Uic11URN_EPC_PATE","espp::Ndef::Uic::URN_EPC_PAT"],[65,7,1,"_CPPv4N4espp4Ndef3Uic11URN_EPC_RAWE","espp::Ndef::Uic::URN_EPC_RAW"],[65,7,1,"_CPPv4N4espp4Ndef3Uic11URN_EPC_TAGE","espp::Ndef::Uic::URN_EPC_TAG"],[65,7,1,"_CPPv4N4espp4Ndef3Uic7URN_NFCE","espp::Ndef::Uic::URN_NFC"],[65,6,1,"_CPPv4N4espp4Ndef22WifiAuthenticationTypeE","espp::Ndef::WifiAuthenticationType"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType4OPENE","espp::Ndef::WifiAuthenticationType::OPEN"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType6SHAREDE","espp::Ndef::WifiAuthenticationType::SHARED"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType15WPA2_ENTERPRISEE","espp::Ndef::WifiAuthenticationType::WPA2_ENTERPRISE"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType13WPA2_PERSONALE","espp::Ndef::WifiAuthenticationType::WPA2_PERSONAL"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType14WPA_ENTERPRISEE","espp::Ndef::WifiAuthenticationType::WPA_ENTERPRISE"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType12WPA_PERSONALE","espp::Ndef::WifiAuthenticationType::WPA_PERSONAL"],[65,7,1,"_CPPv4N4espp4Ndef22WifiAuthenticationType17WPA_WPA2_PERSONALE","espp::Ndef::WifiAuthenticationType::WPA_WPA2_PERSONAL"],[65,2,1,"_CPPv4N4espp4Ndef10WifiConfigE","espp::Ndef::WifiConfig"],[65,1,1,"_CPPv4N4espp4Ndef10WifiConfig14authenticationE","espp::Ndef::WifiConfig::authentication"],[65,1,1,"_CPPv4N4espp4Ndef10WifiConfig10encryptionE","espp::Ndef::WifiConfig::encryption"],[65,1,1,"_CPPv4N4espp4Ndef10WifiConfig3keyE","espp::Ndef::WifiConfig::key"],[65,1,1,"_CPPv4N4espp4Ndef10WifiConfig11mac_addressE","espp::Ndef::WifiConfig::mac_address"],[65,1,1,"_CPPv4N4espp4Ndef10WifiConfig4ssidE","espp::Ndef::WifiConfig::ssid"],[65,6,1,"_CPPv4N4espp4Ndef18WifiEncryptionTypeE","espp::Ndef::WifiEncryptionType"],[65,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType3AESE","espp::Ndef::WifiEncryptionType::AES"],[65,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType4NONEE","espp::Ndef::WifiEncryptionType::NONE"],[65,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType4TKIPE","espp::Ndef::WifiEncryptionType::TKIP"],[65,7,1,"_CPPv4N4espp4Ndef18WifiEncryptionType3WEPE","espp::Ndef::WifiEncryptionType::WEP"],[65,3,1,"_CPPv4NK4espp4Ndef6get_idEv","espp::Ndef::get_id"],[65,3,1,"_CPPv4NK4espp4Ndef8get_sizeEv","espp::Ndef::get_size"],[65,3,1,"_CPPv4N4espp4Ndef24make_alternative_carrierERK17CarrierPowerStatei","espp::Ndef::make_alternative_carrier"],[65,4,1,"_CPPv4N4espp4Ndef24make_alternative_carrierERK17CarrierPowerStatei","espp::Ndef::make_alternative_carrier::carrier_data_ref"],[65,4,1,"_CPPv4N4espp4Ndef24make_alternative_carrierERK17CarrierPowerStatei","espp::Ndef::make_alternative_carrier::power_state"],[65,3,1,"_CPPv4N4espp4Ndef21make_android_launcherENSt11string_viewE","espp::Ndef::make_android_launcher"],[65,4,1,"_CPPv4N4espp4Ndef21make_android_launcherENSt11string_viewE","espp::Ndef::make_android_launcher::uri"],[65,3,1,"_CPPv4N4espp4Ndef21make_handover_requestEi","espp::Ndef::make_handover_request"],[65,4,1,"_CPPv4N4espp4Ndef21make_handover_requestEi","espp::Ndef::make_handover_request::carrier_data_ref"],[65,3,1,"_CPPv4N4espp4Ndef20make_handover_selectEi","espp::Ndef::make_handover_select"],[65,4,1,"_CPPv4N4espp4Ndef20make_handover_selectEi","espp::Ndef::make_handover_select::carrier_data_ref"],[65,3,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::appearance"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::confirm_value"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::mac_addr"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::name"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::random_value"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::role"],[65,4,1,"_CPPv4N4espp4Ndef19make_le_oob_pairingE8uint64_t7BleRoleNSt11string_viewE12BtAppearanceNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_le_oob_pairing::tk"],[65,3,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_oob_pairing"],[65,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_oob_pairing::confirm_value"],[65,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_oob_pairing::device_class"],[65,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_oob_pairing::mac_addr"],[65,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_oob_pairing::name"],[65,4,1,"_CPPv4N4espp4Ndef16make_oob_pairingE8uint64_t8uint32_tNSt11string_viewENSt11string_viewENSt11string_viewE","espp::Ndef::make_oob_pairing::random_value"],[65,3,1,"_CPPv4N4espp4Ndef9make_textENSt11string_viewE","espp::Ndef::make_text"],[65,4,1,"_CPPv4N4espp4Ndef9make_textENSt11string_viewE","espp::Ndef::make_text::text"],[65,3,1,"_CPPv4N4espp4Ndef8make_uriENSt11string_viewE3Uic","espp::Ndef::make_uri"],[65,4,1,"_CPPv4N4espp4Ndef8make_uriENSt11string_viewE3Uic","espp::Ndef::make_uri::uic"],[65,4,1,"_CPPv4N4espp4Ndef8make_uriENSt11string_viewE3Uic","espp::Ndef::make_uri::uri"],[65,3,1,"_CPPv4N4espp4Ndef16make_wifi_configERK10WifiConfig","espp::Ndef::make_wifi_config"],[65,4,1,"_CPPv4N4espp4Ndef16make_wifi_configERK10WifiConfig","espp::Ndef::make_wifi_config::config"],[65,3,1,"_CPPv4N4espp4Ndef7payloadEv","espp::Ndef::payload"],[65,3,1,"_CPPv4N4espp4Ndef9serializeEbb","espp::Ndef::serialize"],[65,4,1,"_CPPv4N4espp4Ndef9serializeEbb","espp::Ndef::serialize::message_begin"],[65,4,1,"_CPPv4N4espp4Ndef9serializeEbb","espp::Ndef::serialize::message_end"],[65,3,1,"_CPPv4N4espp4Ndef6set_idEi","espp::Ndef::set_id"],[65,4,1,"_CPPv4N4espp4Ndef6set_idEi","espp::Ndef::set_id::id"],[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"],[67,2,1,"_CPPv4N4espp3PidE","espp::Pid"],[67,2,1,"_CPPv4N4espp3Pid6ConfigE","espp::Pid::Config"],[67,1,1,"_CPPv4N4espp3Pid6Config14integrator_maxE","espp::Pid::Config::integrator_max"],[67,1,1,"_CPPv4N4espp3Pid6Config14integrator_minE","espp::Pid::Config::integrator_min"],[67,1,1,"_CPPv4N4espp3Pid6Config2kdE","espp::Pid::Config::kd"],[67,1,1,"_CPPv4N4espp3Pid6Config2kiE","espp::Pid::Config::ki"],[67,1,1,"_CPPv4N4espp3Pid6Config2kpE","espp::Pid::Config::kp"],[67,1,1,"_CPPv4N4espp3Pid6Config9log_levelE","espp::Pid::Config::log_level"],[67,1,1,"_CPPv4N4espp3Pid6Config10output_maxE","espp::Pid::Config::output_max"],[67,1,1,"_CPPv4N4espp3Pid6Config10output_minE","espp::Pid::Config::output_min"],[67,3,1,"_CPPv4N4espp3Pid3PidERK6Config","espp::Pid::Pid"],[67,4,1,"_CPPv4N4espp3Pid3PidERK6Config","espp::Pid::Pid::config"],[67,3,1,"_CPPv4N4espp3Pid12change_gainsERK6Configb","espp::Pid::change_gains"],[67,4,1,"_CPPv4N4espp3Pid12change_gainsERK6Configb","espp::Pid::change_gains::config"],[67,4,1,"_CPPv4N4espp3Pid12change_gainsERK6Configb","espp::Pid::change_gains::reset_state"],[67,3,1,"_CPPv4N4espp3Pid5clearEv","espp::Pid::clear"],[67,3,1,"_CPPv4NK4espp3Pid10get_configEv","espp::Pid::get_config"],[67,3,1,"_CPPv4NK4espp3Pid9get_errorEv","espp::Pid::get_error"],[67,3,1,"_CPPv4NK4espp3Pid14get_integratorEv","espp::Pid::get_integrator"],[67,3,1,"_CPPv4N4espp3PidclEf","espp::Pid::operator()"],[67,4,1,"_CPPv4N4espp3PidclEf","espp::Pid::operator()::error"],[67,3,1,"_CPPv4N4espp3Pid10set_configERK6Configb","espp::Pid::set_config"],[67,4,1,"_CPPv4N4espp3Pid10set_configERK6Configb","espp::Pid::set_config::config"],[67,4,1,"_CPPv4N4espp3Pid10set_configERK6Configb","espp::Pid::set_config::reset_state"],[67,3,1,"_CPPv4N4espp3Pid6updateEf","espp::Pid::update"],[67,4,1,"_CPPv4N4espp3Pid6updateEf","espp::Pid::update::error"],[68,2,1,"_CPPv4N4espp8QwiicNesE","espp::QwiicNes"],[68,6,1,"_CPPv4N4espp8QwiicNes6ButtonE","espp::QwiicNes::Button"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button1AE","espp::QwiicNes::Button::A"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button1BE","espp::QwiicNes::Button::B"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button4DOWNE","espp::QwiicNes::Button::DOWN"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button4LEFTE","espp::QwiicNes::Button::LEFT"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button5RIGHTE","espp::QwiicNes::Button::RIGHT"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button6SELECTE","espp::QwiicNes::Button::SELECT"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button5STARTE","espp::QwiicNes::Button::START"],[68,7,1,"_CPPv4N4espp8QwiicNes6Button2UPE","espp::QwiicNes::Button::UP"],[68,2,1,"_CPPv4N4espp8QwiicNes11ButtonStateE","espp::QwiicNes::ButtonState"],[68,2,1,"_CPPv4N4espp8QwiicNes6ConfigE","espp::QwiicNes::Config"],[68,1,1,"_CPPv4N4espp8QwiicNes6Config9log_levelE","espp::QwiicNes::Config::log_level"],[68,1,1,"_CPPv4N4espp8QwiicNes6Config5writeE","espp::QwiicNes::Config::write"],[68,1,1,"_CPPv4N4espp8QwiicNes6Config10write_readE","espp::QwiicNes::Config::write_read"],[68,1,1,"_CPPv4N4espp8QwiicNes15DEFAULT_ADDRESSE","espp::QwiicNes::DEFAULT_ADDRESS"],[68,3,1,"_CPPv4N4espp8QwiicNes8QwiicNesERK6Config","espp::QwiicNes::QwiicNes"],[68,4,1,"_CPPv4N4espp8QwiicNes8QwiicNesERK6Config","espp::QwiicNes::QwiicNes::config"],[68,3,1,"_CPPv4NK4espp8QwiicNes16get_button_stateEv","espp::QwiicNes::get_button_state"],[68,3,1,"_CPPv4N4espp8QwiicNes10is_pressedE7uint8_t6Button","espp::QwiicNes::is_pressed"],[68,3,1,"_CPPv4NK4espp8QwiicNes10is_pressedE6Button","espp::QwiicNes::is_pressed"],[68,4,1,"_CPPv4N4espp8QwiicNes10is_pressedE7uint8_t6Button","espp::QwiicNes::is_pressed::button"],[68,4,1,"_CPPv4NK4espp8QwiicNes10is_pressedE6Button","espp::QwiicNes::is_pressed::button"],[68,4,1,"_CPPv4N4espp8QwiicNes10is_pressedE7uint8_t6Button","espp::QwiicNes::is_pressed::state"],[68,3,1,"_CPPv4NK4espp8QwiicNes12read_addressERNSt10error_codeE","espp::QwiicNes::read_address"],[68,4,1,"_CPPv4NK4espp8QwiicNes12read_addressERNSt10error_codeE","espp::QwiicNes::read_address::ec"],[68,3,1,"_CPPv4NK4espp8QwiicNes18read_current_stateERNSt10error_codeE","espp::QwiicNes::read_current_state"],[68,4,1,"_CPPv4NK4espp8QwiicNes18read_current_stateERNSt10error_codeE","espp::QwiicNes::read_current_state::ec"],[68,3,1,"_CPPv4N4espp8QwiicNes6updateERNSt10error_codeE","espp::QwiicNes::update"],[68,4,1,"_CPPv4N4espp8QwiicNes6updateERNSt10error_codeE","espp::QwiicNes::update::ec"],[68,3,1,"_CPPv4N4espp8QwiicNes14update_addressE7uint8_tRNSt10error_codeE","espp::QwiicNes::update_address"],[68,4,1,"_CPPv4N4espp8QwiicNes14update_addressE7uint8_tRNSt10error_codeE","espp::QwiicNes::update_address::ec"],[68,4,1,"_CPPv4N4espp8QwiicNes14update_addressE7uint8_tRNSt10error_codeE","espp::QwiicNes::update_address::new_address"],[68,8,1,"_CPPv4N4espp8QwiicNes8write_fnE","espp::QwiicNes::write_fn"],[68,8,1,"_CPPv4N4espp8QwiicNes13write_read_fnE","espp::QwiicNes::write_read_fn"],[57,2,1,"_CPPv4I0EN4espp11RangeMapperE","espp::RangeMapper"],[57,2,1,"_CPPv4N4espp11RangeMapper6ConfigE","espp::RangeMapper::Config"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config6centerE","espp::RangeMapper::Config::center"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config8deadbandE","espp::RangeMapper::Config::deadband"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config12invert_inputE","espp::RangeMapper::Config::invert_input"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config13invert_outputE","espp::RangeMapper::Config::invert_output"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config7maximumE","espp::RangeMapper::Config::maximum"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config7minimumE","espp::RangeMapper::Config::minimum"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config13output_centerE","espp::RangeMapper::Config::output_center"],[57,1,1,"_CPPv4N4espp11RangeMapper6Config12output_rangeE","espp::RangeMapper::Config::output_range"],[57,3,1,"_CPPv4N4espp11RangeMapper11RangeMapperERK6Config","espp::RangeMapper::RangeMapper"],[57,4,1,"_CPPv4N4espp11RangeMapper11RangeMapperERK6Config","espp::RangeMapper::RangeMapper::config"],[57,5,1,"_CPPv4I0EN4espp11RangeMapperE","espp::RangeMapper::T"],[57,3,1,"_CPPv4N4espp11RangeMapper9configureERK6Config","espp::RangeMapper::configure"],[57,4,1,"_CPPv4N4espp11RangeMapper9configureERK6Config","espp::RangeMapper::configure::config"],[57,3,1,"_CPPv4NK4espp11RangeMapper17get_output_centerEv","espp::RangeMapper::get_output_center"],[57,3,1,"_CPPv4NK4espp11RangeMapper14get_output_maxEv","espp::RangeMapper::get_output_max"],[57,3,1,"_CPPv4NK4espp11RangeMapper14get_output_minEv","espp::RangeMapper::get_output_min"],[57,3,1,"_CPPv4NK4espp11RangeMapper16get_output_rangeEv","espp::RangeMapper::get_output_range"],[57,3,1,"_CPPv4N4espp11RangeMapper3mapERK1T","espp::RangeMapper::map"],[57,4,1,"_CPPv4N4espp11RangeMapper3mapERK1T","espp::RangeMapper::map::v"],[12,2,1,"_CPPv4N4espp3RgbE","espp::Rgb"],[12,3,1,"_CPPv4N4espp3Rgb3RgbERK3Hsv","espp::Rgb::Rgb"],[12,3,1,"_CPPv4N4espp3Rgb3RgbERK3Rgb","espp::Rgb::Rgb"],[12,3,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb"],[12,4,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb::b"],[12,4,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb::g"],[12,4,1,"_CPPv4N4espp3Rgb3RgbERK3Hsv","espp::Rgb::Rgb::hsv"],[12,4,1,"_CPPv4N4espp3Rgb3RgbERKfRKfRKf","espp::Rgb::Rgb::r"],[12,4,1,"_CPPv4N4espp3Rgb3RgbERK3Rgb","espp::Rgb::Rgb::rgb"],[12,1,1,"_CPPv4N4espp3Rgb1bE","espp::Rgb::b"],[12,1,1,"_CPPv4N4espp3Rgb1gE","espp::Rgb::g"],[12,3,1,"_CPPv4NK4espp3Rgb3hsvEv","espp::Rgb::hsv"],[12,3,1,"_CPPv4NK4espp3RgbplERK3Rgb","espp::Rgb::operator+"],[12,4,1,"_CPPv4NK4espp3RgbplERK3Rgb","espp::Rgb::operator+::rhs"],[12,3,1,"_CPPv4N4espp3RgbpLERK3Rgb","espp::Rgb::operator+="],[12,4,1,"_CPPv4N4espp3RgbpLERK3Rgb","espp::Rgb::operator+=::rhs"],[12,1,1,"_CPPv4N4espp3Rgb1rE","espp::Rgb::r"],[69,2,1,"_CPPv4N4espp3RmtE","espp::Rmt"],[69,2,1,"_CPPv4N4espp3Rmt6ConfigE","espp::Rmt::Config"],[69,1,1,"_CPPv4N4espp3Rmt6Config10block_sizeE","espp::Rmt::Config::block_size"],[69,1,1,"_CPPv4N4espp3Rmt6Config9clock_srcE","espp::Rmt::Config::clock_src"],[69,1,1,"_CPPv4N4espp3Rmt6Config11dma_enabledE","espp::Rmt::Config::dma_enabled"],[69,1,1,"_CPPv4N4espp3Rmt6Config8gpio_numE","espp::Rmt::Config::gpio_num"],[69,1,1,"_CPPv4N4espp3Rmt6Config9log_levelE","espp::Rmt::Config::log_level"],[69,1,1,"_CPPv4N4espp3Rmt6Config13resolution_hzE","espp::Rmt::Config::resolution_hz"],[69,1,1,"_CPPv4N4espp3Rmt6Config23transaction_queue_depthE","espp::Rmt::Config::transaction_queue_depth"],[69,3,1,"_CPPv4N4espp3Rmt3RmtERK6Config","espp::Rmt::Rmt"],[69,4,1,"_CPPv4N4espp3Rmt3RmtERK6Config","espp::Rmt::Rmt::config"],[69,3,1,"_CPPv4N4espp3Rmt8transmitEPK7uint8_t6size_t","espp::Rmt::transmit"],[69,4,1,"_CPPv4N4espp3Rmt8transmitEPK7uint8_t6size_t","espp::Rmt::transmit::data"],[69,4,1,"_CPPv4N4espp3Rmt8transmitEPK7uint8_t6size_t","espp::Rmt::transmit::length"],[69,3,1,"_CPPv4N4espp3RmtD0Ev","espp::Rmt::~Rmt"],[69,2,1,"_CPPv4N4espp10RmtEncoderE","espp::RmtEncoder"],[69,2,1,"_CPPv4N4espp10RmtEncoder6ConfigE","espp::RmtEncoder::Config"],[69,1,1,"_CPPv4N4espp10RmtEncoder6Config20bytes_encoder_configE","espp::RmtEncoder::Config::bytes_encoder_config"],[69,1,1,"_CPPv4N4espp10RmtEncoder6Config3delE","espp::RmtEncoder::Config::del"],[69,1,1,"_CPPv4N4espp10RmtEncoder6Config6encodeE","espp::RmtEncoder::Config::encode"],[69,1,1,"_CPPv4N4espp10RmtEncoder6Config5resetE","espp::RmtEncoder::Config::reset"],[69,3,1,"_CPPv4N4espp10RmtEncoder10RmtEncoderERK6Config","espp::RmtEncoder::RmtEncoder"],[69,4,1,"_CPPv4N4espp10RmtEncoder10RmtEncoderERK6Config","espp::RmtEncoder::RmtEncoder::config"],[69,8,1,"_CPPv4N4espp10RmtEncoder9delete_fnE","espp::RmtEncoder::delete_fn"],[69,8,1,"_CPPv4N4espp10RmtEncoder9encode_fnE","espp::RmtEncoder::encode_fn"],[69,3,1,"_CPPv4NK4espp10RmtEncoder6handleEv","espp::RmtEncoder::handle"],[69,8,1,"_CPPv4N4espp10RmtEncoder8reset_fnE","espp::RmtEncoder::reset_fn"],[69,3,1,"_CPPv4N4espp10RmtEncoderD0Ev","espp::RmtEncoder::~RmtEncoder"],[72,2,1,"_CPPv4N4espp10RtcpPacketE","espp::RtcpPacket"],[72,2,1,"_CPPv4N4espp13RtpJpegPacketE","espp::RtpJpegPacket"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::data"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::frag_type"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::frag_type"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::height"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::height"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::offset"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q0"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::q1"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::scan_data"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::scan_data"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::type_specific"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::type_specific"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiKiNSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::width"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket13RtpJpegPacketEKiKiKiKiKiNSt11string_viewENSt11string_viewENSt11string_viewE","espp::RtpJpegPacket::RtpJpegPacket::width"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket8get_dataEv","espp::RtpJpegPacket::get_data"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket10get_heightEv","espp::RtpJpegPacket::get_height"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket13get_jpeg_dataEv","espp::RtpJpegPacket::get_jpeg_data"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket16get_mjpeg_headerEv","espp::RtpJpegPacket::get_mjpeg_header"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket16get_num_q_tablesEv","espp::RtpJpegPacket::get_num_q_tables"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket10get_offsetEv","espp::RtpJpegPacket::get_offset"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket10get_packetEv","espp::RtpJpegPacket::get_packet"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket11get_payloadEv","espp::RtpJpegPacket::get_payload"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket5get_qEv","espp::RtpJpegPacket::get_q"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket11get_q_tableEi","espp::RtpJpegPacket::get_q_table"],[72,4,1,"_CPPv4NK4espp13RtpJpegPacket11get_q_tableEi","espp::RtpJpegPacket::get_q_table::index"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket14get_rpt_headerEv","espp::RtpJpegPacket::get_rpt_header"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket19get_rtp_header_sizeEv","espp::RtpJpegPacket::get_rtp_header_size"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket17get_type_specificEv","espp::RtpJpegPacket::get_type_specific"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket11get_versionEv","espp::RtpJpegPacket::get_version"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket9get_widthEv","espp::RtpJpegPacket::get_width"],[72,3,1,"_CPPv4NK4espp13RtpJpegPacket12has_q_tablesEv","espp::RtpJpegPacket::has_q_tables"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket9serializeEv","espp::RtpJpegPacket::serialize"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket11set_payloadENSt11string_viewE","espp::RtpJpegPacket::set_payload"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket11set_payloadENSt11string_viewE","espp::RtpJpegPacket::set_payload::payload"],[72,3,1,"_CPPv4N4espp13RtpJpegPacket11set_versionEi","espp::RtpJpegPacket::set_version"],[72,4,1,"_CPPv4N4espp13RtpJpegPacket11set_versionEi","espp::RtpJpegPacket::set_version::version"],[72,2,1,"_CPPv4N4espp9RtpPacketE","espp::RtpPacket"],[72,3,1,"_CPPv4N4espp9RtpPacket9RtpPacketE6size_t","espp::RtpPacket::RtpPacket"],[72,3,1,"_CPPv4N4espp9RtpPacket9RtpPacketENSt11string_viewE","espp::RtpPacket::RtpPacket"],[72,3,1,"_CPPv4N4espp9RtpPacket9RtpPacketEv","espp::RtpPacket::RtpPacket"],[72,4,1,"_CPPv4N4espp9RtpPacket9RtpPacketENSt11string_viewE","espp::RtpPacket::RtpPacket::data"],[72,4,1,"_CPPv4N4espp9RtpPacket9RtpPacketE6size_t","espp::RtpPacket::RtpPacket::payload_size"],[72,3,1,"_CPPv4NK4espp9RtpPacket8get_dataEv","espp::RtpPacket::get_data"],[72,3,1,"_CPPv4N4espp9RtpPacket10get_packetEv","espp::RtpPacket::get_packet"],[72,3,1,"_CPPv4NK4espp9RtpPacket11get_payloadEv","espp::RtpPacket::get_payload"],[72,3,1,"_CPPv4NK4espp9RtpPacket14get_rpt_headerEv","espp::RtpPacket::get_rpt_header"],[72,3,1,"_CPPv4NK4espp9RtpPacket19get_rtp_header_sizeEv","espp::RtpPacket::get_rtp_header_size"],[72,3,1,"_CPPv4NK4espp9RtpPacket11get_versionEv","espp::RtpPacket::get_version"],[72,3,1,"_CPPv4N4espp9RtpPacket9serializeEv","espp::RtpPacket::serialize"],[72,3,1,"_CPPv4N4espp9RtpPacket11set_payloadENSt11string_viewE","espp::RtpPacket::set_payload"],[72,4,1,"_CPPv4N4espp9RtpPacket11set_payloadENSt11string_viewE","espp::RtpPacket::set_payload::payload"],[72,3,1,"_CPPv4N4espp9RtpPacket11set_versionEi","espp::RtpPacket::set_version"],[72,4,1,"_CPPv4N4espp9RtpPacket11set_versionEi","espp::RtpPacket::set_version::version"],[72,2,1,"_CPPv4N4espp10RtspClientE","espp::RtspClient"],[72,2,1,"_CPPv4N4espp10RtspClient6ConfigE","espp::RtspClient::Config"],[72,1,1,"_CPPv4N4espp10RtspClient6Config9log_levelE","espp::RtspClient::Config::log_level"],[72,1,1,"_CPPv4N4espp10RtspClient6Config13on_jpeg_frameE","espp::RtspClient::Config::on_jpeg_frame"],[72,1,1,"_CPPv4N4espp10RtspClient6Config4pathE","espp::RtspClient::Config::path"],[72,1,1,"_CPPv4N4espp10RtspClient6Config9rtsp_portE","espp::RtspClient::Config::rtsp_port"],[72,1,1,"_CPPv4N4espp10RtspClient6Config14server_addressE","espp::RtspClient::Config::server_address"],[72,3,1,"_CPPv4N4espp10RtspClient10RtspClientERK6Config","espp::RtspClient::RtspClient"],[72,4,1,"_CPPv4N4espp10RtspClient10RtspClientERK6Config","espp::RtspClient::RtspClient::config"],[72,3,1,"_CPPv4N4espp10RtspClient7connectERNSt10error_codeE","espp::RtspClient::connect"],[72,4,1,"_CPPv4N4espp10RtspClient7connectERNSt10error_codeE","espp::RtspClient::connect::ec"],[72,3,1,"_CPPv4N4espp10RtspClient8describeERNSt10error_codeE","espp::RtspClient::describe"],[72,4,1,"_CPPv4N4espp10RtspClient8describeERNSt10error_codeE","espp::RtspClient::describe::ec"],[72,3,1,"_CPPv4N4espp10RtspClient10disconnectERNSt10error_codeE","espp::RtspClient::disconnect"],[72,4,1,"_CPPv4N4espp10RtspClient10disconnectERNSt10error_codeE","espp::RtspClient::disconnect::ec"],[72,8,1,"_CPPv4N4espp10RtspClient21jpeg_frame_callback_tE","espp::RtspClient::jpeg_frame_callback_t"],[72,3,1,"_CPPv4N4espp10RtspClient5pauseERNSt10error_codeE","espp::RtspClient::pause"],[72,4,1,"_CPPv4N4espp10RtspClient5pauseERNSt10error_codeE","espp::RtspClient::pause::ec"],[72,3,1,"_CPPv4N4espp10RtspClient4playERNSt10error_codeE","espp::RtspClient::play"],[72,4,1,"_CPPv4N4espp10RtspClient4playERNSt10error_codeE","espp::RtspClient::play::ec"],[72,3,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request"],[72,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::ec"],[72,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::extra_headers"],[72,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::method"],[72,4,1,"_CPPv4N4espp10RtspClient12send_requestERKNSt6stringERKNSt6stringERKNSt13unordered_mapINSt6stringENSt6stringEEERNSt10error_codeE","espp::RtspClient::send_request::path"],[72,3,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup"],[72,3,1,"_CPPv4N4espp10RtspClient5setupERNSt10error_codeE","espp::RtspClient::setup"],[72,4,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup::ec"],[72,4,1,"_CPPv4N4espp10RtspClient5setupERNSt10error_codeE","espp::RtspClient::setup::ec"],[72,4,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup::rtcp_port"],[72,4,1,"_CPPv4N4espp10RtspClient5setupE6size_t6size_tRNSt10error_codeE","espp::RtspClient::setup::rtp_port"],[72,3,1,"_CPPv4N4espp10RtspClient8teardownERNSt10error_codeE","espp::RtspClient::teardown"],[72,4,1,"_CPPv4N4espp10RtspClient8teardownERNSt10error_codeE","espp::RtspClient::teardown::ec"],[72,3,1,"_CPPv4N4espp10RtspClientD0Ev","espp::RtspClient::~RtspClient"],[72,2,1,"_CPPv4N4espp10RtspServerE","espp::RtspServer"],[72,2,1,"_CPPv4N4espp10RtspServer6ConfigE","espp::RtspServer::Config"],[72,1,1,"_CPPv4N4espp10RtspServer6Config9log_levelE","espp::RtspServer::Config::log_level"],[72,1,1,"_CPPv4N4espp10RtspServer6Config13max_data_sizeE","espp::RtspServer::Config::max_data_size"],[72,1,1,"_CPPv4N4espp10RtspServer6Config4pathE","espp::RtspServer::Config::path"],[72,1,1,"_CPPv4N4espp10RtspServer6Config4portE","espp::RtspServer::Config::port"],[72,1,1,"_CPPv4N4espp10RtspServer6Config14server_addressE","espp::RtspServer::Config::server_address"],[72,3,1,"_CPPv4N4espp10RtspServer10RtspServerERK6Config","espp::RtspServer::RtspServer"],[72,4,1,"_CPPv4N4espp10RtspServer10RtspServerERK6Config","espp::RtspServer::RtspServer::config"],[72,3,1,"_CPPv4N4espp10RtspServer10send_frameERK9JpegFrame","espp::RtspServer::send_frame"],[72,4,1,"_CPPv4N4espp10RtspServer10send_frameERK9JpegFrame","espp::RtspServer::send_frame::frame"],[72,3,1,"_CPPv4N4espp10RtspServer21set_session_log_levelEN6Logger9VerbosityE","espp::RtspServer::set_session_log_level"],[72,4,1,"_CPPv4N4espp10RtspServer21set_session_log_levelEN6Logger9VerbosityE","espp::RtspServer::set_session_log_level::log_level"],[72,3,1,"_CPPv4N4espp10RtspServer5startEv","espp::RtspServer::start"],[72,3,1,"_CPPv4N4espp10RtspServer4stopEv","espp::RtspServer::stop"],[72,3,1,"_CPPv4N4espp10RtspServerD0Ev","espp::RtspServer::~RtspServer"],[72,2,1,"_CPPv4N4espp11RtspSessionE","espp::RtspSession"],[72,2,1,"_CPPv4N4espp11RtspSession6ConfigE","espp::RtspSession::Config"],[72,1,1,"_CPPv4N4espp11RtspSession6Config9log_levelE","espp::RtspSession::Config::log_level"],[72,1,1,"_CPPv4N4espp11RtspSession6Config9rtsp_pathE","espp::RtspSession::Config::rtsp_path"],[72,1,1,"_CPPv4N4espp11RtspSession6Config14server_addressE","espp::RtspSession::Config::server_address"],[72,3,1,"_CPPv4N4espp11RtspSession11RtspSessionENSt10unique_ptrI9TcpSocketEERK6Config","espp::RtspSession::RtspSession"],[72,4,1,"_CPPv4N4espp11RtspSession11RtspSessionENSt10unique_ptrI9TcpSocketEERK6Config","espp::RtspSession::RtspSession::config"],[72,4,1,"_CPPv4N4espp11RtspSession11RtspSessionENSt10unique_ptrI9TcpSocketEERK6Config","espp::RtspSession::RtspSession::control_socket"],[72,3,1,"_CPPv4NK4espp11RtspSession14get_session_idEv","espp::RtspSession::get_session_id"],[72,3,1,"_CPPv4NK4espp11RtspSession9is_activeEv","espp::RtspSession::is_active"],[72,3,1,"_CPPv4NK4espp11RtspSession9is_closedEv","espp::RtspSession::is_closed"],[72,3,1,"_CPPv4NK4espp11RtspSession12is_connectedEv","espp::RtspSession::is_connected"],[72,3,1,"_CPPv4N4espp11RtspSession5pauseEv","espp::RtspSession::pause"],[72,3,1,"_CPPv4N4espp11RtspSession4playEv","espp::RtspSession::play"],[72,3,1,"_CPPv4N4espp11RtspSession16send_rtcp_packetERK10RtcpPacket","espp::RtspSession::send_rtcp_packet"],[72,4,1,"_CPPv4N4espp11RtspSession16send_rtcp_packetERK10RtcpPacket","espp::RtspSession::send_rtcp_packet::packet"],[72,3,1,"_CPPv4N4espp11RtspSession15send_rtp_packetERK9RtpPacket","espp::RtspSession::send_rtp_packet"],[72,4,1,"_CPPv4N4espp11RtspSession15send_rtp_packetERK9RtpPacket","espp::RtspSession::send_rtp_packet::packet"],[72,3,1,"_CPPv4N4espp11RtspSession8teardownEv","espp::RtspSession::teardown"],[61,2,1,"_CPPv4N4espp6SocketE","espp::Socket"],[61,2,1,"_CPPv4N4espp6Socket4InfoE","espp::Socket::Info"],[61,1,1,"_CPPv4N4espp6Socket4Info7addressE","espp::Socket::Info::address"],[61,3,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK11sockaddr_in","espp::Socket::Info::from_sockaddr"],[61,3,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK12sockaddr_in6","espp::Socket::Info::from_sockaddr"],[61,3,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK16sockaddr_storage","espp::Socket::Info::from_sockaddr"],[61,4,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK11sockaddr_in","espp::Socket::Info::from_sockaddr::source_address"],[61,4,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK12sockaddr_in6","espp::Socket::Info::from_sockaddr::source_address"],[61,4,1,"_CPPv4N4espp6Socket4Info13from_sockaddrERK16sockaddr_storage","espp::Socket::Info::from_sockaddr::source_address"],[61,3,1,"_CPPv4N4espp6Socket4Info9init_ipv4ERKNSt6stringE6size_t","espp::Socket::Info::init_ipv4"],[61,4,1,"_CPPv4N4espp6Socket4Info9init_ipv4ERKNSt6stringE6size_t","espp::Socket::Info::init_ipv4::addr"],[61,4,1,"_CPPv4N4espp6Socket4Info9init_ipv4ERKNSt6stringE6size_t","espp::Socket::Info::init_ipv4::prt"],[61,3,1,"_CPPv4N4espp6Socket4Info8ipv4_ptrEv","espp::Socket::Info::ipv4_ptr"],[61,3,1,"_CPPv4N4espp6Socket4Info8ipv6_ptrEv","espp::Socket::Info::ipv6_ptr"],[61,1,1,"_CPPv4N4espp6Socket4Info4portE","espp::Socket::Info::port"],[61,3,1,"_CPPv4N4espp6Socket4Info6updateEv","espp::Socket::Info::update"],[61,3,1,"_CPPv4N4espp6Socket6SocketE4TypeRKN6Logger6ConfigE","espp::Socket::Socket"],[61,3,1,"_CPPv4N4espp6Socket6SocketEiRKN6Logger6ConfigE","espp::Socket::Socket"],[61,4,1,"_CPPv4N4espp6Socket6SocketE4TypeRKN6Logger6ConfigE","espp::Socket::Socket::logger_config"],[61,4,1,"_CPPv4N4espp6Socket6SocketEiRKN6Logger6ConfigE","espp::Socket::Socket::logger_config"],[61,4,1,"_CPPv4N4espp6Socket6SocketEiRKN6Logger6ConfigE","espp::Socket::Socket::socket_fd"],[61,4,1,"_CPPv4N4espp6Socket6SocketE4TypeRKN6Logger6ConfigE","espp::Socket::Socket::type"],[61,3,1,"_CPPv4N4espp6Socket19add_multicast_groupERKNSt6stringE","espp::Socket::add_multicast_group"],[61,4,1,"_CPPv4N4espp6Socket19add_multicast_groupERKNSt6stringE","espp::Socket::add_multicast_group::multicast_group"],[61,3,1,"_CPPv4N4espp6Socket12enable_reuseEv","espp::Socket::enable_reuse"],[61,3,1,"_CPPv4N4espp6Socket13get_ipv4_infoEv","espp::Socket::get_ipv4_info"],[61,3,1,"_CPPv4N4espp6Socket8is_validEi","espp::Socket::is_valid"],[61,3,1,"_CPPv4NK4espp6Socket8is_validEv","espp::Socket::is_valid"],[61,4,1,"_CPPv4N4espp6Socket8is_validEi","espp::Socket::is_valid::socket_fd"],[61,3,1,"_CPPv4N4espp6Socket14make_multicastE7uint8_t7uint8_t","espp::Socket::make_multicast"],[61,4,1,"_CPPv4N4espp6Socket14make_multicastE7uint8_t7uint8_t","espp::Socket::make_multicast::loopback_enabled"],[61,4,1,"_CPPv4N4espp6Socket14make_multicastE7uint8_t7uint8_t","espp::Socket::make_multicast::time_to_live"],[61,8,1,"_CPPv4N4espp6Socket19receive_callback_fnE","espp::Socket::receive_callback_fn"],[61,8,1,"_CPPv4N4espp6Socket20response_callback_fnE","espp::Socket::response_callback_fn"],[61,3,1,"_CPPv4N4espp6Socket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::Socket::set_receive_timeout"],[61,4,1,"_CPPv4N4espp6Socket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::Socket::set_receive_timeout::timeout"],[61,3,1,"_CPPv4N4espp6SocketD0Ev","espp::Socket::~Socket"],[29,2,1,"_CPPv4I_6size_t0EN4espp9SosFilterE","espp::SosFilter"],[29,5,1,"_CPPv4I_6size_t0EN4espp9SosFilterE","espp::SosFilter::N"],[29,5,1,"_CPPv4I_6size_t0EN4espp9SosFilterE","espp::SosFilter::SectionImpl"],[29,3,1,"_CPPv4N4espp9SosFilter9SosFilterERKNSt5arrayI16TransferFunctionIXL3EEE1NEE","espp::SosFilter::SosFilter"],[29,4,1,"_CPPv4N4espp9SosFilter9SosFilterERKNSt5arrayI16TransferFunctionIXL3EEE1NEE","espp::SosFilter::SosFilter::config"],[29,3,1,"_CPPv4N4espp9SosFilterclEf","espp::SosFilter::operator()"],[29,4,1,"_CPPv4N4espp9SosFilterclEf","espp::SosFilter::operator()::input"],[29,3,1,"_CPPv4N4espp9SosFilter6updateEf","espp::SosFilter::update"],[29,4,1,"_CPPv4N4espp9SosFilter6updateEf","espp::SosFilter::update::input"],[66,2,1,"_CPPv4N4espp6St25dvE","espp::St25dv"],[66,2,1,"_CPPv4N4espp6St25dv6ConfigE","espp::St25dv::Config"],[66,1,1,"_CPPv4N4espp6St25dv6Config9auto_initE","espp::St25dv::Config::auto_init"],[66,1,1,"_CPPv4N4espp6St25dv6Config9log_levelE","espp::St25dv::Config::log_level"],[66,1,1,"_CPPv4N4espp6St25dv6Config4readE","espp::St25dv::Config::read"],[66,1,1,"_CPPv4N4espp6St25dv6Config5writeE","espp::St25dv::Config::write"],[66,1,1,"_CPPv4N4espp6St25dv12DATA_ADDRESSE","espp::St25dv::DATA_ADDRESS"],[66,2,1,"_CPPv4N4espp6St25dv7EH_CTRLE","espp::St25dv::EH_CTRL"],[66,2,1,"_CPPv4N4espp6St25dv3GPOE","espp::St25dv::GPO"],[66,2,1,"_CPPv4N4espp6St25dv6IT_STSE","espp::St25dv::IT_STS"],[66,2,1,"_CPPv4N4espp6St25dv6IT_STSE","espp::St25dv::IT_STS"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS13FIELD_FALLINGE","espp::St25dv::IT_STS::FIELD_FALLING"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS13FIELD_FALLINGE","espp::St25dv::IT_STS::FIELD_FALLING"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS12FIELD_RISINGE","espp::St25dv::IT_STS::FIELD_RISING"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS12FIELD_RISINGE","espp::St25dv::IT_STS::FIELD_RISING"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS11RF_ACTIVITYE","espp::St25dv::IT_STS::RF_ACTIVITY"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS11RF_ACTIVITYE","espp::St25dv::IT_STS::RF_ACTIVITY"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_GET_MSGE","espp::St25dv::IT_STS::RF_GET_MSG"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_GET_MSGE","espp::St25dv::IT_STS::RF_GET_MSG"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS12RF_INTTERUPTE","espp::St25dv::IT_STS::RF_INTTERUPT"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS12RF_INTTERUPTE","espp::St25dv::IT_STS::RF_INTTERUPT"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_PUT_MSGE","espp::St25dv::IT_STS::RF_PUT_MSG"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS10RF_PUT_MSGE","espp::St25dv::IT_STS::RF_PUT_MSG"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS7RF_USERE","espp::St25dv::IT_STS::RF_USER"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS7RF_USERE","espp::St25dv::IT_STS::RF_USER"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS8RF_WRITEE","espp::St25dv::IT_STS::RF_WRITE"],[66,1,1,"_CPPv4N4espp6St25dv6IT_STS8RF_WRITEE","espp::St25dv::IT_STS::RF_WRITE"],[66,2,1,"_CPPv4N4espp6St25dv7MB_CTRLE","espp::St25dv::MB_CTRL"],[66,1,1,"_CPPv4N4espp6St25dv12SYST_ADDRESSE","espp::St25dv::SYST_ADDRESS"],[66,3,1,"_CPPv4N4espp6St25dv6St25dvERK6Config","espp::St25dv::St25dv"],[66,4,1,"_CPPv4N4espp6St25dv6St25dvERK6Config","espp::St25dv::St25dv::config"],[66,3,1,"_CPPv4N4espp6St25dv14get_ftm_lengthERNSt10error_codeE","espp::St25dv::get_ftm_length"],[66,4,1,"_CPPv4N4espp6St25dv14get_ftm_lengthERNSt10error_codeE","espp::St25dv::get_ftm_length::ec"],[66,3,1,"_CPPv4N4espp6St25dv20get_interrupt_statusERNSt10error_codeE","espp::St25dv::get_interrupt_status"],[66,4,1,"_CPPv4N4espp6St25dv20get_interrupt_statusERNSt10error_codeE","espp::St25dv::get_interrupt_status::ec"],[66,3,1,"_CPPv4N4espp6St25dv10initializeERNSt10error_codeE","espp::St25dv::initialize"],[66,4,1,"_CPPv4N4espp6St25dv10initializeERNSt10error_codeE","espp::St25dv::initialize::ec"],[66,3,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_tRNSt10error_codeE","espp::St25dv::read"],[66,3,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::read"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_tRNSt10error_codeE","espp::St25dv::read::data"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::read::data"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_tRNSt10error_codeE","espp::St25dv::read::ec"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::read::ec"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_tRNSt10error_codeE","espp::St25dv::read::length"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::read::length"],[66,4,1,"_CPPv4N4espp6St25dv4readEP7uint8_t7uint8_t8uint16_tRNSt10error_codeE","espp::St25dv::read::offset"],[66,8,1,"_CPPv4N4espp6St25dv7read_fnE","espp::St25dv::read_fn"],[66,3,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::receive"],[66,4,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::receive::data"],[66,4,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::receive::ec"],[66,4,1,"_CPPv4N4espp6St25dv7receiveEP7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::receive::length"],[66,3,1,"_CPPv4N4espp6St25dv10set_recordER4NdefRNSt10error_codeE","espp::St25dv::set_record"],[66,3,1,"_CPPv4N4espp6St25dv10set_recordERKNSt6vectorI7uint8_tEERNSt10error_codeE","espp::St25dv::set_record"],[66,4,1,"_CPPv4N4espp6St25dv10set_recordER4NdefRNSt10error_codeE","espp::St25dv::set_record::ec"],[66,4,1,"_CPPv4N4espp6St25dv10set_recordERKNSt6vectorI7uint8_tEERNSt10error_codeE","espp::St25dv::set_record::ec"],[66,4,1,"_CPPv4N4espp6St25dv10set_recordER4NdefRNSt10error_codeE","espp::St25dv::set_record::record"],[66,4,1,"_CPPv4N4espp6St25dv10set_recordERKNSt6vectorI7uint8_tEERNSt10error_codeE","espp::St25dv::set_record::record_data"],[66,3,1,"_CPPv4N4espp6St25dv11set_recordsERNSt6vectorI4NdefEERNSt10error_codeE","espp::St25dv::set_records"],[66,4,1,"_CPPv4N4espp6St25dv11set_recordsERNSt6vectorI4NdefEERNSt10error_codeE","espp::St25dv::set_records::ec"],[66,4,1,"_CPPv4N4espp6St25dv11set_recordsERNSt6vectorI4NdefEERNSt10error_codeE","espp::St25dv::set_records::records"],[66,3,1,"_CPPv4N4espp6St25dv24start_fast_transfer_modeERNSt10error_codeE","espp::St25dv::start_fast_transfer_mode"],[66,4,1,"_CPPv4N4espp6St25dv24start_fast_transfer_modeERNSt10error_codeE","espp::St25dv::start_fast_transfer_mode::ec"],[66,3,1,"_CPPv4N4espp6St25dv23stop_fast_transfer_modeERNSt10error_codeE","espp::St25dv::stop_fast_transfer_mode"],[66,4,1,"_CPPv4N4espp6St25dv23stop_fast_transfer_modeERNSt10error_codeE","espp::St25dv::stop_fast_transfer_mode::ec"],[66,3,1,"_CPPv4N4espp6St25dv8transferEPK7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::transfer"],[66,4,1,"_CPPv4N4espp6St25dv8transferEPK7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::transfer::data"],[66,4,1,"_CPPv4N4espp6St25dv8transferEPK7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::transfer::ec"],[66,4,1,"_CPPv4N4espp6St25dv8transferEPK7uint8_t7uint8_tRNSt10error_codeE","espp::St25dv::transfer::length"],[66,3,1,"_CPPv4N4espp6St25dv5writeENSt11string_viewERNSt10error_codeE","espp::St25dv::write"],[66,4,1,"_CPPv4N4espp6St25dv5writeENSt11string_viewERNSt10error_codeE","espp::St25dv::write::ec"],[66,4,1,"_CPPv4N4espp6St25dv5writeENSt11string_viewERNSt10error_codeE","espp::St25dv::write::payload"],[66,8,1,"_CPPv4N4espp6St25dv8write_fnE","espp::St25dv::write_fn"],[16,2,1,"_CPPv4N4espp6St7789E","espp::St7789"],[16,3,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear"],[16,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::color"],[16,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::height"],[16,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::width"],[16,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::x"],[16,4,1,"_CPPv4N4espp6St77895clearE6size_t6size_t6size_t6size_t8uint16_t","espp::St7789::clear::y"],[16,3,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill"],[16,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::area"],[16,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::color_map"],[16,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::drv"],[16,4,1,"_CPPv4N4espp6St77894fillEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t8uint32_t","espp::St7789::fill::flags"],[16,3,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush"],[16,4,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush::area"],[16,4,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush::color_map"],[16,4,1,"_CPPv4N4espp6St77895flushEP13lv_disp_drv_tPK9lv_area_tP10lv_color_t","espp::St7789::flush::drv"],[16,3,1,"_CPPv4N4espp6St778910get_offsetERiRi","espp::St7789::get_offset"],[16,4,1,"_CPPv4N4espp6St778910get_offsetERiRi","espp::St7789::get_offset::x"],[16,4,1,"_CPPv4N4espp6St778910get_offsetERiRi","espp::St7789::get_offset::y"],[16,3,1,"_CPPv4N4espp6St778910initializeERKN15display_drivers6ConfigE","espp::St7789::initialize"],[16,4,1,"_CPPv4N4espp6St778910initializeERKN15display_drivers6ConfigE","espp::St7789::initialize::config"],[16,3,1,"_CPPv4N4espp6St778912send_commandE7uint8_t","espp::St7789::send_command"],[16,4,1,"_CPPv4N4espp6St778912send_commandE7uint8_t","espp::St7789::send_command::command"],[16,3,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data"],[16,4,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data::data"],[16,4,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data::flags"],[16,4,1,"_CPPv4N4espp6St77899send_dataEPK7uint8_t6size_t8uint32_t","espp::St7789::send_data::length"],[16,3,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area"],[16,3,1,"_CPPv4N4espp6St778916set_drawing_areaEPK9lv_area_t","espp::St7789::set_drawing_area"],[16,4,1,"_CPPv4N4espp6St778916set_drawing_areaEPK9lv_area_t","espp::St7789::set_drawing_area::area"],[16,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::xe"],[16,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::xs"],[16,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::ye"],[16,4,1,"_CPPv4N4espp6St778916set_drawing_areaE6size_t6size_t6size_t6size_t","espp::St7789::set_drawing_area::ys"],[16,3,1,"_CPPv4N4espp6St778910set_offsetEii","espp::St7789::set_offset"],[16,4,1,"_CPPv4N4espp6St778910set_offsetEii","espp::St7789::set_offset::x"],[16,4,1,"_CPPv4N4espp6St778910set_offsetEii","espp::St7789::set_offset::y"],[43,2,1,"_CPPv4N4espp9TKeyboardE","espp::TKeyboard"],[43,2,1,"_CPPv4N4espp9TKeyboard6ConfigE","espp::TKeyboard::Config"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config7addressE","espp::TKeyboard::Config::address"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config10auto_startE","espp::TKeyboard::Config::auto_start"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config6key_cbE","espp::TKeyboard::Config::key_cb"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config9log_levelE","espp::TKeyboard::Config::log_level"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config16polling_intervalE","espp::TKeyboard::Config::polling_interval"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config4readE","espp::TKeyboard::Config::read"],[43,1,1,"_CPPv4N4espp9TKeyboard6Config5writeE","espp::TKeyboard::Config::write"],[43,1,1,"_CPPv4N4espp9TKeyboard15DEFAULT_ADDRESSE","espp::TKeyboard::DEFAULT_ADDRESS"],[43,3,1,"_CPPv4N4espp9TKeyboard9TKeyboardERK6Config","espp::TKeyboard::TKeyboard"],[43,4,1,"_CPPv4N4espp9TKeyboard9TKeyboardERK6Config","espp::TKeyboard::TKeyboard::config"],[43,3,1,"_CPPv4NK4espp9TKeyboard7get_keyEv","espp::TKeyboard::get_key"],[43,8,1,"_CPPv4N4espp9TKeyboard9key_cb_fnE","espp::TKeyboard::key_cb_fn"],[43,8,1,"_CPPv4N4espp9TKeyboard7read_fnE","espp::TKeyboard::read_fn"],[43,3,1,"_CPPv4N4espp9TKeyboard8read_keyERNSt10error_codeE","espp::TKeyboard::read_key"],[43,4,1,"_CPPv4N4espp9TKeyboard8read_keyERNSt10error_codeE","espp::TKeyboard::read_key::ec"],[43,3,1,"_CPPv4N4espp9TKeyboard5startEv","espp::TKeyboard::start"],[43,3,1,"_CPPv4N4espp9TKeyboard4stopEv","espp::TKeyboard::stop"],[43,8,1,"_CPPv4N4espp9TKeyboard8write_fnE","espp::TKeyboard::write_fn"],[76,2,1,"_CPPv4N4espp4TaskE","espp::Task"],[76,2,1,"_CPPv4N4espp4Task6ConfigE","espp::Task::Config"],[76,1,1,"_CPPv4N4espp4Task6Config8callbackE","espp::Task::Config::callback"],[76,1,1,"_CPPv4N4espp4Task6Config7core_idE","espp::Task::Config::core_id"],[76,1,1,"_CPPv4N4espp4Task6Config9log_levelE","espp::Task::Config::log_level"],[76,1,1,"_CPPv4N4espp4Task6Config4nameE","espp::Task::Config::name"],[76,1,1,"_CPPv4N4espp4Task6Config8priorityE","espp::Task::Config::priority"],[76,1,1,"_CPPv4N4espp4Task6Config16stack_size_bytesE","espp::Task::Config::stack_size_bytes"],[76,2,1,"_CPPv4N4espp4Task12SimpleConfigE","espp::Task::SimpleConfig"],[76,1,1,"_CPPv4N4espp4Task12SimpleConfig8callbackE","espp::Task::SimpleConfig::callback"],[76,1,1,"_CPPv4N4espp4Task12SimpleConfig7core_idE","espp::Task::SimpleConfig::core_id"],[76,1,1,"_CPPv4N4espp4Task12SimpleConfig9log_levelE","espp::Task::SimpleConfig::log_level"],[76,1,1,"_CPPv4N4espp4Task12SimpleConfig4nameE","espp::Task::SimpleConfig::name"],[76,1,1,"_CPPv4N4espp4Task12SimpleConfig8priorityE","espp::Task::SimpleConfig::priority"],[76,1,1,"_CPPv4N4espp4Task12SimpleConfig16stack_size_bytesE","espp::Task::SimpleConfig::stack_size_bytes"],[76,3,1,"_CPPv4N4espp4Task4TaskERK12SimpleConfig","espp::Task::Task"],[76,3,1,"_CPPv4N4espp4Task4TaskERK6Config","espp::Task::Task"],[76,4,1,"_CPPv4N4espp4Task4TaskERK12SimpleConfig","espp::Task::Task::config"],[76,4,1,"_CPPv4N4espp4Task4TaskERK6Config","espp::Task::Task::config"],[76,8,1,"_CPPv4N4espp4Task11callback_fnE","espp::Task::callback_fn"],[76,3,1,"_CPPv4NK4espp4Task10is_runningEv","espp::Task::is_running"],[76,3,1,"_CPPv4NK4espp4Task10is_startedEv","espp::Task::is_started"],[76,3,1,"_CPPv4N4espp4Task11make_uniqueERK12SimpleConfig","espp::Task::make_unique"],[76,3,1,"_CPPv4N4espp4Task11make_uniqueERK6Config","espp::Task::make_unique"],[76,4,1,"_CPPv4N4espp4Task11make_uniqueERK12SimpleConfig","espp::Task::make_unique::config"],[76,4,1,"_CPPv4N4espp4Task11make_uniqueERK6Config","espp::Task::make_unique::config"],[76,8,1,"_CPPv4N4espp4Task18simple_callback_fnE","espp::Task::simple_callback_fn"],[76,3,1,"_CPPv4N4espp4Task5startEv","espp::Task::start"],[76,3,1,"_CPPv4N4espp4Task4stopEv","espp::Task::stop"],[76,3,1,"_CPPv4N4espp4TaskD0Ev","espp::Task::~Task"],[59,2,1,"_CPPv4N4espp11TaskMonitorE","espp::TaskMonitor"],[59,2,1,"_CPPv4N4espp11TaskMonitor6ConfigE","espp::TaskMonitor::Config"],[59,1,1,"_CPPv4N4espp11TaskMonitor6Config6periodE","espp::TaskMonitor::Config::period"],[59,1,1,"_CPPv4N4espp11TaskMonitor6Config21task_stack_size_bytesE","espp::TaskMonitor::Config::task_stack_size_bytes"],[59,3,1,"_CPPv4N4espp11TaskMonitor15get_latest_infoEv","espp::TaskMonitor::get_latest_info"],[62,2,1,"_CPPv4N4espp9TcpSocketE","espp::TcpSocket"],[62,2,1,"_CPPv4N4espp9TcpSocket6ConfigE","espp::TcpSocket::Config"],[62,1,1,"_CPPv4N4espp9TcpSocket6Config9log_levelE","espp::TcpSocket::Config::log_level"],[62,2,1,"_CPPv4N4espp9TcpSocket13ConnectConfigE","espp::TcpSocket::ConnectConfig"],[62,1,1,"_CPPv4N4espp9TcpSocket13ConnectConfig10ip_addressE","espp::TcpSocket::ConnectConfig::ip_address"],[62,1,1,"_CPPv4N4espp9TcpSocket13ConnectConfig4portE","espp::TcpSocket::ConnectConfig::port"],[62,3,1,"_CPPv4N4espp9TcpSocket9TcpSocketERK6Config","espp::TcpSocket::TcpSocket"],[62,4,1,"_CPPv4N4espp9TcpSocket9TcpSocketERK6Config","espp::TcpSocket::TcpSocket::config"],[62,3,1,"_CPPv4N4espp9TcpSocket6acceptEv","espp::TcpSocket::accept"],[62,3,1,"_CPPv4N4espp9TcpSocket19add_multicast_groupERKNSt6stringE","espp::TcpSocket::add_multicast_group"],[62,4,1,"_CPPv4N4espp9TcpSocket19add_multicast_groupERKNSt6stringE","espp::TcpSocket::add_multicast_group::multicast_group"],[62,3,1,"_CPPv4N4espp9TcpSocket4bindEi","espp::TcpSocket::bind"],[62,4,1,"_CPPv4N4espp9TcpSocket4bindEi","espp::TcpSocket::bind::port"],[62,3,1,"_CPPv4N4espp9TcpSocket5closeEv","espp::TcpSocket::close"],[62,3,1,"_CPPv4N4espp9TcpSocket7connectERK13ConnectConfig","espp::TcpSocket::connect"],[62,4,1,"_CPPv4N4espp9TcpSocket7connectERK13ConnectConfig","espp::TcpSocket::connect::connect_config"],[62,3,1,"_CPPv4N4espp9TcpSocket12enable_reuseEv","espp::TcpSocket::enable_reuse"],[62,3,1,"_CPPv4N4espp9TcpSocket13get_ipv4_infoEv","espp::TcpSocket::get_ipv4_info"],[62,3,1,"_CPPv4NK4espp9TcpSocket15get_remote_infoEv","espp::TcpSocket::get_remote_info"],[62,3,1,"_CPPv4NK4espp9TcpSocket12is_connectedEv","espp::TcpSocket::is_connected"],[62,3,1,"_CPPv4N4espp9TcpSocket8is_validEi","espp::TcpSocket::is_valid"],[62,3,1,"_CPPv4NK4espp9TcpSocket8is_validEv","espp::TcpSocket::is_valid"],[62,4,1,"_CPPv4N4espp9TcpSocket8is_validEi","espp::TcpSocket::is_valid::socket_fd"],[62,3,1,"_CPPv4N4espp9TcpSocket6listenEi","espp::TcpSocket::listen"],[62,4,1,"_CPPv4N4espp9TcpSocket6listenEi","espp::TcpSocket::listen::max_pending_connections"],[62,3,1,"_CPPv4N4espp9TcpSocket14make_multicastE7uint8_t7uint8_t","espp::TcpSocket::make_multicast"],[62,4,1,"_CPPv4N4espp9TcpSocket14make_multicastE7uint8_t7uint8_t","espp::TcpSocket::make_multicast::loopback_enabled"],[62,4,1,"_CPPv4N4espp9TcpSocket14make_multicastE7uint8_t7uint8_t","espp::TcpSocket::make_multicast::time_to_live"],[62,3,1,"_CPPv4N4espp9TcpSocket7receiveEP7uint8_t6size_t","espp::TcpSocket::receive"],[62,3,1,"_CPPv4N4espp9TcpSocket7receiveERNSt6vectorI7uint8_tEE6size_t","espp::TcpSocket::receive"],[62,4,1,"_CPPv4N4espp9TcpSocket7receiveEP7uint8_t6size_t","espp::TcpSocket::receive::data"],[62,4,1,"_CPPv4N4espp9TcpSocket7receiveERNSt6vectorI7uint8_tEE6size_t","espp::TcpSocket::receive::data"],[62,4,1,"_CPPv4N4espp9TcpSocket7receiveEP7uint8_t6size_t","espp::TcpSocket::receive::max_num_bytes"],[62,4,1,"_CPPv4N4espp9TcpSocket7receiveERNSt6vectorI7uint8_tEE6size_t","espp::TcpSocket::receive::max_num_bytes"],[62,8,1,"_CPPv4N4espp9TcpSocket19receive_callback_fnE","espp::TcpSocket::receive_callback_fn"],[62,3,1,"_CPPv4N4espp9TcpSocket6reinitEv","espp::TcpSocket::reinit"],[62,8,1,"_CPPv4N4espp9TcpSocket20response_callback_fnE","espp::TcpSocket::response_callback_fn"],[62,3,1,"_CPPv4N4espp9TcpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::TcpSocket::set_receive_timeout"],[62,4,1,"_CPPv4N4espp9TcpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::TcpSocket::set_receive_timeout::timeout"],[62,3,1,"_CPPv4N4espp9TcpSocket8transmitENSt11string_viewERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit"],[62,3,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorI7uint8_tEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit"],[62,3,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorIcEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit"],[62,4,1,"_CPPv4N4espp9TcpSocket8transmitENSt11string_viewERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::data"],[62,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorI7uint8_tEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::data"],[62,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorIcEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::data"],[62,4,1,"_CPPv4N4espp9TcpSocket8transmitENSt11string_viewERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::transmit_config"],[62,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorI7uint8_tEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::transmit_config"],[62,4,1,"_CPPv4N4espp9TcpSocket8transmitERKNSt6vectorIcEERKN6detail17TcpTransmitConfigE","espp::TcpSocket::transmit::transmit_config"],[62,3,1,"_CPPv4N4espp9TcpSocketD0Ev","espp::TcpSocket::~TcpSocket"],[77,2,1,"_CPPv4N4espp10ThermistorE","espp::Thermistor"],[77,2,1,"_CPPv4N4espp10Thermistor6ConfigE","espp::Thermistor::Config"],[77,1,1,"_CPPv4N4espp10Thermistor6Config4betaE","espp::Thermistor::Config::beta"],[77,1,1,"_CPPv4N4espp10Thermistor6Config14divider_configE","espp::Thermistor::Config::divider_config"],[77,1,1,"_CPPv4N4espp10Thermistor6Config21fixed_resistance_ohmsE","espp::Thermistor::Config::fixed_resistance_ohms"],[77,1,1,"_CPPv4N4espp10Thermistor6Config9log_levelE","espp::Thermistor::Config::log_level"],[77,1,1,"_CPPv4N4espp10Thermistor6Config23nominal_resistance_ohmsE","espp::Thermistor::Config::nominal_resistance_ohms"],[77,1,1,"_CPPv4N4espp10Thermistor6Config7read_mvE","espp::Thermistor::Config::read_mv"],[77,1,1,"_CPPv4N4espp10Thermistor6Config9supply_mvE","espp::Thermistor::Config::supply_mv"],[77,6,1,"_CPPv4N4espp10Thermistor21ResistorDividerConfigE","espp::Thermistor::ResistorDividerConfig"],[77,7,1,"_CPPv4N4espp10Thermistor21ResistorDividerConfig5LOWERE","espp::Thermistor::ResistorDividerConfig::LOWER"],[77,7,1,"_CPPv4N4espp10Thermistor21ResistorDividerConfig5UPPERE","espp::Thermistor::ResistorDividerConfig::UPPER"],[77,3,1,"_CPPv4N4espp10Thermistor10ThermistorERK6Config","espp::Thermistor::Thermistor"],[77,4,1,"_CPPv4N4espp10Thermistor10ThermistorERK6Config","espp::Thermistor::Thermistor::config"],[77,3,1,"_CPPv4N4espp10Thermistor11get_celsiusEv","espp::Thermistor::get_celsius"],[77,3,1,"_CPPv4N4espp10Thermistor14get_fahrenheitEv","espp::Thermistor::get_fahrenheit"],[77,3,1,"_CPPv4N4espp10Thermistor10get_kelvinEv","espp::Thermistor::get_kelvin"],[77,3,1,"_CPPv4N4espp10Thermistor14get_resistanceEv","espp::Thermistor::get_resistance"],[77,8,1,"_CPPv4N4espp10Thermistor10read_mv_fnE","espp::Thermistor::read_mv_fn"],[78,2,1,"_CPPv4N4espp5TimerE","espp::Timer"],[78,2,1,"_CPPv4N4espp5Timer6ConfigE","espp::Timer::Config"],[78,1,1,"_CPPv4N4espp5Timer6Config10auto_startE","espp::Timer::Config::auto_start"],[78,1,1,"_CPPv4N4espp5Timer6Config8callbackE","espp::Timer::Config::callback"],[78,1,1,"_CPPv4N4espp5Timer6Config7core_idE","espp::Timer::Config::core_id"],[78,1,1,"_CPPv4N4espp5Timer6Config5delayE","espp::Timer::Config::delay"],[78,1,1,"_CPPv4N4espp5Timer6Config9log_levelE","espp::Timer::Config::log_level"],[78,1,1,"_CPPv4N4espp5Timer6Config4nameE","espp::Timer::Config::name"],[78,1,1,"_CPPv4N4espp5Timer6Config6periodE","espp::Timer::Config::period"],[78,1,1,"_CPPv4N4espp5Timer6Config8priorityE","espp::Timer::Config::priority"],[78,1,1,"_CPPv4N4espp5Timer6Config16stack_size_bytesE","espp::Timer::Config::stack_size_bytes"],[78,3,1,"_CPPv4N4espp5Timer5TimerERK6Config","espp::Timer::Timer"],[78,4,1,"_CPPv4N4espp5Timer5TimerERK6Config","espp::Timer::Timer::config"],[78,8,1,"_CPPv4N4espp5Timer11callback_fnE","espp::Timer::callback_fn"],[78,3,1,"_CPPv4N4espp5Timer6cancelEv","espp::Timer::cancel"],[78,3,1,"_CPPv4NK4espp5Timer10is_runningEv","espp::Timer::is_running"],[78,3,1,"_CPPv4N4espp5Timer5startENSt6chrono8durationIfEE","espp::Timer::start"],[78,3,1,"_CPPv4N4espp5Timer5startEv","espp::Timer::start"],[78,4,1,"_CPPv4N4espp5Timer5startENSt6chrono8durationIfEE","espp::Timer::start::delay"],[78,3,1,"_CPPv4N4espp5Timer4stopEv","espp::Timer::stop"],[78,3,1,"_CPPv4N4espp5TimerD0Ev","espp::Timer::~Timer"],[6,2,1,"_CPPv4N4espp7Tla2528E","espp::Tla2528"],[6,6,1,"_CPPv4N4espp7Tla252810AlertLogicE","espp::Tla2528::AlertLogic"],[6,7,1,"_CPPv4N4espp7Tla252810AlertLogic11ACTIVE_HIGHE","espp::Tla2528::AlertLogic::ACTIVE_HIGH"],[6,7,1,"_CPPv4N4espp7Tla252810AlertLogic10ACTIVE_LOWE","espp::Tla2528::AlertLogic::ACTIVE_LOW"],[6,7,1,"_CPPv4N4espp7Tla252810AlertLogic11PULSED_HIGHE","espp::Tla2528::AlertLogic::PULSED_HIGH"],[6,7,1,"_CPPv4N4espp7Tla252810AlertLogic10PULSED_LOWE","espp::Tla2528::AlertLogic::PULSED_LOW"],[6,6,1,"_CPPv4N4espp7Tla25286AppendE","espp::Tla2528::Append"],[6,7,1,"_CPPv4N4espp7Tla25286Append10CHANNEL_IDE","espp::Tla2528::Append::CHANNEL_ID"],[6,7,1,"_CPPv4N4espp7Tla25286Append4NONEE","espp::Tla2528::Append::NONE"],[6,6,1,"_CPPv4N4espp7Tla25287ChannelE","espp::Tla2528::Channel"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH0E","espp::Tla2528::Channel::CH0"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH1E","espp::Tla2528::Channel::CH1"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH2E","espp::Tla2528::Channel::CH2"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH3E","espp::Tla2528::Channel::CH3"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH4E","espp::Tla2528::Channel::CH4"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH5E","espp::Tla2528::Channel::CH5"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH6E","espp::Tla2528::Channel::CH6"],[6,7,1,"_CPPv4N4espp7Tla25287Channel3CH7E","espp::Tla2528::Channel::CH7"],[6,2,1,"_CPPv4N4espp7Tla25286ConfigE","espp::Tla2528::Config"],[6,1,1,"_CPPv4N4espp7Tla25286Config13analog_inputsE","espp::Tla2528::Config::analog_inputs"],[6,1,1,"_CPPv4N4espp7Tla25286Config6appendE","espp::Tla2528::Config::append"],[6,1,1,"_CPPv4N4espp7Tla25286Config9auto_initE","espp::Tla2528::Config::auto_init"],[6,1,1,"_CPPv4N4espp7Tla25286Config10avdd_voltsE","espp::Tla2528::Config::avdd_volts"],[6,1,1,"_CPPv4N4espp7Tla25286Config14device_addressE","espp::Tla2528::Config::device_address"],[6,1,1,"_CPPv4N4espp7Tla25286Config14digital_inputsE","espp::Tla2528::Config::digital_inputs"],[6,1,1,"_CPPv4N4espp7Tla25286Config20digital_output_modesE","espp::Tla2528::Config::digital_output_modes"],[6,1,1,"_CPPv4N4espp7Tla25286Config21digital_output_valuesE","espp::Tla2528::Config::digital_output_values"],[6,1,1,"_CPPv4N4espp7Tla25286Config15digital_outputsE","espp::Tla2528::Config::digital_outputs"],[6,1,1,"_CPPv4N4espp7Tla25286Config9log_levelE","espp::Tla2528::Config::log_level"],[6,1,1,"_CPPv4N4espp7Tla25286Config4modeE","espp::Tla2528::Config::mode"],[6,1,1,"_CPPv4N4espp7Tla25286Config18oversampling_ratioE","espp::Tla2528::Config::oversampling_ratio"],[6,1,1,"_CPPv4N4espp7Tla25286Config4readE","espp::Tla2528::Config::read"],[6,1,1,"_CPPv4N4espp7Tla25286Config5writeE","espp::Tla2528::Config::write"],[6,1,1,"_CPPv4N4espp7Tla252815DEFAULT_ADDRESSE","espp::Tla2528::DEFAULT_ADDRESS"],[6,6,1,"_CPPv4N4espp7Tla252810DataFormatE","espp::Tla2528::DataFormat"],[6,7,1,"_CPPv4N4espp7Tla252810DataFormat8AVERAGEDE","espp::Tla2528::DataFormat::AVERAGED"],[6,7,1,"_CPPv4N4espp7Tla252810DataFormat3RAWE","espp::Tla2528::DataFormat::RAW"],[6,6,1,"_CPPv4N4espp7Tla25284ModeE","espp::Tla2528::Mode"],[6,7,1,"_CPPv4N4espp7Tla25284Mode8AUTO_SEQE","espp::Tla2528::Mode::AUTO_SEQ"],[6,7,1,"_CPPv4N4espp7Tla25284Mode6MANUALE","espp::Tla2528::Mode::MANUAL"],[6,6,1,"_CPPv4N4espp7Tla252810OutputModeE","espp::Tla2528::OutputMode"],[6,7,1,"_CPPv4N4espp7Tla252810OutputMode10OPEN_DRAINE","espp::Tla2528::OutputMode::OPEN_DRAIN"],[6,7,1,"_CPPv4N4espp7Tla252810OutputMode9PUSH_PULLE","espp::Tla2528::OutputMode::PUSH_PULL"],[6,6,1,"_CPPv4N4espp7Tla252817OversamplingRatioE","espp::Tla2528::OversamplingRatio"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio4NONEE","espp::Tla2528::OversamplingRatio::NONE"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio7OSR_128E","espp::Tla2528::OversamplingRatio::OSR_128"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio6OSR_16E","espp::Tla2528::OversamplingRatio::OSR_16"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio5OSR_2E","espp::Tla2528::OversamplingRatio::OSR_2"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio6OSR_32E","espp::Tla2528::OversamplingRatio::OSR_32"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio5OSR_4E","espp::Tla2528::OversamplingRatio::OSR_4"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio6OSR_64E","espp::Tla2528::OversamplingRatio::OSR_64"],[6,7,1,"_CPPv4N4espp7Tla252817OversamplingRatio5OSR_8E","espp::Tla2528::OversamplingRatio::OSR_8"],[6,3,1,"_CPPv4N4espp7Tla25287Tla2528ERK6Config","espp::Tla2528::Tla2528"],[6,4,1,"_CPPv4N4espp7Tla25287Tla2528ERK6Config","espp::Tla2528::Tla2528::config"],[6,3,1,"_CPPv4N4espp7Tla252810get_all_mvERNSt10error_codeE","espp::Tla2528::get_all_mv"],[6,4,1,"_CPPv4N4espp7Tla252810get_all_mvERNSt10error_codeE","espp::Tla2528::get_all_mv::ec"],[6,3,1,"_CPPv4N4espp7Tla252814get_all_mv_mapERNSt10error_codeE","espp::Tla2528::get_all_mv_map"],[6,4,1,"_CPPv4N4espp7Tla252814get_all_mv_mapERNSt10error_codeE","espp::Tla2528::get_all_mv_map::ec"],[6,3,1,"_CPPv4N4espp7Tla252823get_digital_input_valueE7ChannelRNSt10error_codeE","espp::Tla2528::get_digital_input_value"],[6,4,1,"_CPPv4N4espp7Tla252823get_digital_input_valueE7ChannelRNSt10error_codeE","espp::Tla2528::get_digital_input_value::channel"],[6,4,1,"_CPPv4N4espp7Tla252823get_digital_input_valueE7ChannelRNSt10error_codeE","espp::Tla2528::get_digital_input_value::ec"],[6,3,1,"_CPPv4N4espp7Tla252824get_digital_input_valuesERNSt10error_codeE","espp::Tla2528::get_digital_input_values"],[6,4,1,"_CPPv4N4espp7Tla252824get_digital_input_valuesERNSt10error_codeE","espp::Tla2528::get_digital_input_values::ec"],[6,3,1,"_CPPv4N4espp7Tla25286get_mvE7ChannelRNSt10error_codeE","espp::Tla2528::get_mv"],[6,4,1,"_CPPv4N4espp7Tla25286get_mvE7ChannelRNSt10error_codeE","espp::Tla2528::get_mv::channel"],[6,4,1,"_CPPv4N4espp7Tla25286get_mvE7ChannelRNSt10error_codeE","espp::Tla2528::get_mv::ec"],[6,3,1,"_CPPv4N4espp7Tla252810initializeERNSt10error_codeE","espp::Tla2528::initialize"],[6,4,1,"_CPPv4N4espp7Tla252810initializeERNSt10error_codeE","espp::Tla2528::initialize::ec"],[6,8,1,"_CPPv4N4espp7Tla25287read_fnE","espp::Tla2528::read_fn"],[6,3,1,"_CPPv4N4espp7Tla25285resetERNSt10error_codeE","espp::Tla2528::reset"],[6,4,1,"_CPPv4N4espp7Tla25285resetERNSt10error_codeE","espp::Tla2528::reset::ec"],[6,3,1,"_CPPv4N4espp7Tla252823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Tla2528::set_digital_output_mode"],[6,4,1,"_CPPv4N4espp7Tla252823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Tla2528::set_digital_output_mode::channel"],[6,4,1,"_CPPv4N4espp7Tla252823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Tla2528::set_digital_output_mode::ec"],[6,4,1,"_CPPv4N4espp7Tla252823set_digital_output_modeE7Channel10OutputModeRNSt10error_codeE","espp::Tla2528::set_digital_output_mode::output_mode"],[6,3,1,"_CPPv4N4espp7Tla252824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Tla2528::set_digital_output_value"],[6,4,1,"_CPPv4N4espp7Tla252824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Tla2528::set_digital_output_value::channel"],[6,4,1,"_CPPv4N4espp7Tla252824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Tla2528::set_digital_output_value::ec"],[6,4,1,"_CPPv4N4espp7Tla252824set_digital_output_valueE7ChannelbRNSt10error_codeE","espp::Tla2528::set_digital_output_value::value"],[6,8,1,"_CPPv4N4espp7Tla25288write_fnE","espp::Tla2528::write_fn"],[44,2,1,"_CPPv4N4espp13TouchpadInputE","espp::TouchpadInput"],[44,2,1,"_CPPv4N4espp13TouchpadInput6ConfigE","espp::TouchpadInput::Config"],[44,1,1,"_CPPv4N4espp13TouchpadInput6Config8invert_xE","espp::TouchpadInput::Config::invert_x"],[44,1,1,"_CPPv4N4espp13TouchpadInput6Config8invert_yE","espp::TouchpadInput::Config::invert_y"],[44,1,1,"_CPPv4N4espp13TouchpadInput6Config9log_levelE","espp::TouchpadInput::Config::log_level"],[44,1,1,"_CPPv4N4espp13TouchpadInput6Config7swap_xyE","espp::TouchpadInput::Config::swap_xy"],[44,1,1,"_CPPv4N4espp13TouchpadInput6Config13touchpad_readE","espp::TouchpadInput::Config::touchpad_read"],[44,3,1,"_CPPv4N4espp13TouchpadInput13TouchpadInputERK6Config","espp::TouchpadInput::TouchpadInput"],[44,4,1,"_CPPv4N4espp13TouchpadInput13TouchpadInputERK6Config","espp::TouchpadInput::TouchpadInput::config"],[44,3,1,"_CPPv4N4espp13TouchpadInput28get_home_button_input_deviceEv","espp::TouchpadInput::get_home_button_input_device"],[44,3,1,"_CPPv4N4espp13TouchpadInput25get_touchpad_input_deviceEv","espp::TouchpadInput::get_touchpad_input_device"],[44,8,1,"_CPPv4N4espp13TouchpadInput16touchpad_read_fnE","espp::TouchpadInput::touchpad_read_fn"],[44,3,1,"_CPPv4N4espp13TouchpadInputD0Ev","espp::TouchpadInput::~TouchpadInput"],[45,2,1,"_CPPv4N4espp7Tt21100E","espp::Tt21100"],[45,2,1,"_CPPv4N4espp7Tt211006ConfigE","espp::Tt21100::Config"],[45,1,1,"_CPPv4N4espp7Tt211006Config9log_levelE","espp::Tt21100::Config::log_level"],[45,1,1,"_CPPv4N4espp7Tt211006Config4readE","espp::Tt21100::Config::read"],[45,1,1,"_CPPv4N4espp7Tt2110015DEFAULT_ADDRESSE","espp::Tt21100::DEFAULT_ADDRESS"],[45,3,1,"_CPPv4N4espp7Tt211007Tt21100ERK6Config","espp::Tt21100::Tt21100"],[45,4,1,"_CPPv4N4espp7Tt211007Tt21100ERK6Config","espp::Tt21100::Tt21100::config"],[45,3,1,"_CPPv4NK4espp7Tt2110021get_home_button_stateEv","espp::Tt21100::get_home_button_state"],[45,3,1,"_CPPv4NK4espp7Tt2110020get_num_touch_pointsEv","espp::Tt21100::get_num_touch_points"],[45,3,1,"_CPPv4NK4espp7Tt2110015get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Tt21100::get_touch_point"],[45,4,1,"_CPPv4NK4espp7Tt2110015get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Tt21100::get_touch_point::num_touch_points"],[45,4,1,"_CPPv4NK4espp7Tt2110015get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Tt21100::get_touch_point::x"],[45,4,1,"_CPPv4NK4espp7Tt2110015get_touch_pointEP7uint8_tP8uint16_tP8uint16_t","espp::Tt21100::get_touch_point::y"],[45,8,1,"_CPPv4N4espp7Tt211007read_fnE","espp::Tt21100::read_fn"],[45,3,1,"_CPPv4N4espp7Tt211006updateERNSt10error_codeE","espp::Tt21100::update"],[45,4,1,"_CPPv4N4espp7Tt211006updateERNSt10error_codeE","espp::Tt21100::update::ec"],[63,2,1,"_CPPv4N4espp9UdpSocketE","espp::UdpSocket"],[63,2,1,"_CPPv4N4espp9UdpSocket6ConfigE","espp::UdpSocket::Config"],[63,1,1,"_CPPv4N4espp9UdpSocket6Config9log_levelE","espp::UdpSocket::Config::log_level"],[63,2,1,"_CPPv4N4espp9UdpSocket13ReceiveConfigE","espp::UdpSocket::ReceiveConfig"],[63,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig11buffer_sizeE","espp::UdpSocket::ReceiveConfig::buffer_size"],[63,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig21is_multicast_endpointE","espp::UdpSocket::ReceiveConfig::is_multicast_endpoint"],[63,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig15multicast_groupE","espp::UdpSocket::ReceiveConfig::multicast_group"],[63,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig19on_receive_callbackE","espp::UdpSocket::ReceiveConfig::on_receive_callback"],[63,1,1,"_CPPv4N4espp9UdpSocket13ReceiveConfig4portE","espp::UdpSocket::ReceiveConfig::port"],[63,2,1,"_CPPv4N4espp9UdpSocket10SendConfigE","espp::UdpSocket::SendConfig"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig10ip_addressE","espp::UdpSocket::SendConfig::ip_address"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig21is_multicast_endpointE","espp::UdpSocket::SendConfig::is_multicast_endpoint"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig20on_response_callbackE","espp::UdpSocket::SendConfig::on_response_callback"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig4portE","espp::UdpSocket::SendConfig::port"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig13response_sizeE","espp::UdpSocket::SendConfig::response_size"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig16response_timeoutE","espp::UdpSocket::SendConfig::response_timeout"],[63,1,1,"_CPPv4N4espp9UdpSocket10SendConfig17wait_for_responseE","espp::UdpSocket::SendConfig::wait_for_response"],[63,3,1,"_CPPv4N4espp9UdpSocket9UdpSocketERK6Config","espp::UdpSocket::UdpSocket"],[63,4,1,"_CPPv4N4espp9UdpSocket9UdpSocketERK6Config","espp::UdpSocket::UdpSocket::config"],[63,3,1,"_CPPv4N4espp9UdpSocket19add_multicast_groupERKNSt6stringE","espp::UdpSocket::add_multicast_group"],[63,4,1,"_CPPv4N4espp9UdpSocket19add_multicast_groupERKNSt6stringE","espp::UdpSocket::add_multicast_group::multicast_group"],[63,3,1,"_CPPv4N4espp9UdpSocket12enable_reuseEv","espp::UdpSocket::enable_reuse"],[63,3,1,"_CPPv4N4espp9UdpSocket13get_ipv4_infoEv","espp::UdpSocket::get_ipv4_info"],[63,3,1,"_CPPv4N4espp9UdpSocket8is_validEi","espp::UdpSocket::is_valid"],[63,3,1,"_CPPv4NK4espp9UdpSocket8is_validEv","espp::UdpSocket::is_valid"],[63,4,1,"_CPPv4N4espp9UdpSocket8is_validEi","espp::UdpSocket::is_valid::socket_fd"],[63,3,1,"_CPPv4N4espp9UdpSocket14make_multicastE7uint8_t7uint8_t","espp::UdpSocket::make_multicast"],[63,4,1,"_CPPv4N4espp9UdpSocket14make_multicastE7uint8_t7uint8_t","espp::UdpSocket::make_multicast::loopback_enabled"],[63,4,1,"_CPPv4N4espp9UdpSocket14make_multicastE7uint8_t7uint8_t","espp::UdpSocket::make_multicast::time_to_live"],[63,3,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive"],[63,4,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive::data"],[63,4,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive::max_num_bytes"],[63,4,1,"_CPPv4N4espp9UdpSocket7receiveE6size_tRNSt6vectorI7uint8_tEERN6Socket4InfoE","espp::UdpSocket::receive::remote_info"],[63,8,1,"_CPPv4N4espp9UdpSocket19receive_callback_fnE","espp::UdpSocket::receive_callback_fn"],[63,8,1,"_CPPv4N4espp9UdpSocket20response_callback_fnE","espp::UdpSocket::response_callback_fn"],[63,3,1,"_CPPv4N4espp9UdpSocket4sendENSt11string_viewERK10SendConfig","espp::UdpSocket::send"],[63,3,1,"_CPPv4N4espp9UdpSocket4sendERKNSt6vectorI7uint8_tEERK10SendConfig","espp::UdpSocket::send"],[63,4,1,"_CPPv4N4espp9UdpSocket4sendENSt11string_viewERK10SendConfig","espp::UdpSocket::send::data"],[63,4,1,"_CPPv4N4espp9UdpSocket4sendERKNSt6vectorI7uint8_tEERK10SendConfig","espp::UdpSocket::send::data"],[63,4,1,"_CPPv4N4espp9UdpSocket4sendENSt11string_viewERK10SendConfig","espp::UdpSocket::send::send_config"],[63,4,1,"_CPPv4N4espp9UdpSocket4sendERKNSt6vectorI7uint8_tEERK10SendConfig","espp::UdpSocket::send::send_config"],[63,3,1,"_CPPv4N4espp9UdpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::UdpSocket::set_receive_timeout"],[63,4,1,"_CPPv4N4espp9UdpSocket19set_receive_timeoutERKNSt6chrono8durationIfEE","espp::UdpSocket::set_receive_timeout::timeout"],[63,3,1,"_CPPv4N4espp9UdpSocket15start_receivingERN4Task6ConfigERK13ReceiveConfig","espp::UdpSocket::start_receiving"],[63,4,1,"_CPPv4N4espp9UdpSocket15start_receivingERN4Task6ConfigERK13ReceiveConfig","espp::UdpSocket::start_receiving::receive_config"],[63,4,1,"_CPPv4N4espp9UdpSocket15start_receivingERN4Task6ConfigERK13ReceiveConfig","espp::UdpSocket::start_receiving::task_config"],[63,3,1,"_CPPv4N4espp9UdpSocketD0Ev","espp::UdpSocket::~UdpSocket"],[58,2,1,"_CPPv4I0EN4espp8Vector2dE","espp::Vector2d"],[58,5,1,"_CPPv4I0EN4espp8Vector2dE","espp::Vector2d::T"],[58,3,1,"_CPPv4N4espp8Vector2d8Vector2dE1T1T","espp::Vector2d::Vector2d"],[58,3,1,"_CPPv4N4espp8Vector2d8Vector2dERK8Vector2d","espp::Vector2d::Vector2d"],[58,4,1,"_CPPv4N4espp8Vector2d8Vector2dERK8Vector2d","espp::Vector2d::Vector2d::other"],[58,4,1,"_CPPv4N4espp8Vector2d8Vector2dE1T1T","espp::Vector2d::Vector2d::x"],[58,4,1,"_CPPv4N4espp8Vector2d8Vector2dE1T1T","espp::Vector2d::Vector2d::y"],[58,3,1,"_CPPv4NK4espp8Vector2d3dotERK8Vector2d","espp::Vector2d::dot"],[58,4,1,"_CPPv4NK4espp8Vector2d3dotERK8Vector2d","espp::Vector2d::dot::other"],[58,3,1,"_CPPv4NK4espp8Vector2d9magnitudeEv","espp::Vector2d::magnitude"],[58,3,1,"_CPPv4NK4espp8Vector2d17magnitude_squaredEv","espp::Vector2d::magnitude_squared"],[58,3,1,"_CPPv4NK4espp8Vector2d10normalizedEv","espp::Vector2d::normalized"],[58,3,1,"_CPPv4NK4espp8Vector2dmlERK1T","espp::Vector2d::operator*"],[58,4,1,"_CPPv4NK4espp8Vector2dmlERK1T","espp::Vector2d::operator*::v"],[58,3,1,"_CPPv4N4espp8Vector2dmLERK1T","espp::Vector2d::operator*="],[58,4,1,"_CPPv4N4espp8Vector2dmLERK1T","espp::Vector2d::operator*=::v"],[58,3,1,"_CPPv4NK4espp8Vector2dplERK8Vector2d","espp::Vector2d::operator+"],[58,4,1,"_CPPv4NK4espp8Vector2dplERK8Vector2d","espp::Vector2d::operator+::rhs"],[58,3,1,"_CPPv4N4espp8Vector2dpLERK8Vector2d","espp::Vector2d::operator+="],[58,4,1,"_CPPv4N4espp8Vector2dpLERK8Vector2d","espp::Vector2d::operator+=::rhs"],[58,3,1,"_CPPv4NK4espp8Vector2dmiERK8Vector2d","espp::Vector2d::operator-"],[58,3,1,"_CPPv4NK4espp8Vector2dmiEv","espp::Vector2d::operator-"],[58,4,1,"_CPPv4NK4espp8Vector2dmiERK8Vector2d","espp::Vector2d::operator-::rhs"],[58,3,1,"_CPPv4N4espp8Vector2dmIERK8Vector2d","espp::Vector2d::operator-="],[58,4,1,"_CPPv4N4espp8Vector2dmIERK8Vector2d","espp::Vector2d::operator-=::rhs"],[58,3,1,"_CPPv4NK4espp8Vector2ddvERK1T","espp::Vector2d::operator/"],[58,3,1,"_CPPv4NK4espp8Vector2ddvERK8Vector2d","espp::Vector2d::operator/"],[58,4,1,"_CPPv4NK4espp8Vector2ddvERK1T","espp::Vector2d::operator/::v"],[58,4,1,"_CPPv4NK4espp8Vector2ddvERK8Vector2d","espp::Vector2d::operator/::v"],[58,3,1,"_CPPv4N4espp8Vector2ddVERK1T","espp::Vector2d::operator/="],[58,3,1,"_CPPv4N4espp8Vector2ddVERK8Vector2d","espp::Vector2d::operator/="],[58,4,1,"_CPPv4N4espp8Vector2ddVERK1T","espp::Vector2d::operator/=::v"],[58,4,1,"_CPPv4N4espp8Vector2ddVERK8Vector2d","espp::Vector2d::operator/=::v"],[58,3,1,"_CPPv4N4espp8Vector2daSERK8Vector2d","espp::Vector2d::operator="],[58,4,1,"_CPPv4N4espp8Vector2daSERK8Vector2d","espp::Vector2d::operator=::other"],[58,3,1,"_CPPv4N4espp8Vector2dixEi","espp::Vector2d::operator[]"],[58,4,1,"_CPPv4N4espp8Vector2dixEi","espp::Vector2d::operator[]::index"],[58,3,1,"_CPPv4I0_PNSt9enable_ifINSt17is_floating_pointI1UE5valueEE4typeEENK4espp8Vector2d7rotatedE8Vector2d1T","espp::Vector2d::rotated"],[58,5,1,"_CPPv4I0_PNSt9enable_ifINSt17is_floating_pointI1UE5valueEE4typeEENK4espp8Vector2d7rotatedE8Vector2d1T","espp::Vector2d::rotated::U"],[58,4,1,"_CPPv4I0_PNSt9enable_ifINSt17is_floating_pointI1UE5valueEE4typeEENK4espp8Vector2d7rotatedE8Vector2d1T","espp::Vector2d::rotated::radians"],[58,3,1,"_CPPv4N4espp8Vector2d1xE1T","espp::Vector2d::x"],[58,3,1,"_CPPv4NK4espp8Vector2d1xEv","espp::Vector2d::x"],[58,4,1,"_CPPv4N4espp8Vector2d1xE1T","espp::Vector2d::x::v"],[58,3,1,"_CPPv4N4espp8Vector2d1yE1T","espp::Vector2d::y"],[58,3,1,"_CPPv4NK4espp8Vector2d1yEv","espp::Vector2d::y"],[58,4,1,"_CPPv4N4espp8Vector2d1yE1T","espp::Vector2d::y::v"],[80,2,1,"_CPPv4N4espp6WifiApE","espp::WifiAp"],[80,2,1,"_CPPv4N4espp6WifiAp6ConfigE","espp::WifiAp::Config"],[80,1,1,"_CPPv4N4espp6WifiAp6Config7channelE","espp::WifiAp::Config::channel"],[80,1,1,"_CPPv4N4espp6WifiAp6Config9log_levelE","espp::WifiAp::Config::log_level"],[80,1,1,"_CPPv4N4espp6WifiAp6Config22max_number_of_stationsE","espp::WifiAp::Config::max_number_of_stations"],[80,1,1,"_CPPv4N4espp6WifiAp6Config8passwordE","espp::WifiAp::Config::password"],[80,1,1,"_CPPv4N4espp6WifiAp6Config4ssidE","espp::WifiAp::Config::ssid"],[80,3,1,"_CPPv4N4espp6WifiAp6WifiApERK6Config","espp::WifiAp::WifiAp"],[80,4,1,"_CPPv4N4espp6WifiAp6WifiApERK6Config","espp::WifiAp::WifiAp::config"],[81,2,1,"_CPPv4N4espp7WifiStaE","espp::WifiSta"],[81,2,1,"_CPPv4N4espp7WifiSta6ConfigE","espp::WifiSta::Config"],[81,1,1,"_CPPv4N4espp7WifiSta6Config6ap_macE","espp::WifiSta::Config::ap_mac"],[81,1,1,"_CPPv4N4espp7WifiSta6Config7channelE","espp::WifiSta::Config::channel"],[81,1,1,"_CPPv4N4espp7WifiSta6Config9log_levelE","espp::WifiSta::Config::log_level"],[81,1,1,"_CPPv4N4espp7WifiSta6Config19num_connect_retriesE","espp::WifiSta::Config::num_connect_retries"],[81,1,1,"_CPPv4N4espp7WifiSta6Config12on_connectedE","espp::WifiSta::Config::on_connected"],[81,1,1,"_CPPv4N4espp7WifiSta6Config15on_disconnectedE","espp::WifiSta::Config::on_disconnected"],[81,1,1,"_CPPv4N4espp7WifiSta6Config9on_got_ipE","espp::WifiSta::Config::on_got_ip"],[81,1,1,"_CPPv4N4espp7WifiSta6Config8passwordE","espp::WifiSta::Config::password"],[81,1,1,"_CPPv4N4espp7WifiSta6Config10set_ap_macE","espp::WifiSta::Config::set_ap_mac"],[81,1,1,"_CPPv4N4espp7WifiSta6Config4ssidE","espp::WifiSta::Config::ssid"],[81,3,1,"_CPPv4N4espp7WifiSta7WifiStaERK6Config","espp::WifiSta::WifiSta"],[81,4,1,"_CPPv4N4espp7WifiSta7WifiStaERK6Config","espp::WifiSta::WifiSta::config"],[81,8,1,"_CPPv4N4espp7WifiSta16connect_callbackE","espp::WifiSta::connect_callback"],[81,8,1,"_CPPv4N4espp7WifiSta19disconnect_callbackE","espp::WifiSta::disconnect_callback"],[81,8,1,"_CPPv4N4espp7WifiSta11ip_callbackE","espp::WifiSta::ip_callback"],[81,3,1,"_CPPv4NK4espp7WifiSta12is_connectedEv","espp::WifiSta::is_connected"],[81,3,1,"_CPPv4N4espp7WifiStaD0Ev","espp::WifiSta::~WifiSta"],[14,2,1,"_CPPv4N4espp21__csv_documentation__E","espp::__csv_documentation__"],[73,2,1,"_CPPv4N4espp31__serialization_documentation__E","espp::__serialization_documentation__"],[74,2,1,"_CPPv4N4espp31__state_machine_documentation__E","espp::__state_machine_documentation__"],[75,2,1,"_CPPv4N4espp26__tabulate_documentation__E","espp::__tabulate_documentation__"],[74,2,1,"_CPPv4N4espp13state_machine16DeepHistoryStateE","espp::state_machine::DeepHistoryState"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState5entryEv","espp::state_machine::DeepHistoryState::entry"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState4exitEv","espp::state_machine::DeepHistoryState::exit"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState12exitChildrenEv","espp::state_machine::DeepHistoryState::exitChildren"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14getActiveChildEv","espp::state_machine::DeepHistoryState::getActiveChild"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState13getActiveLeafEv","espp::state_machine::DeepHistoryState::getActiveLeaf"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState10getInitialEv","espp::state_machine::DeepHistoryState::getInitial"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14getParentStateEv","espp::state_machine::DeepHistoryState::getParentState"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState11handleEventEP9EventBase","espp::state_machine::DeepHistoryState::handleEvent"],[74,4,1,"_CPPv4N4espp13state_machine16DeepHistoryState11handleEventEP9EventBase","espp::state_machine::DeepHistoryState::handleEvent::event"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState10initializeEv","espp::state_machine::DeepHistoryState::initialize"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState10makeActiveEv","espp::state_machine::DeepHistoryState::makeActive"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setActiveChildEP9StateBase","espp::state_machine::DeepHistoryState::setActiveChild"],[74,4,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setActiveChildEP9StateBase","espp::state_machine::DeepHistoryState::setActiveChild::childState"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setDeepHistoryEv","espp::state_machine::DeepHistoryState::setDeepHistory"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setParentStateEP9StateBase","espp::state_machine::DeepHistoryState::setParentState"],[74,4,1,"_CPPv4N4espp13state_machine16DeepHistoryState14setParentStateEP9StateBase","espp::state_machine::DeepHistoryState::setParentState::parent"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState17setShallowHistoryEv","espp::state_machine::DeepHistoryState::setShallowHistory"],[74,3,1,"_CPPv4N4espp13state_machine16DeepHistoryState4tickEv","espp::state_machine::DeepHistoryState::tick"],[74,2,1,"_CPPv4N4espp13state_machine9EventBaseE","espp::state_machine::EventBase"],[74,2,1,"_CPPv4N4espp13state_machine19ShallowHistoryStateE","espp::state_machine::ShallowHistoryState"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState5entryEv","espp::state_machine::ShallowHistoryState::entry"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState4exitEv","espp::state_machine::ShallowHistoryState::exit"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState12exitChildrenEv","espp::state_machine::ShallowHistoryState::exitChildren"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14getActiveChildEv","espp::state_machine::ShallowHistoryState::getActiveChild"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState13getActiveLeafEv","espp::state_machine::ShallowHistoryState::getActiveLeaf"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState10getInitialEv","espp::state_machine::ShallowHistoryState::getInitial"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14getParentStateEv","espp::state_machine::ShallowHistoryState::getParentState"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState11handleEventEP9EventBase","espp::state_machine::ShallowHistoryState::handleEvent"],[74,4,1,"_CPPv4N4espp13state_machine19ShallowHistoryState11handleEventEP9EventBase","espp::state_machine::ShallowHistoryState::handleEvent::event"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState10initializeEv","espp::state_machine::ShallowHistoryState::initialize"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState10makeActiveEv","espp::state_machine::ShallowHistoryState::makeActive"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setActiveChildEP9StateBase","espp::state_machine::ShallowHistoryState::setActiveChild"],[74,4,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setActiveChildEP9StateBase","espp::state_machine::ShallowHistoryState::setActiveChild::childState"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setDeepHistoryEv","espp::state_machine::ShallowHistoryState::setDeepHistory"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setParentStateEP9StateBase","espp::state_machine::ShallowHistoryState::setParentState"],[74,4,1,"_CPPv4N4espp13state_machine19ShallowHistoryState14setParentStateEP9StateBase","espp::state_machine::ShallowHistoryState::setParentState::parent"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState17setShallowHistoryEv","espp::state_machine::ShallowHistoryState::setShallowHistory"],[74,3,1,"_CPPv4N4espp13state_machine19ShallowHistoryState4tickEv","espp::state_machine::ShallowHistoryState::tick"],[74,2,1,"_CPPv4N4espp13state_machine9StateBaseE","espp::state_machine::StateBase"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase5entryEv","espp::state_machine::StateBase::entry"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase4exitEv","espp::state_machine::StateBase::exit"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase12exitChildrenEv","espp::state_machine::StateBase::exitChildren"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase14getActiveChildEv","espp::state_machine::StateBase::getActiveChild"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase13getActiveLeafEv","espp::state_machine::StateBase::getActiveLeaf"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase10getInitialEv","espp::state_machine::StateBase::getInitial"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase14getParentStateEv","espp::state_machine::StateBase::getParentState"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase11handleEventEP9EventBase","espp::state_machine::StateBase::handleEvent"],[74,4,1,"_CPPv4N4espp13state_machine9StateBase11handleEventEP9EventBase","espp::state_machine::StateBase::handleEvent::event"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase10initializeEv","espp::state_machine::StateBase::initialize"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase10makeActiveEv","espp::state_machine::StateBase::makeActive"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase14setActiveChildEP9StateBase","espp::state_machine::StateBase::setActiveChild"],[74,4,1,"_CPPv4N4espp13state_machine9StateBase14setActiveChildEP9StateBase","espp::state_machine::StateBase::setActiveChild::childState"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase14setDeepHistoryEv","espp::state_machine::StateBase::setDeepHistory"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase14setParentStateEP9StateBase","espp::state_machine::StateBase::setParentState"],[74,4,1,"_CPPv4N4espp13state_machine9StateBase14setParentStateEP9StateBase","espp::state_machine::StateBase::setParentState::parent"],[74,3,1,"_CPPv4N4espp13state_machine9StateBase17setShallowHistoryEv","espp::state_machine::StateBase::setShallowHistory"],[74,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,8,10,11,12,13,14,15,16,18,19,22,23,24,25,26,28,33,34,36,39,40,43,45,46,48,49,50,51,52,53,55,57,58,59,61,62,63,65,66,67,68,69,72,75,76,77,78,81],"00":19,"000":[75,77],"000f":8,"00b":65,"01":[15,33,66],"010f":8,"01f":[19,22],"02":[7,66],"024v":1,"02x":66,"03":[52,59,66],"04":[33,66],"048v":1,"04x":36,"05":66,"054":75,"05f":51,"06":66,"067488":77,"0693":75,"06f":76,"0755":24,"08":[],"096v":1,"0b":[],"0b00000001":66,"0b00000010":66,"0b00000011":46,"0b00000100":66,"0b00001000":66,"0b0000110":22,"0b00010000":66,"0b00100000":66,"0b00111111":46,"0b0100000":48,"0b01000000":66,"0b0110110":19,"0b10000000":66,"0b11":46,"0b11111":51,"0f":[7,8,13,19,22,23,33,49,50,51,52,53,55,59,67,69],"0m":78,"0s":50,"0x00":[46,48,66],"0x0000":16,"0x000000":[],"0x06":6,"0x060504030201":66,"0x10":[2,6],"0x13":65,"0x14":40,"0x16":6,"0x24":45,"0x38":39,"0x48":1,"0x51":70,"0x54":68,"0x55":43,"0x58":[36,46],"0x5d":40,"0xa6":66,"0xa8":68,"0xae":66,"0xf412fa42fe9":65,"0xff":[51,66],"0xffffffffffff":65,"1":[1,2,3,6,7,8,10,11,12,13,14,15,16,18,19,22,23,24,25,26,34,36,43,46,48,49,50,52,53,55,57,61,62,63,65,66,67,68,72,73,75,76,77,80],"10":[2,8,11,15,18,36,43,45,50,52,59,73,75,76,77],"100":[16,23,48,49,50,67,77],"1000":[3,8,16,18,36,50,67,72,77],"10000":77,"1000000":69,"10000000":69,"100m":[16,50,59,67,74,76,81],"1024":[1,2,3,6,8,10,13,19,22,23,34,46,48,51,59,62,63,66,69,76,77],"10k":77,"10m":[2,6,50,62,66,76,77],"10mhz":69,"11":[70,75],"11k":6,"12":[2,6,65,75],"123":34,"127":[62,63,65],"128":[1,2,6,62,63,65,72],"12800":16,"128x":[2,6],"13":[46,80],"135":16,"14":46,"144v":1,"14763":77,"15":[2,6,46,70,73,75,77],"1500":72,"152":77,"16":[1,2,6,16,46,48,65,66,75],"1600":1,"16384":[16,19,22],"1678892742599":34,"16kb":66,"16x":[2,6],"17":75,"1700":[13,49],"1784807f":[],"18":[65,69,75],"18688":65,"187":75,"192":65,"1b":65,"1f":[18,23,49,50,67],"1s":[10,33,34,51,52,59,62,63,67,70,72,74,76,78],"2":[1,2,3,6,8,10,13,14,15,19,22,23,24,25,26,28,46,49,50,52,55,58,59,62,63,65,66,67,69,72,75,78],"20":[3,8,16,24,75,77],"200":[33,72,75],"200m":[1,76],"2013":75,"20143":19,"2016":75,"2019":75,"2023":70,"2046":65,"20df":19,"20m":13,"21":[8,13,75],"224":[61,62,63],"23":[70,75],"23017":48,"239":[61,62,63],"23s17":48,"240":16,"2400":1,"2435":72,"2494":77,"24b":[],"25":[23,46,75,77],"250":1,"250136576":65,"250m":[18,43],"255":[12,46,51,61,62,63,65,66,69],"256":[3,65,69,72],"2566":75,"256v":1,"25c":77,"264":72,"265":72,"2657":77,"273":77,"298":77,"299":75,"2f":[13,23,77],"2pi":[19,22],"2s":78,"2x":[2,6],"3":[1,2,6,7,8,13,14,15,29,33,46,48,50,62,63,65,69,73,75,77,78],"30":[70,75,77],"300f":8,"300m":52,"31":[13,51,77],"313":75,"32":[1,2,6,13,65],"320":[8,16],"32x":[2,6],"33":13,"3300":[1,49,77],"3380":77,"34":[2,6,8],"3422":77,"3435":77,"3453":77,"3484":69,"3484_datasheet":69,"35981":77,"36":[8,13],"360":[12,19,22,51,69],"36005":19,"37":13,"370":75,"376":75,"37ma":46,"38":13,"39":13,"3914752":[],"3940":77,"3950":77,"3986":65,"3f":[1,2,6,10,18,19,22,34,46,48,52,66,67,77,78],"3s":3,"4":[1,2,6,8,10,13,14,19,22,34,51,53,62,63,65,66,69,70,75,76,80],"40":[16,75,77],"400":36,"400000":[],"4096":[18,78],"42":[13,65,73],"43173a3eb323":19,"458":75,"461":75,"475":1,"48":[23,65,66],"4886":46,"48b":66,"490":1,"4\u03c0":75,"4b":65,"4kb":66,"4x":[2,6],"5":[1,2,3,6,8,13,14,19,22,23,26,28,33,34,39,46,48,51,55,59,62,63,65,66,69,73,75,77],"50":[16,46,50,66,69,75,77],"5000":[50,62,63,72],"5001":72,"500m":[3,5,13,23,36,39,40,49,52,59,76,78],"50c":77,"50m":[19,22,45,46,48,51,68,69],"50u":69,"512v":1,"53":16,"53229":77,"55":75,"571":75,"5f":[19,22,50,51,55,63,69],"5m":67,"5s":23,"6":[1,2,6,7,12,13,14,34,62,63,65,66,69,75,81],"60":[16,19,22,75],"61067330":24,"614":75,"61622309":66,"626":75,"64":[1,2,6,69],"649ee61c":19,"64kb":66,"64x":[2,6],"6742":75,"68":75,"7":[2,6,8,34,48,65,68,73,75,77],"70":75,"720":[19,22],"72593":34,"730":75,"75":[46,77],"792":75,"8":[1,2,6,12,15,23,34,46,48,59,65,66,70,75],"80":77,"80552":77,"817":75,"8192":18,"85":77,"8502":77,"854":75,"8554":72,"860":1,"8f9a":19,"8x":[2,6],"9":[18,46,69,75],"90":75,"920":1,"93hart_equ":77,"9692":11,"9781449324094":65,"9907":77,"999":11,"9e":65,"9e10":19,"9th":[2,6],"\u00b2":75,"\u00b3\u2074":75,"\u00b9":75,"\u00b9\u00b2f":75,"\u00b9\u00b9m\u00b3":75,"\u03ba":77,"\u03c9":[75,77],"\u16a0":75,"\u16a1":75,"\u16a2":75,"\u16a3":75,"\u16a4":75,"\u16a5":75,"\u16a6":75,"\u16a7":75,"\u16a8":75,"\u16a9":75,"\u16aa":75,"\u16ab":75,"\u16ac":75,"\u16ad":75,"\u16ae":75,"\u16af":75,"\u16b0":75,"\u16b1":75,"\u16b2":75,"\u16b3":75,"\u16b4":75,"\u16b5":75,"\u16b6":75,"\u16b7":75,"\u16b8":75,"\u16b9":75,"\u16ba":75,"\u16bb":75,"\u16bc":75,"\u16bd":75,"\u16be":75,"\u16bf":75,"\u16c0":75,"\u16c1":75,"\u16c2":75,"\u16c3":75,"\u16c4":75,"\u16c5":75,"\u16c6":75,"\u16c7":75,"\u16c8":75,"\u16c9":75,"\u16ca":75,"\u16cb":75,"\u16cc":75,"\u16cd":75,"\u16ce":75,"\u16cf":75,"\u16d0":75,"\u16d1":75,"\u16d2":75,"\u16d3":75,"\u2076":75,"\u2077":75,"abstract":[37,60,61,76],"boolean":24,"break":74,"byte":[1,2,3,6,15,16,19,22,23,24,34,46,48,51,59,61,62,63,65,66,68,69,70,72],"case":[19,22,63,69],"char":[24,43,62,72,76],"class":27,"const":[1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,22,23,24,25,26,28,29,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,61,62,63,65,66,67,68,69,70,72,74,76,77,78,80,81],"default":[1,2,6,11,13,15,16,33,34,39,40,43,45,46,48,51,53,55,57,58,59,68,69,70,72,73,80,81],"do":[2,5,10,13,14,23,34,43,59,72,73,74,75,76],"enum":[1,2,6,10,13,15,34,39,46,48,49,51,52,65,68,77],"export":75,"final":[13,19,22,36,39,40,45,46,48,59,65,66,68,70,72,74],"float":[1,2,3,5,6,7,8,10,12,13,15,18,19,22,23,25,26,28,29,33,34,46,48,49,50,51,52,53,54,55,58,59,61,62,63,67,69,74,76,77,78],"function":[1,2,3,5,6,7,8,10,11,12,13,15,16,18,19,22,23,24,25,26,27,28,29,33,34,35,36,37,38,39,40,42,43,44,45,46,48,49,50,51,52,53,54,55,57,58,59,60,61,62,63,65,66,67,69,72,74,76,77,78,80,81],"goto":69,"int":[1,2,5,7,10,11,13,16,18,19,22,23,24,31,46,50,51,58,59,61,62,63,65,66,67,68,69,72,73,74,75,76,77,78],"long":[11,72,75,78],"new":[5,7,8,10,11,16,23,25,26,28,29,31,39,40,45,46,49,50,51,52,55,57,58,65,66,67,68,72,76,78],"null":43,"public":[1,2,3,5,6,7,8,10,11,12,13,15,16,18,19,22,23,24,25,26,28,29,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,59,61,62,63,65,66,67,68,69,70,72,74,76,77,78,80,81],"return":[1,2,3,5,6,7,8,10,11,12,13,15,16,18,19,22,23,24,25,26,28,29,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,59,61,62,63,65,66,67,68,69,70,72,74,76,77,78,81],"short":[13,65],"static":[1,2,6,8,10,11,16,19,22,23,24,33,34,36,39,40,43,45,46,48,50,51,54,59,61,62,63,65,66,68,69,70,74,76,77,78],"super":14,"switch":[2,6,15,69],"throw":[11,24],"true":[1,2,6,7,8,10,11,13,14,15,16,18,19,22,23,24,31,33,34,36,39,40,43,44,45,46,48,49,50,51,52,57,61,62,63,65,66,67,68,69,70,72,74,75,76,78,81],"void":[2,3,6,7,8,10,11,13,15,16,19,22,23,25,28,31,33,34,36,39,40,43,44,45,46,48,49,50,51,52,55,57,58,61,62,63,65,66,67,68,69,70,72,74,77,78,81],"while":[10,11,16,23,43,50,52,59,72,74,76,81],A:[2,6,7,10,13,23,30,31,48,51,62,65,68,72,75,78],And:51,As:23,By:11,For:[11,15,29,34,68,72,75,76],IN:34,IT:[24,66],If:[2,5,6,7,11,12,23,33,34,36,44,50,57,61,62,63,65,72,74,76,78,80,81],In:[13,23,46],Is:[61,62,63,76],It:[2,3,5,6,8,10,11,13,14,19,22,23,24,31,33,34,36,43,45,46,50,51,67,69,72,74,75,76,77],NOT:[2,13],No:[2,6,33,52,65],Not:24,ON:11,ONE:1,On:[2,33,43],The:[1,2,3,5,6,7,8,9,10,11,12,13,14,15,18,19,22,23,24,25,26,28,29,30,31,32,33,34,36,38,39,40,42,43,45,46,48,49,50,51,52,53,54,55,57,58,59,60,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],There:[19,21,22,27,35,47,59,74],These:[2,6,9,69,72],To:[23,68,72],Will:[7,19,22,46,57,59,61,66,72,74],With:49,_1:[39,40,43,45,59,68,70],_2:[39,40,43,45,59,68,70],_3:[39,40,43,45,68,70],_4:[39,40,68,70],_5:40,_:14,__csv_documentation__:14,__gnu_linux__:[14,73],__linux__:11,__serialization_documentation__:73,__state_machine_documentation__:74,__tabulate_documentation__:75,__unix__:75,__unnamed11__:68,__unnamed13__:68,__unnamed7__:65,__unnamed9__:65,_activest:74,_build:[31,68,70],_cli:11,_event_data:74,_in:11,_out:11,_parentst:74,_rate_limit:52,_really_:51,a0:[48,49],a1:49,a2:48,a_0:25,a_1:25,a_2:25,a_gpio:18,a_pin:48,ab:[57,77],abi:[21,37],abi_encod:18,abiencod:[],abil:[52,59],abl:[31,49,62,74,78],about:[11,14,59,63,65,66,69,74,75,77],abov:[2,6,11,19,22,23,46,51,69,74],absolut:[19,22,24,65],absolute_uri:65,abxi:13,ac:65,acceler:28,accept:[31,62,72],access:[18,24,37,61,66,74,79,81],accord:[24,46,48,49,50,52,72],accordingli:[10,13],accumul:[18,19,22,68],accur:67,ack:[2,6],acknowledg:[36,62],across:[3,33],act:65,action:[74,76],activ:[2,6,7,10,13,48,65,66,72,74],active_high:[2,6,48],active_level:10,active_low:[2,6,13],activeleaf:74,activelevel:10,actual:[1,2,6,13,16,23,33,34,65,72,74,77],actual_celsiu:77,actual_kelvin:77,actuat:[34,35],ad0:46,ad1:46,ad:[1,2,8,13,23,58,65,72],adafruit:[13,34,46,65,69],adc1:77,adc:[13,18,34,37,67],adc_atten_db_11:[3,5,13,49,77],adc_channel_1:13,adc_channel_2:13,adc_channel_6:[3,5],adc_channel_7:[3,5,77],adc_channel_8:49,adc_channel_9:49,adc_channel_t:[3,5],adc_conv_single_unit_1:[3,77],adc_conv_single_unit_2:[],adc_decap:6,adc_digi_convert_mode_t:3,adc_typ:0,adc_unit_1:[3,5,77],adc_unit_2:[13,49],adc_unit_t:5,adcconfig:[3,5,13,49,68,70,77],add:[7,12,16,58,61,62,63,72],add_multicast_group:[61,62,63],add_publish:23,add_row:75,add_scan:72,add_subscrib:[10,23],addit:[3,12,15,37,49,58,76],addition:[2,6,10,11,72],addr:[34,61,66],address:[1,2,6,16,19,22,31,34,36,39,40,43,45,46,48,61,62,63,65,66,68,70,72,81],adjust:[33,62],ads1015:1,ads1015config:[1,13],ads1015rat:1,ads1115:1,ads1115config:1,ads1115rat:1,ads1x15:[4,13,37],ads7128:[2,6],ads7138:[4,37],ads_read:[1,2,13],ads_read_task_fn:[1,2,13],ads_task:[1,2,13],ads_writ:[1,2,13],adventur:14,advis:57,ae:65,affect:[19,22,72],affin:76,after:[2,6,15,43,49,51,57,61,62,63,66,69,72,78,81],again:[23,66,74],against:[],agent:72,alert:[2,6],alert_1000m:34,alert_750m:34,alert_log:2,alert_pin:2,alert_task:2,alertlog:[2,6],algorithm:[7,8,9,12,75],alias:[19,22],align:[51,75],aliv:31,all:[2,5,6,7,11,23,24,34,46,51,52,57,59,63,68,69,72,74],all_mv:[2,6],all_mv_map:6,alloc:[3,15,59,76],allocatingconfig:[15,16],allocation_flag:15,allow:[1,2,3,5,6,7,8,11,13,15,18,19,22,33,34,36,39,40,43,45,46,48,49,50,51,55,57,60,61,62,63,67,68,69,70,72,74,76,77],along:[54,66],alow:55,alpaca:[23,37],alpha:[50,55],alreadi:[23,24,25,62,63,72,76,78],also:[2,6,11,13,14,15,16,19,22,23,24,33,34,46,59,69,72,74,75,76],alt:43,alter_unit:[3,77],altern:[2,3,24,40,65],alwai:[3,5,7,8,19,22,24,34,57,59,72,74],am:19,amount:[3,24,57,58],amp:8,amplitud:55,an:[0,1,2,5,6,7,10,11,12,13,18,19,22,23,24,25,26,28,29,30,32,33,34,40,43,44,45,46,48,49,51,53,55,57,59,61,62,63,65,68,69,72,74,75,76,78,81],analog:[2,3,5,6,34,49],analog_input:[2,6],analogev:2,analogjoystickconfig:13,analyz:59,anaolg:13,android:[65,66],angl:[8,19,22],angle_filt:8,angle_openloop:8,angle_pid_config:8,ani:[2,5,6,7,8,10,11,14,19,22,31,46,51,61,62,63,66,69,72,74,75,76,78],anonym:[23,65],anoth:[10,11,23,24,58],answer:11,any_edg:10,anyth:[14,52,59,73,74,75],anywher:11,ap:[37,79,81],ap_mac:81,apa102_start_fram:51,apa102_writ:[],apa:65,api:37,app:[65,66],app_main:59,appear:65,append:[2,6,72],appli:[3,46,49],applic:[37,72,75],appropri:[7,62,63],approxim:[2,6,49,54],ar:[2,4,6,7,8,9,11,13,16,17,18,21,23,24,27,33,34,35,46,47,48,49,51,52,57,59,60,62,65,66,67,68,69,72,73,74,76,78,79],arari:73,arbitrari:11,area:[15,16],arg:52,argument:[31,52,68,70],arithmet:25,around:[3,5,7,10,11,14,15,24,36,38,42,44,49,50,52,53,55,57,61,69,73,74,75,76],arrai:[1,2,6,16,19,22,25,28,29,34,46,48,53,61,62,63,66,73],arrow:11,articl:77,artifact:69,as5600:[21,37],as5600_ds000365_5:19,as5600_read:19,as5600_writ:19,asid:50,ask:76,aspect:11,asset:34,assign:58,associ:[0,3,5,10,13,15,16,18,23,38,42,44,46,48,49,50,53,58,59,61,62,63,76],associt:[61,62,63],assum:[11,51,62,63,77],assumpt:[19,22],asymmetr:67,ate:24,atom:[8,13],attach:[16,46],attenu:[0,3,5,13,49,77],attribut:[1,2,6,19,22,39,40,43,45,46,48,51,65,66,68,69,70],audio:34,audiovib:34,authent:[31,65],auto:[1,2,3,5,6,8,10,11,13,14,16,18,19,22,23,24,33,34,36,39,40,43,45,46,48,49,50,51,52,59,62,63,66,67,68,69,70,73,74,75,76,77,78],auto_init:[2,6,19,22,34,36,46,48,66],auto_seq:[2,6],auto_start:[43,78],autoc:34,automat:[2,6,11,12,19,22,36,43,46,66,72,75,76,78],autonom:[2,6],autostop:76,avail:[3,18,23,58,66],avdd:[2,6],avdd_volt:[2,6],averag:[2,6,12],aw9523:[37,47],aw9523_read:46,aw9523_writ:46,aw9523b:46,awaken:14,ax:[13,49],axi:[2,8,13,49],b0:65,b1:65,b25:77,b2:65,b3:65,b4:65,b7:48,b:[7,11,12,13,14,18,30,43,46,48,51,55,59,65,66,68,69,73,76,77],b_0:25,b_1:25,b_2:25,b_bright:46,b_down:46,b_gpio:18,b_led:46,b_pin:48,b_up:46,back:[11,15,24,62,63,66,69],background:[33,78],background_color:75,backlight:[15,16,43],backlight_on_valu:[15,16],backlight_pin:[15,16],backspac:11,bad:[12,77],band:65,bandwidth:62,base:[8,12,19,22,25,26,27,28,29,33,50,51,59,61,66,67,69,72,74,75,77],base_encod:69,basi:[2,6],basic:11,batch:75,batteri:23,batteryst:23,bcd2byte:70,bcd:70,becaus:[8,19,22,24,69,75,78],becom:6,been:[2,6,11,25,34,43,51,62,63,66,68,69,72,76,78],befor:[2,6,18,24,33,51,62,66,72,74,76,78,81],beg:24,begin:[11,23,24,62,63,65,76],behavior:[33,67],being:[1,2,3,5,6,8,11,13,18,19,22,23,34,36,39,40,45,46,48,49,51,67,68,69,70,74,76,77],belong:63,below:[2,6,8,74,75],beta:[50,55,77],better:[28,67],between:[12,15,23,32,53,57,66],beyond:[11,14,69,75],bezier:[37,56],bezierinfo:53,bgr:51,bi:66,bia:33,biequad:25,binari:24,bind:[31,39,40,43,45,52,59,62,63,68,70,72],biquad:[26,27,29,37],biquad_filt:25,biquadfilt:25,biquadfilterdf1:25,biquadfilterdf2:[19,22,25,26,29],biquadrat:25,bit0:69,bit1:69,bit:[2,6,11,13,16,46,48,50,65,66,68],bitfield:[2,6],bitmask:2,bldc:[35,37],bldc_driver:7,bldc_haptic:33,bldc_motor:[8,9],bldc_type:8,bldcdriver:[7,8],bldchaptic:33,bldcmotor:[8,19,22,33],ble:[65,66],ble_appear:66,ble_oob_record:[],ble_radio_nam:66,ble_rol:66,blend:12,blerol:[65,66],blob:[11,16],block:[2,3,5,6,11,33,50,51,62,63,69,72,76,78],block_siz:69,blue:[12,14,51,69,75],bluetooth:65,bm8563:[37,68,71],board:[16,68],bob:[8,31,68,70],bodmer:16,bold:75,bool:[1,2,6,7,8,10,11,13,15,16,18,19,22,23,24,31,33,34,36,39,40,43,44,45,46,48,49,50,51,57,61,62,63,65,66,67,68,69,70,72,74,76,78,81],boot:43,border_bottom:75,border_color:75,border_left:75,border_right:75,border_top:75,both:[2,3,6,13,14,25,33,45,46,48,49,50,57,65,69,75],both_unit:[3,77],bother:45,bottom:11,bound:[33,62,69],bounded_no_det:33,box:[13,45,66],boxart:14,bp:2,br:65,breakout:68,breathing_period:50,breathing_start:50,bredr:65,bright:[15,46,51],bro:14,broadcast:[63,65],broken:72,brushless:[7,8,9],bs:23,bsp:16,bt:65,bt_device_class:[],bt_oob_record:[],bt_radio_nam:[],btappear:[65,66],bteir:65,btgoep:65,btl2cap:65,btspp:65,btssp_1_1:65,bttype:65,bu:[2,6,16,36,39,68],budget:75,bufer:76,buffer:[2,3,6,10,15,23,62,69,72,73,76],buffer_s:63,build:[27,37,72],built:[14,62,73,74,75],bundl:13,buscfg:16,busi:63,butterworth:[27,37],butterworth_filt:26,butterworthfilt:[19,22,26,29],button:[2,13,37,38,40,42,44,45,46,68],button_2:10,button_component_nam:10,button_st:[45,68],button_top:10,buttonst:[68,70],buzz1:34,buzz2:34,buzz3:34,buzz4:34,buzz5:34,buzz:[],byte2bcd:70,byte_ord:51,byteord:51,bytes_encod:69,bytes_encoder_config:69,bytes_written:[10,73],c:[7,11,14,16,23,24,37,65,69,73,75,77],c_str:24,cach:[40,72],calcul:[2,6,8,33,77],calibr:[5,8,34,49],call:[2,3,5,6,10,11,12,13,15,18,19,22,23,33,34,40,43,45,46,49,51,52,59,61,62,63,66,67,68,69,72,74,76,78,80,81],call_onc:23,callback:[1,2,3,5,6,8,10,13,15,18,19,22,23,34,36,39,40,43,45,46,48,49,50,51,59,60,61,62,63,66,67,68,69,70,72,74,76,77,78],callback_fn:[76,78],camera:72,can:[2,6,7,8,9,10,11,12,13,15,16,18,19,22,24,31,32,33,34,43,45,49,50,51,52,53,57,59,62,63,65,66,67,69,72,73,74,75,76,77,78,80],can_chang:50,cannot:[24,62,66,72,73],capabl:[46,65,66],capacit:[39,45],captain:75,captur:[2,6,48],carrier:65,carrier_data_ref:65,carrierpowerst:65,catalog:77,caus:[72,74],caution:11,cb:[16,23,72],cc:66,cdn:[46,69],cell:[14,75],celsiu:77,center:[13,33,49,57,75],central:65,central_onli:65,central_peripher:65,certain:[33,74],cf:65,ch04:65,ch0:[2,6],ch1:[2,6],ch2:[2,6],ch3:[2,6],ch4:[2,6],ch5:[2,6],ch6:[2,6],ch7:[2,6],chang:[8,10,12,33,46,48,50,52,55,67,72,74],change_gain:67,channel:[0,1,2,3,5,6,7,12,13,18,49,50,69,72,77,80,81],channel_id:[2,6],channel_sel:[2,6],channelconfig:50,charact:11,characterist:75,chararact:[],chart:[59,75],chdir:24,check:[2,7,8,10,24,31,33,50,61,62,68,72,78,81],child:74,childstat:74,chip:[1,2,3,6,18,21,40,46,47,48,51,66,70,77],choos:7,chose:77,chrono:[1,2,6,8,10,15,19,22,34,43,46,48,50,51,52,59,61,62,63,67,69,74,76,77,78],chrono_liter:[1,2,6,13,34],chunk:65,cin:[11,74],circl:49,circuit:77,circular:49,clamp:[7,12,67,69],clang:77,class_of_devic:65,classic:65,clean:[24,62,76],cleanup:[24,61],clear:[2,11,16,18,46,66,67,72],clear_event_high_flag:2,clear_event_low_flag:2,clear_lin:11,clear_pin:46,clear_screen:11,clear_to_end_of_lin:11,clear_to_start_of_lin:11,cli:[37,74],click:[],client:[31,32,37,60,61],client_socket:[62,63],client_task:[62,63],client_task_fn:[62,63],clifilesesson:11,clint:75,clisess:11,clk_speed:[1,2,6,13,19,22,34,36,46,48,66],clock:[2,6,36,51,65,69],clock_spe:16,clock_speed_hz:16,clock_src:69,clockwis:[],close:[8,9,19,22,24,33,62,72],clutter:74,co:[51,69],coars:33,coarse_values_strong_det:33,code:[1,2,4,6,8,9,11,16,17,18,19,22,23,24,34,39,40,43,45,46,48,49,52,59,60,65,66,67,68,69,72,73,74,75,76,78,79],coeffici:[25,28,30,55,77],collect:[2,72],color:[11,15,16,37,51,69,75],color_data:15,color_map:16,column:[75,77],column_separ:75,column_width:[],com:[2,6,7,8,11,14,16,19,24,25,29,33,34,46,52,63,65,66,69,72,74,75,77,80,81],combin:[61,62,63],combo:61,come:63,comma:14,command:[8,16,31,37],common:[13,16,34,65],common_compon:11,commun:[1,2,6,13,19,22,34,39,40,43,45,46,48,62,63,66,68,70],compat:72,complet:[2,6,11,14,34,50,65,72,75,76],complex:76,complex_root:74,compon:[0,1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,18,19,20,21,22,23,24,25,26,28,29,30,31,33,34,35,36,37,38,39,40,42,43,44,45,46,47,48,49,50,51,52,53,54,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],component_nam:[],compos:65,comput:[12,19,22,32,57,65,67,77],compute_voltag:77,condit:[18,36,50,76],condition_vari:[1,2,3,5,6,8,13,18,19,22,34,36,39,40,45,46,48,49,51,66,67,68,69,70,74,76,77],conf:[3,5],config:[1,2,3,5,6,7,8,10,13,15,18,19,22,24,26,28,29,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,59,61,62,63,65,66,67,68,69,70,72,76,77,78,80,81],config_bt_ble_en:66,config_esp32_wifi_nvs_en:[80,81],config_esp_maximum_retri:81,config_esp_wifi_password:[66,80,81],config_esp_wifi_ssid:[66,80,81],config_freertos_generate_run_time_stat:59,config_freertos_use_trace_facil:59,config_hardware_box:[],config_hardware_ttgo:[],config_hardware_wrover_kit:[],config_rtsp_server_port:72,configur:[0,1,2,3,5,6,7,8,10,11,13,15,16,18,19,22,24,26,28,29,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,59,61,62,63,65,66,67,68,69,70,72,73,74,76,77,78,81],configure_alert:2,configure_global_control:46,configure_l:46,configure_pow:7,configure_stdin_stdout:[11,74],confirm:65,confirm_valu:65,connect:[6,8,10,13,31,34,48,50,62,65,72,80,81],connect_callback:81,connect_config:62,connectconfig:62,consecut:2,consol:75,constant:[67,75],constexpr:[1,2,6,16,19,22,33,36,39,40,43,45,46,48,65,66,68,69,70,73],construct:[1,2,6,10,11,12,19,20,22,26,29,34,36,39,46,48,52,53,55,59,61,66,68,72,76,78],constructor:[2,6,11,12,23,33,40,43,45,46,51,52,58,61,69,70,72,77],consum:74,contain:[0,10,11,12,13,15,16,18,23,24,30,33,38,42,44,53,58,59,63,65,66,67,68,72,73,74,81],content:[24,75],context:[23,74,78],continu:[2,4,6,11,24,34,37,63,76,77],continuous_adc:3,continuousadc:[3,77],control:[2,6,7,8,9,16,19,22,23,31,33,34,37,41,43,46,48,50,51,53,65,67,68,72],control_point:53,control_socket:72,controller_driv:16,conveni:[11,13,14,19,22,50,61,73,74,75],convers:[1,2,3,6,12,19,22,49,61],convert:[2,5,6,7,8,12,13,19,22,23,24,49,57,61,66,70,72,77],convert_mod:[3,77],convieni:[53,55],cool:52,coolei:75,coordin:[16,39,40,44],copi:[11,12,24,58,69,74,76],copy_encod:69,core:[10,65,76,78],core_id:[8,10,76,78],core_update_period:8,corner:[16,75],correct:[8,74],correspond:[2,6,16,34,46,68,77],could:[2,6,12,14,19,24,39,40,67,73,74,75],couldn:[23,24],count:[1,2,6,8,10,18,19,22,34,46,48,50,51,52,59,67,69,76,77],counter:[18,19,22],counter_clockwis:[],counts_per_revolut:[18,19,22],counts_per_revolution_f:[19,22],counts_to_degre:[19,22],counts_to_radian:[19,22],coupl:[23,49],cout:[11,75],cplusplu:11,cpp:[24,31,37,52,66,68,70,72],cpprefer:[24,52],cpu:59,cr:72,crd:18,creat:[2,8,10,11,12,13,14,16,18,19,22,24,31,33,49,51,52,57,59,62,63,65,66,67,69,72,74,75,76,77,80,81],create_directori:24,creation:[19,22],credenti:65,cross:[2,52,76,78],cs:8,cseq:72,csv2:14,csv:[2,6,24,37],csv_data:14,ctrl:11,cubic:53,curent:[61,74],current:[7,8,10,11,13,16,18,19,22,23,31,32,33,43,44,46,50,52,55,58,59,60,67,68,69,72,77,81],current_directori:31,current_duti:50,current_hfsm_period:74,current_limit:8,current_pid_config:8,current_sens:8,currentlyact:74,currentsensor:8,currentsensorconcept:8,cursor:[11,16],curv:53,custom:[15,23,24,34,69,73],cutoff:[8,26,28],cv:[1,2,3,5,6,8,13,18,19,22,23,34,36,39,40,45,46,48,49,50,51,62,66,67,68,69,70,74,76,77],cv_retval:76,cv_statu:76,cyan:75,cycl:[7,34,50,69],d2:13,d3:13,d4:13,d5:13,d6:13,d:[8,13,23,52,61,62,63,70],d_current_filt:8,dai:70,dam:77,daniele77:11,data:[0,1,2,3,5,6,8,10,12,13,14,15,16,19,22,23,24,25,26,28,29,31,34,36,39,40,43,44,45,46,48,49,51,59,61,62,63,65,66,68,70,72,73,74,77,81],data_address:66,data_command_pin:16,data_len:[1,2,6,13,19,22,34,36,39,45,46,48,68],data_s:69,data_sheet:77,data_str:23,dataformat:[2,6],datasheet:[19,34,46,66,69,77],datasheet_info:77,date:[3,24,68,70,75],date_tim:[24,70],datetim:[68,70],dav:65,db:77,dbm:65,dc:[7,8,9,16],dc_current:[],dc_level_bit:16,dc_pin:16,dc_pin_num:16,de:23,dead_zon:7,deadband:[13,49,57],deadzon:49,deadzone_radiu:49,deal:65,debug:[8,52,66,74,76,78],debug_rate_limit:52,deck:43,decod:[8,19,22,39,40,43,66,68,72],dedic:13,deep:74,deep_history_st:74,deephistoryst:74,default_address:[1,2,6,19,22,34,39,43,45,46,48,68,70],default_address_1:40,default_address_2:40,defautl:55,defin:[23,51,57,69,72,73,74],definit:[20,23],deftail:68,degre:[18,19,22],deinit:[3,36,81],deiniti:36,del:69,delai:[8,25],delet:[5,11,13,18,24,69],delete_fn:69,delimit:14,demo:[11,16],depend:[3,33,57,69,74],depth:69,dequ:11,deriv:[67,74],describ:[15,16,57,62,65,72],descriptor:[61,62,63],deseri:[10,23,65,73],design:[13,19,22,33,35,38,42,43,44,51,72,74,77],desir:[0,7,33],destin:24,destroi:[1,2,3,5,6,7,8,10,13,18,19,22,31,34,36,39,40,45,46,48,49,51,67,68,69,70,72,74,76,77,78],destruct:76,destructor:[11,23,33,69,72,76],detail:[8,33,62,65],detect:[10,11,39],detent:33,detent_config:33,detentconfig:[33,68,70],determin:[19,22],determinist:3,dev:16,dev_addr:[1,2,6,13,19,22,34,36,45,46,48],dev_kit:16,devcfg:16,develop:[8,16,65,74],devic:[1,2,6,16,19,22,33,34,36,38,39,42,44,45,46,48,65,66,68,80],device_address:[1,2,6,19,22,34,36,46,48],device_class:65,devkit:16,diagno:34,diagnost:34,did_pub:23,did_sub:[10,23],differ:[2,6,16,19,20,21,22,23,25,27,34,47,50,51,52,66,67,69,74],digial:28,digit:[2,6,25,26,29],digital_biquad_filt:[25,29],digital_input:[2,6],digital_output:[2,6],digital_output_mod:[2,6],digital_output_valu:[2,6],digitalconfig:13,digitalev:2,dim:46,dimension:58,dir_entri:24,dirac:75,direct:[5,13,25,46,48,66],directli:[2,6,7,9,21,34,35,51,53],director:75,directori:[24,31,68,70],directory_iter:24,directory_list:24,disabl:[2,6,7,8,11,18,19,46,66,69],disconnect:[72,81],disconnect_callback:81,discontinu:57,discover:65,discuss:[11,66],displai:[14,37,65,72],display_driv:[16,17],display_event_menu:74,displaydriv:16,distinguish:73,distribut:[23,57],divid:[12,25,58,67,69,77],divider_config:77,divis:77,dma:[3,69,77],dma_en:69,dnp:[2,6],doc:[7,11,15,31,68,69,70,77,80,81],document:[11,14,19,69,73,74,75],doe:[3,5,7,11,14,18,19,22,24,31,33,46,48,51,61,68,72,73,74,75,78],doesn:[2,6,24],don:[1,2,3,5,6,8,13,18,19,22,23,34,36,39,40,45,46,48,49,51,59,62,63,66,67,68,69,70,74,76,77,78],done:[23,50,61,62,63],dot:58,doubl:[11,15],double_buff:15,double_click:34,down:[11,13,42,51,61,62,63,67,68,74,76],download:65,doxygen:[31,68,70],doxygenclass:[],doxygenfunct:[31,68,70],dq:[],drain:[2,6],draw:[15,16],drive:[2,8,23,34,35,46,69],driven:[33,35],driver:[1,2,6,8,9,11,13,15,17,19,22,35,36,37,38,40,42,44,45,46,48,51,66,68,70,72],driverconcept:8,drv2605:[35,37],drv:16,ds:[2,6,34],dsiplai:15,dsp:[25,28],dsprelat:[25,29],dt:70,dual:[13,65],dualconfig:13,dummycurrentsens:8,dump:75,durat:[1,2,6,8,10,15,19,22,33,34,46,48,50,51,52,59,61,62,63,67,69,74,76,77,78],duration0:69,duration1:69,dure:[66,67,74],duti:[7,50],duty_a:7,duty_b:7,duty_c:7,duty_perc:50,duty_resolut:50,dx:14,dynam:[8,33,55,66,67],dynamictask:76,e2:77,e:[11,24,34,51,55,65,69,74,77],each:[2,3,5,6,7,12,13,23,24,29,31,33,46,49,52,59,68,72,73],earli:[1,2,3,5,6,8,13,18,19,22,34,36,39,40,45,46,48,49,51,67,68,69,70,74,76,77],easier:[],easili:[2,6,19,60,75,76],eastwood:75,ec:[1,2,6,10,13,19,22,23,24,34,36,39,40,43,45,46,48,66,68,70,72,73],eccentr:[34,35],ecm:34,ed:18,edg:[2,6,10,19,22,33,34,69],edit:11,edr:65,eeprom:66,effici:[6,14],eh_ctrl:66,eight:1,eir:65,either:[13,18,59,77],el_angl:8,elaps:[1,2,6,10,34,50,52,66,67,76,77,78],electr:[8,75],element:[5,58],els:[2,3,5,8,10,24,36,45,46,48,66,70,73,74,75,77],em:[10,23],emb:75,embed:75,embedded_t:75,emplace_back:66,empti:[34,51,65,72,80,81],empty_row:75,en:[7,11,24,25,26,29,31,52,61,62,63,65,66,68,69,70,77,80,81],enabl:[2,3,5,6,7,8,10,11,13,15,23,33,43,46,59,60,62,66,75,76,80,81],enable_if:[18,58],enable_reus:[61,62,63],encapsul:66,encod:[33,37,41,72],encode_fn:69,encoded_symbol:69,encoder_input:38,encoder_typ:20,encoder_update_period:[19,22],encoderinput:38,encodertyp:18,encrypt:65,end:[2,6,11,16,23,24,33,34,51,62,63,65,66,74,76],end_fram:51,endev:74,endif:[66,75],endl:[11,75],endpoint:[61,62,63],energi:65,enforc:[74,75],english:[46,65],enough:[11,76],ensur:[8,11,57,68,69,80,81],enter:[2,6,11,42,74],enterpris:65,entri:[59,74],enumer:[1,2,6,10,13,15,34,39,46,48,49,51,52,65,68,77],eoi:72,epc:65,equal:11,equat:[18,25,77],equival:[11,14,46,75],erm:[34,35],erm_0:34,erm_1:34,erm_2:34,erm_3:34,erm_4:34,err:[1,2,6,13,19,22,24,34,46,48,66],error:[1,2,6,10,13,19,22,23,24,34,39,40,43,45,46,48,52,66,67,68,69,70,72,77],error_cod:[1,2,6,10,13,19,22,23,24,34,36,39,40,43,45,46,48,66,68,70,72,73],error_rate_limit:52,escap:42,esp32:[3,7,11,13,24,31,33,45,49,68,69,70,72,75,80,81],esp32s2:3,esp32s3:3,esp:[3,5,7,10,11,16,18,25,28,31,36,37,50,52,63,66,68,69,70,72,75,76,78,80,81],esp_bt_dev_get_address:66,esp_err_t:[16,69],esp_err_to_nam:[],esp_error_check:16,esp_lcd_ili9341:16,esp_log:52,esp_ok:[1,2,6,13,19,22,34,46,48,66,69],esphom:16,espp:[1,2,3,5,6,7,8,10,11,12,13,15,16,18,19,22,23,24,25,26,28,29,31,32,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,76,77,78,80,81],espressif:[7,11,16,28,63,69,80,81],estim:75,etc:[10,24,42,46,48,51,67,69,73],evalu:[53,55],even:[66,73,75],evenli:33,event1:23,event1_cb:23,event2:23,event2_cb:23,event:[2,6,10,11,37,66,74,81],event_callback_fn:[10,23],event_count:2,event_flag:2,event_high_flag:2,event_low_flag:2,event_manag:23,eventbas:74,eventdata:81,eventmanag:[10,23],everi:[15,19,22,52],everybodi:11,everyth:11,exactli:65,exampl:[4,9,17,60,79],exceed:81,excel:8,except:[11,24],exchang:65,execut:[11,23,74,76,78],exis:81,exist:[7,11,14,24,72,73,74,75],exit:[1,2,3,5,6,8,11,13,18,19,22,34,36,39,40,45,46,48,49,51,67,68,69,70,74,76,77],exitact:11,exitchildren:74,exitselect:74,exp:[55,59],expand:37,expir:78,explicit:[1,2,3,5,6,7,8,10,11,12,13,15,18,19,22,26,28,29,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,61,62,63,65,66,67,68,69,70,72,76,77,78,80,81],explicitli:[11,76],expos:[11,14,52,75],extend:65,extern:[2,6,11,34,49,65,74,75],external_typ:65,extra:[69,72],extra_head:72,exttrigedg:34,exttriglvl:34,f4:65,f:[11,24],f_cutoff:[26,28],f_sampl:[26,28],fa:65,facil:59,factor:[19,22,28,33,77],fade:50,fade_time_m:50,fahrenheit:77,fail:[1,2,6,10,13,19,22,34,36,39,45,46,48,66,68,73,81],fake:76,fall:[2,6,10,66,69],falling_edg:10,fals:[1,2,3,5,6,7,8,10,11,13,16,18,19,22,23,24,31,33,34,36,39,40,43,44,45,46,48,49,50,51,57,59,62,63,66,67,68,69,70,72,74,76,77,78,81],famili:[1,2,6],far:11,fast:[37,56,66],fast_co:54,fast_ln:54,fast_math:54,fast_sin:54,fast_sqrt:54,fastest:[19,22],fault:7,fclose:24,fe:65,featur:[2,11],feedback:[33,34,35],feel:8,few:[11,16,23,74],ff:65,fi:[80,81],field:[2,6,8,24,49,65,66,68,72],field_fal:66,field_ris:66,figur:[14,24,73,74,75],file2:24,file:[32,37],file_byt:24,file_cont:24,file_s:24,file_str:24,file_system:24,filenam:14,filesystem:31,fill:[16,25,28,44,49,61,62,63,66],filter:[3,5,8,18,19,22,30,37,77],filter_cutoff_hz:[19,22],filter_fn:[8,19,22],find:[],fine:33,fine_values_no_det:33,fine_values_with_det:33,finger563:74,finish:[11,33,69],first:[2,8,23,34,51,62,63,65,66,72,77,78],first_row_is_head:14,fish:11,fit:15,fix:77,fixed_length_encod:73,fixed_resistance_ohm:77,flag:[2,6,16,23,65,66,69],flip:57,floatrangemapp:49,flush:[15,16,24],flush_callback:[15,16],flush_cb:[],flush_fn:15,fmod:50,fmt:[2,3,5,6,11,13,14,16,18,19,22,23,36,39,40,43,45,46,48,49,50,59,62,63,66,67,68,69,70,72,73,74,75,76,77,78,81],foc:[7,8],foc_curr:[],foc_typ:8,foctyp:8,folder:[4,9,11,14,17,18,49,52,59,60,67,73,74,75,76,78,79],follow:[2,6,8,25,33,34,51,54,59,65,66,69,74,77],font_align:75,font_background_color:75,font_color:75,font_styl:75,fontalign:75,fontstyl:75,fopen:24,forc:[7,15],force_refresh:15,form:[25,26,72],format:[2,6,14,16,23,24,37,59,65,72,75,76,77],formula:77,forum:65,forward:11,found:[19,22,34,45,65,66],four:1,frac:[25,55,77],frag_typ:72,fragment:72,frame:[2,6,51,72],fread:24,free:[15,24,50,69,75],free_spac:24,freebook:[25,29],freerto:[10,59,76,78],frequenc:[3,5,19,22,26,28,33,50],frequency_hz:50,frequent:[15,67],from:[1,2,3,5,6,7,8,11,12,13,15,16,19,22,23,24,27,31,33,34,35,36,37,39,40,43,44,45,46,48,49,50,52,55,57,58,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,81],from_sockaddr:61,fs:24,fseek:24,ft5x06:[37,41],ftell:24,fthat:12,ftm:66,ftp:[37,65,72],ftp_anon:65,ftp_client_sess:31,ftp_ftp:65,ftp_server:31,ftpclientsess:31,ftpserver:31,fulfil:[19,22],full:[7,46,51,72],fulli:[34,74,76],fun:23,further:72,futur:[52,65,72],fwrite:24,g:[12,24,34,46,51,55,65,69,77],g_bright:46,g_down:46,g_led:46,g_up:46,gain:[1,33,67],game:65,gamepad:[65,66],gamma:[50,55],gate:7,gaussian:[37,50,56],gb:14,gbc:14,gener:[2,19,22,27,61,65,69,72,80,81],generatedeventbas:74,generic_hid:65,geometr:12,gestur:39,get:[1,2,3,6,7,8,10,11,12,13,14,15,16,18,19,22,23,24,31,33,38,39,40,42,43,44,45,46,48,49,50,51,55,59,61,62,63,65,66,67,69,70,72,73,74,75,76,77,81],get_accumul:[19,22],get_all_mv:[2,6],get_all_mv_map:[2,6],get_bright:15,get_button_input_devic:38,get_button_st:68,get_celsiu:77,get_config:67,get_count:[18,19,22],get_dat:70,get_data:72,get_date_tim:70,get_degre:[18,19,22],get_digital_input_valu:[2,6],get_duti:50,get_electrical_angl:8,get_encoder_input_devic:38,get_error:67,get_event_data:2,get_event_flag:2,get_event_high_flag:2,get_event_low_flag:2,get_fahrenheit:77,get_free_spac:24,get_ftm_length:66,get_head:72,get_height:72,get_histori:11,get_home_button_input_devic:44,get_home_button_st:[40,45],get_id:65,get_info:76,get_input_devic:42,get_integr:67,get_interrupt_captur:48,get_interrupt_statu:66,get_ipv4_info:[61,62,63],get_jpeg_data:72,get_kei:43,get_kelvin:77,get_mechanical_degre:[19,22],get_mechanical_radian:[19,22],get_mjpeg_head:72,get_mount_point:24,get_mv:[2,3,6,77],get_num_q_t:72,get_num_touch_point:[39,40,45],get_offset:[16,72],get_output:46,get_output_cent:57,get_output_max:57,get_output_min:57,get_output_rang:57,get_packet:72,get_partition_label:24,get_payload:72,get_pin:[46,48],get_posit:33,get_power_supply_limit:7,get_q:72,get_q_tabl:72,get_quantization_t:72,get_radian:[18,19,22],get_rat:3,get_remote_info:62,get_resist:77,get_revolut:18,get_root_path:24,get_rpm:[19,22],get_rpt_head:72,get_rtp_header_s:72,get_scan_data:72,get_session_id:72,get_shaft_angl:8,get_shaft_veloc:8,get_siz:65,get_stat:13,get_terminal_s:11,get_tim:70,get_total_spac:24,get_touch_point:[39,40,45],get_touchpad_input_devic:44,get_type_specif:72,get_used_spac:24,get_user_input:11,get_user_select:74,get_valu:[13,49],get_values_fn:49,get_vers:72,get_voltag:77,get_voltage_limit:7,get_width:72,getactivechild:74,getactiveleaf:74,getiniti:74,getinputhistori:11,getlin:11,getparentst:74,getsocknam:[61,62,63],getter:[58,72],gettimerperiod:74,gettin:49,gimbal:33,github:[11,14,16,33,53,63,66,69,72,74,75],give:[61,74,76],given:[2,6,23,26,68,72,74],glitch:18,global:[3,46],go:[23,24,74],goe:[2,6],gone:76,goodby:11,googl:66,got:[2,23,72,81],gotten:[11,81],gpio:[2,7,10,13,15,18,46,48,50,69],gpio_a:13,gpio_a_h:[7,8],gpio_a_l:[7,8],gpio_b:13,gpio_b_h:[7,8],gpio_b_l:[7,8],gpio_c_h:[7,8],gpio_c_l:[7,8],gpio_config:2,gpio_config_t:2,gpio_down:13,gpio_en:[7,8],gpio_evt_queu:2,gpio_fault:[7,8],gpio_i:13,gpio_install_isr_servic:2,gpio_intr_negedg:2,gpio_isr_handl:2,gpio_isr_handler_add:2,gpio_joystick_select:13,gpio_left:13,gpio_mode_input:2,gpio_mode_output:43,gpio_num:[10,51,69],gpio_num_10:43,gpio_num_12:70,gpio_num_14:70,gpio_num_18:[16,39,40,43,45],gpio_num_19:[16,36,68],gpio_num_22:[16,36,68],gpio_num_23:16,gpio_num_2:10,gpio_num_37:10,gpio_num_45:16,gpio_num_48:16,gpio_num_4:16,gpio_num_5:16,gpio_num_6:16,gpio_num_7:16,gpio_num_8:[39,40,43,45],gpio_num_nc:36,gpio_num_t:[15,16,36],gpio_pullup:13,gpio_pullup_dis:[2,6,36],gpio_pullup_en:[1,2,13,19,22,34,39,45,46,48,66,70],gpio_pullup_t:36,gpio_right:13,gpio_select:13,gpio_set_direct:43,gpio_set_level:43,gpio_start:13,gpio_up:13,gpio_x:13,gpo:66,grab:49,gradient:12,grai:52,graphic:12,gravit:75,grb:51,greater:52,green:[12,51,52,69,75],greengrass:75,grei:75,ground:13,group:[24,61,62,63,65],group_publ:65,gt911:[37,41],guarante:51,guard:74,gui:[15,16,59],guid:[11,80,81],h:[11,12,16,52,72],ha:[2,6,8,11,13,18,19,22,23,24,31,34,40,43,46,48,50,51,59,62,63,65,66,69,72,74,75,76,78,81],hack:11,half:[19,22,25],handl:[10,11,31,46,48,51,62,63,69,74,76],handle_all_ev:74,handle_res:11,handleev:74,handler:[2,10,63],handov:65,handover_vers:65,happen:[11,23],haptic:37,haptic_config:33,haptic_motor:33,hapticconfig:33,hardawr:50,hardwar:[8,18,28,46,50,51,72],harmless:78,hart:77,has_ev:74,has_q_tabl:72,has_stop:74,has_valu:[3,5,13,49,50,77],hash:65,have:[2,6,8,11,14,15,23,25,33,34,38,46,49,50,51,52,59,62,67,68,69,72,74,75,76,77,78,80,81],hc:65,heart:8,height:[11,15,16,72],hello:[11,66],hello_everysess:11,help:65,helper:61,henri:8,here:[11,14,19,23,34,46,48,66,67,74,75,78],hertz:36,hid:65,hid_dev_mod:66,hide_bord:75,hide_border_left:75,hide_border_right:75,hide_border_top:75,high:[2,3,6,7,10,15,18,33,43,48,59,69],high_level:10,high_limit:18,high_resolution_clock:[1,2,6,8,10,19,22,34,46,48,50,51,52,59,67,69,76,77],high_threshold_mv:2,high_water_mark:59,higher:[25,28],highlight:75,histori:[11,25,26,28,29,74],history_s:11,hmi:16,hold:[11,15,65,66],home:[38,40,44,45],hop:[61,62,63],horizont:75,host:[2,6,16,46,65,80],hot:77,hour:70,how:[8,14,15,18,67,73,74,75,77],howev:25,hpp:[0,1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,20,22,23,24,25,26,28,29,30,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,54,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],hr:65,hs:65,hsfm:74,hsv:[12,51,68,69,70],html:[7,11,15,16,25,29,65,69,80,81],http:[2,6,7,8,11,14,15,16,19,24,25,26,29,33,34,46,52,53,61,62,63,65,66,69,72,74,75,77,80,81],http_www:65,https_www:65,hue:[12,51,69],human:[14,24,75],human_read:24,hz:[3,33],i2c:[4,19,21,22,34,37,39,40,43,45,46,47,48,51,66,68,70],i2c_cfg:[1,2,6,13,19,22,34,46,48,66],i2c_config_t:[1,2,6,13,19,22,34,46,48,66],i2c_driver_instal:[1,2,6,13,19,22,34,46,48,66],i2c_freq_hz:[1,2,6,13,19,22,34,46,48,66],i2c_master_read_from_devic:[1,2,6,13],i2c_master_write_read_devic:[19,22,34,46,48,66],i2c_master_write_to_devic:[1,2,6,13,19,22,34,46,48,66],i2c_mode_mast:[1,2,6,13,19,22,34,46,48,66],i2c_num:[1,2,6,13,19,22,34,46,48,66],i2c_num_0:[36,39,40,43,45,68,70],i2c_num_1:[],i2c_param_config:[1,2,6,13,19,22,34,46,48,66],i2c_port_t:36,i2c_read:34,i2c_scl_io:[1,2,6,13,19,22,34,46,48,66],i2c_sda_io:[1,2,6,13,19,22,34,46,48,66],i2c_timeout_m:[1,2,6,13,19,22,34,46,48,66],i2c_writ:34,i:[2,6,8,14,18,37,47,51,59,66,67,73,74,75,76,77],i_gpio:18,id:[2,6,10,31,34,65,72,76,78],ident:11,identifi:[34,65,72],idf:[3,5,7,10,11,36,37,50,52,63,69,80,81],ifs:24,ifstream:24,ignor:[11,18,23],iir:28,il:65,imag:72,imap:65,imax:46,imax_25:46,imax_50:46,imax_75:46,immedi:[74,76],imped:[7,75],impl:[26,29],implement:[2,6,7,8,9,11,12,25,26,28,29,31,32,33,53,54,55,58,65,72,74,78],implicit:[19,22],improv:11,impuls:28,inact:65,includ:[0,1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,20,22,23,24,25,26,28,29,30,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,54,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],incom:62,incomplet:65,increas:[10,18,52,67],increment:[2,6,18,38,46],incur:15,independ:[49,58,75],index:[2,6,18,51,58,72,77],indic:[46,48,62,63,65,66,76],individu:[6,49,53],induct:8,infinit:28,info:[1,2,3,5,6,10,13,18,23,33,34,49,51,52,59,61,62,63,67,69,72,77,78],info_rate_limit:52,inform:[12,15,19,22,26,29,46,48,49,51,53,59,61,62,63,65,66,69,74,77,80,81],infrar:69,inherit:11,init:[34,36,49,61,62],init_ipv4:61,init_low_level:66,initail:[3,77],initi:[1,2,3,5,6,7,8,10,13,15,16,18,19,22,28,34,36,38,42,43,44,46,48,49,50,55,57,61,62,63,66,69,74,76,78,80,81],inlin:[1,2,3,5,6,7,8,10,11,13,15,16,18,19,22,23,24,25,26,28,29,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,59,61,62,63,65,66,67,68,69,70,72,74,76,77,78,80,81],inout:2,input:[2,6,8,10,11,13,19,22,25,26,28,29,33,34,37,40,46,48,49,57,70],input_delay_n:16,input_driv:[38,42,44],input_valu:2,inquiri:65,insert:11,insid:2,instal:[1,2,6,10,13,19,22,34,46,48,66],instanc:[23,24,75],instant:50,instanti:59,instead:[11,31,57,73,74],instruct:28,instrument:[2,6,34],int16_t:18,int8_t:73,integ:[7,18,54,61,66],integr:67,integrator_max:[8,67],integrator_min:[8,67],intend:[53,74,76],interact:[11,21,23,24,43,47,72],interest:[13,23],interfac:[7,9,10,15,21,24,31,33,34,36,37,40,43,46,47,48,51,68,69,72],interfer:33,intermedi:65,intern:[2,11,13,16,18,25,26,28,29,34,46,48,61,74],interpol:12,interrupt:[2,10,18,46,48,66,76],interrupt_typ:10,interrupttyp:10,interv:43,intr_typ:2,introduc:57,inttrig:34,invalid:[11,12],invalid_argu:11,invers:50,invert:[13,44,46,48,50,57],invert_color:16,invert_i:44,invert_input:57,invert_output:57,invert_x:44,invoc:67,io:[15,16,24,37,53,65],io_conf:2,io_num:2,ip2str:81,ip:[31,61,62,63,72,81],ip_add_membership:[61,62,63],ip_address:[31,62,63,72],ip_callback:81,ip_event_got_ip_t:81,ip_evt:81,ip_info:81,ip_multicast_loop:[61,62,63],ip_multicast_ttl:[61,62,63],ipv4:61,ipv4_ptr:61,ipv6:61,ipv6_ptr:61,ir:69,irdaobex:65,is_a_press:13,is_act:72,is_al:31,is_b_press:13,is_charg:23,is_clos:72,is_complet:72,is_connect:[31,62,72,81],is_dir:24,is_directori:24,is_down_press:13,is_en:[7,8],is_fault:7,is_floating_point:58,is_left_press:13,is_multicast_endpoint:63,is_passive_data_connect:31,is_press:[10,13,68],is_right_press:13,is_run:[33,76,78],is_select_press:13,is_start:76,is_start_press:13,is_up_press:13,is_valid:[61,62,63],isr:[2,10],issu:11,istream:11,it_st:66,ital:75,item:[14,24],iter:[16,23,24,62,63,76,78],its:[2,3,6,19,22,23,31,33,46,48,55,59,61,62,63,66,67,74,80],itself:[15,23,38,42,44,72,76],j:75,join:[61,62,63],josh:75,joybonnet:[1,13],joystick:[2,13,37,65],joystick_config:13,joystick_i:13,joystick_select:13,joystick_x:13,jpeg:72,jpeg_data:72,jpeg_fram:72,jpeg_frame_callback_t:72,jpeg_head:72,jpegfram:72,jpeghead:72,jpg:14,js1:49,js2:49,jump:57,june:75,just:[2,13,19,22,23,65,69,72,73,74,77],k:[11,77],k_bemf:8,kbit:66,kd:[8,33,67],kd_factor_max:33,kd_factor_min:33,keep:78,keepal:62,kei:[11,43,65,66,72],kelvin:77,key_cb:43,key_cb_fn:43,keyboard:[11,37,41,65],keypad:[37,41,43],keypad_input:42,keypadinput:42,kg:75,ki:[8,67],kind:[20,74],know:[15,19,22,23,76],known:[65,74],kohm:48,kp:[8,33,67],kp_factor:33,kv:8,kv_rate:8,l:11,label:[16,24],lack:24,lambda:[1,2,6,13,19,22,34,46,48,52,66,77],landscap:[15,16],landscape_invert:15,larg:72,larger:[3,11,72],last:[13,18,34,40,45,49,51,65,67,68,74],last_button_st:68,last_it_st:66,last_unus:13,latch:69,later:[7,16,18,78],latest:[7,11,44,49,59,67,69,77,80,81],launch:65,launcher:[],launcher_record:[],lazi:14,lcd:16,lcd_send_lin:16,lcd_spi_post_transfer_callback:16,lcd_spi_pre_transfer_callback:16,lcd_write:16,le:65,le_rol:65,le_sc_confirm:65,le_sc_random:65,lead:[3,12],leaf:74,learn:[34,65],least:[18,51,62,68],leav:[2,6],led:[2,37,46,69],led_callback:50,led_channel:50,led_encod:[51,69],led_encoder_st:69,led_fade_time_m:50,led_reset_cod:69,led_stip:69,led_strip:[51,69],led_task:50,ledc:50,ledc_channel_5:50,ledc_channel_t:50,ledc_high_speed_mod:[],ledc_low_speed_mod:50,ledc_mode_t:50,ledc_timer_10_bit:50,ledc_timer_13_bit:50,ledc_timer_2:50,ledc_timer_bit_t:50,ledc_timer_t:50,ledstrip:51,left:[13,16,18,42,51,68,75],legaci:65,legend:[14,75],len:[40,51],length16:[],length:[2,6,16,25,28,36,39,40,45,51,58,65,66,68,69],less:[7,49,65,66,76],let:[11,15,23,59],level0:69,level1:69,level:[7,8,9,10,23,33,34,39,43,45,48,51,52,61,62,63,65,68,69,72,74,77,78],leverag:28,lh:[68,70],lib:34,libarari:73,libfmt:52,librari:[11,23,24,33,34,37,65,73,75],licens:75,life:[11,73],lifecycl:15,light:[12,38,42,44,52,73,74,75],like:[23,61],lilygo:[37,41],limit:[7,8,11,18,52,65,67],limit_voltag:[7,8],line:37,line_input:11,linear:[34,35],lineinput:11,link:[14,24],links_awaken:14,list:[2,6,24,34,65],list_directori:24,listconfig:24,listen:[31,62,72],lit:[2,6,34],littl:[23,50],littlef:24,lk:[1,2,3,5,6,8,13,18,19,22,23,34,36,39,40,45,46,48,49,50,51,67,68,69,70,74,76,77],ll:[1,2,6,13,19,22,23,34,39,40,43,45,46,48,51,66,68,70,78],ln:77,load:[13,14,65],local:65,lock:[62,66,76],log:[2,6,8,10,23,33,34,37,38,39,40,42,43,44,45,46,48,50,51,59,66,68,69,70,72,74,76,77,78],log_level:[1,2,3,5,6,7,8,10,13,15,18,19,22,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,62,63,66,67,68,69,70,72,74,76,77,78,80,81],logger1:52,logger1_thread:52,logger2:52,logger2_thread:52,logger:[1,2,3,5,6,7,8,10,13,15,18,19,22,23,24,33,34,36,37,38,39,40,42,43,44,45,46,48,49,50,51,61,62,63,66,67,68,69,70,72,74,76,77,78,80,81],logger_:[15,49],logger_config:61,logger_fn:52,logic:[2,6,13,63,65],long_local_nam:65,longer:11,loop:[8,9,11,19,22,24,33,52,76],loop_foc:8,loop_iter:52,loopback_en:[61,62,63],loos:23,lose:11,lot:[10,75],low:[2,5,6,7,8,9,10,13,18,23,48,61,65,69],low_level:10,low_limit:18,low_threshold_mv:2,lower:[18,46,48,77],lowest:[10,76,78],lowpass:[27,37],lowpass_filt:28,lowpassfilt:28,lra:[34,35],lsb:[2,6,46,48],lv_area_t:[15,16],lv_color_t:[15,16],lv_disp_drv_t:[15,16],lv_disp_flush_readi:15,lv_indev_t:[38,42,44],lv_tick_inc:15,lvgl:[15,16,38,42,44],lvgl_esp32_driv:16,lvgl_tft:16,m:[1,2,3,5,6,8,13,18,19,22,23,33,34,36,39,40,45,46,48,49,50,51,52,62,66,67,68,69,70,74,75,76,77],m_pi:[19,22,59],ma:77,mac:[65,66,81],mac_addr:65,mac_address:65,machin:37,macro:52,made:66,magenta:75,magic_enum_no_check_support:74,magnet:[21,33,37,75],magnetic_det:33,magnitud:[49,58,67],magnitude_squar:58,mai:[2,3,6,10,33,51,65,66,74],mailbox:66,mailto:65,main:[8,15,69],mainli:15,maintain:[15,19,22,66],make:[1,2,6,8,13,19,22,23,24,34,36,39,40,43,45,46,48,61,65,66,68,70,72,74,77],make_alternative_carri:65,make_android_launch:[65,66],make_ev:74,make_handover_request:65,make_handover_select:[65,66],make_le_oob_pair:[65,66],make_multicast:[61,62,63],make_oob_pair:65,make_shar:[8,16],make_text:[65,66],make_uniqu:[1,2,6,11,13,34,50,59,62,63,69,76],make_uri:[65,66],make_wifi_config:[65,66],makeact:74,maker:75,malloc_cap_8bit:15,malloc_cap_dma:15,manag:[5,12,13,14,15,24,37,46,48,50,62,63,65,66],mani:[8,10,18,23,62,63,81],manipul:10,manual:[2,6,11,33,72,74],manual_chid:[2,6],map:[2,6,13,49,57,72],mapped_mv:2,mapper:[37,49,56],mario:14,mark:[59,72],markdownexport:75,marker:72,mask:[46,48],maskaravivek:65,mass:[34,35],master:[1,2,6,11,13,16,19,22,34,46,48,63,66,69],match:[24,31,68,70],math:[37,53,55,57,58],matrix:42,max:[2,7,18,33,34,46,55,57,62,63,67,80],max_connect:62,max_data_s:72,max_glitch_n:18,max_led_curr:46,max_num_byt:[62,63],max_number_of_st:80,max_pending_connect:62,max_receive_s:62,max_transfer_sz:16,maximum:[7,13,19,22,46,49,57,62,63,67,72],maxledcurr:46,maybe_duti:50,maybe_mv:[3,5,77],maybe_r:3,maybe_x_mv:[13,49],maybe_y_mv:[13,49],mb:[24,65],mb_ctrl:66,mcp23x17:[37,47],mcp23x17_read:48,mcp23x17_write:48,mcpwm:[7,33],me:65,mean:[7,10,12,19,22,25,49,57,59,69,73,76,78],measur:[3,5,8,18,19,22,49,67,77],mechan:[3,8,19,22,23,31],media:65,mega_man:14,megaman1:14,megaman:14,member:[1,2,3,5,6,7,8,10,12,13,15,18,19,22,24,26,28,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,59,61,62,63,65,66,67,68,69,70,72,76,77,78,80,81],memori:[11,15,25,28,50,66,69,75,76],memset:[1,2,6,13,16,19,22,34,46,48,66],mention:11,menu:11,menuconfig:24,mere:7,messag:[1,2,6,10,13,23,24,34,45,46,48,65,66,68,70,72,73,74],message_begin:65,message_end:65,method:[8,10,18,24,53,55,67,72,73],metroid1:14,metroid:14,micro:16,micros_per_sec:69,middl:65,might:78,millisecond:[36,43,50],millivolt:77,mime_media:65,min:[2,33,57],minimum:[13,49,57,67],minu:72,minut:[19,22,70],mireq:16,mirror:48,mirror_i:16,mirror_x:16,miso_io_num:16,mit:75,mix:12,mjepg:72,mjpeg:72,mkdir:24,mode:[1,2,3,6,10,13,16,19,22,33,34,46,48,50,65,66],model:[12,74],moder:5,modern:75,modif:8,modifi:[16,46,72],modul:[],modulo:[19,22],monitor:37,month:70,more:[2,3,6,11,12,15,26,27,29,34,49,50,51,52,55,61,62,63,65,69,74,77],mosi:16,mosi_io_num:16,most:[3,8,13,19,22,49,67],motion:[8,33],motion_control_typ:8,motioncontroltyp:8,motoion:8,motor:[7,9,19,22,33,35,37],motor_task:8,motor_task_fn:8,motor_typ:34,motorconcept:33,motortyp:34,mount:24,mount_point:24,mous:65,move:[8,11,51,59,69,76],move_down:39,move_left:39,move_right:39,move_up:39,movement:11,movi:75,ms:15,msb:[2,6,46,48],msb_first:69,msg:74,mt6701:[8,21,37],mt6701_read:[8,22],mt6701_write:[8,22],much:[25,75],multi_byte_charact:75,multi_rev_no_det:33,multicast:[61,62],multicast_address:[61,62,63],multicast_group:[61,62,63],multipl:[3,5,8,13,33,34,35,52,67,72],multipli:[33,58,67],must:[2,5,6,8,11,18,23,24,43,59,61,62,63,65,66,73,74,76,80,81],mutabl:[58,76],mutat:76,mute:2,mutex:[1,2,3,5,6,8,13,18,19,22,23,34,36,39,40,45,46,48,49,50,51,62,66,67,68,69,70,74,76,77],mutual:45,mux:[2,6],mv:[1,2,3,5,6,49,77],mystruct:73,n:[2,3,5,6,11,13,14,18,19,22,23,24,25,29,30,36,39,40,43,45,46,48,49,50,59,62,63,66,67,68,69,70,72,73,74,75,76,77,78,81],name:[1,2,3,5,6,8,10,13,14,18,19,22,23,34,36,39,40,45,46,48,49,50,51,59,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78],namespac:[1,2,6,13,24,34,75],nanosecond:18,navig:11,nby:75,ncharact:75,ncustom:75,ndef:[37,64,66],ndeflib:65,ndefmessag:65,ne:[14,68],nearest:[33,54],necessari:[8,76],need:[3,5,10,11,19,22,23,24,25,33,43,46,59,65,67,69,74,76],needs_zero_search:[19,22],neg:[51,58,67,77],negat:[13,58],neo_bff_io:51,neo_bff_num_l:51,neopixel_writ:51,nest:75,network:[37,62,63,65,80],new_address:68,new_data:[40,45],new_duti:50,new_object:73,new_siz:11,new_target:8,newli:76,newlin:59,newtonian:75,next:[11,33,34,69],nf:65,nfault:8,nfc:[37,65,66],nfcforum:65,nice:75,nicer:52,nm:8,no_timeout:76,nocolor:11,node:[61,62,63,74],nois:57,nomin:77,nominal_resistance_ohm:77,non:[3,33,57,66],nonallocatingconfig:15,none:[2,6,15,31,39,52,65,68,70,74],normal:[15,23,25,58,74],normalizd:[26,28],normalized_cutoff_frequ:[19,22,26,28],note:[1,2,3,5,6,8,10,11,13,18,19,22,23,24,31,33,34,36,39,40,45,46,48,49,51,52,62,63,67,68,69,70,73,74,75,76,77],noth:[7,59,78],notifi:[2,72,76],now:[1,2,6,8,10,11,14,19,22,23,33,34,39,40,43,45,46,48,50,51,52,59,62,63,66,67,68,69,70,76,77],ntc:[6,77],ntc_channel:6,ntc_mv:6,ntc_smd_standard_series_0402:77,ntcg103jf103ft1:77,nthe:81,nullopt:[50,63],nullptr:[8,11,19,22,24,58,62,63,66,74,81],num:72,num_column:[],num_connect_retri:81,num_l:51,num_periods_to_run:50,num_pole_pair:8,num_seconds_to_run:[50,52,67,76],num_steps_per_iter:76,num_task:[59,76],num_touch:44,num_touch_point:[39,40,45],number:[1,2,3,6,8,10,11,15,16,18,19,22,24,25,28,33,34,39,40,44,45,46,48,50,51,54,61,62,63,65,66,69,70,72,77,80,81],number_of_link:24,nvs_flash_init:[80,81],o:[2,6,37,47],object:[8,10,11,12,14,23,51,52,55,59,65,68,69,72,73,74,76,77,78],occur:[2,6,23,40,43,45,46,48,66,72,74],octob:75,off:[2,7,11,18,33,46,52,65,72,77],offset:[16,66,72],offset_i:16,offset_x:16,ofs:24,ofstream:24,ohm:[8,77],ok:[11,72],oldest:11,on_connect:81,on_disconnect:81,on_got_ip:81,on_jpeg_fram:72,on_off_strong_det:33,on_receive_callback:63,on_response_callback:[62,63],onc:[6,13,18,19,22,23,72,78],once_flag:23,one:[2,10,11,19,22,23,31,50,51,62,63,66,69,74,75,78],oneshot:[4,37],oneshot_adc:5,oneshotadc:[5,13,49],onli:[2,6,8,11,13,14,18,19,22,23,25,49,52,58,63,65,66,69,72,73,74,75,78],oob:[65,66],open:[2,6,8,9,11,24,33,62,65,80,81],open_drain:[2,6,46],oper:[2,6,12,24,26,28,29,53,55,58,67,68,70,77],oppos:12,opposit:50,optim:[8,25,54],option:[2,3,5,6,7,8,11,13,15,16,19,22,38,44,49,50,51,52,57,61,62,63,65,72,73,76,78],order:[2,6,25,26,27,30,37,51,52,62],oreilli:65,org:[25,26,29,61,62,63,65,77],orient:[8,15],origin:24,oscil:[2,57],osr_128:[2,6],osr_16:[2,6],osr_2:[2,6],osr_32:[2,6],osr_4:[2,6],osr_64:[2,6],osr_8:[2,6],ostream:11,ostringstream:14,other:[2,6,8,11,12,15,58,61,62,63,66,67,73,74,76,80],otherwis:[2,6,7,8,10,13,19,22,23,31,33,34,40,43,46,48,49,50,62,63,65,66,69,70,72,74,76,78,81],our:[50,61,62,63,76],out:[11,14,24,59,61,62,63,65,69,73,74,75,77],output:[2,6,8,9,11,18,23,24,25,26,28,29,31,44,46,48,50,52,55,57,59,66,67,68,70],output_cent:57,output_drive_mode_p0:46,output_invert:50,output_max:[8,57,67],output_min:[8,57,67],output_mod:[2,6],output_rang:57,outputdrivemodep0:46,outputmod:[2,6],outsid:[2,11,12],over:[2,7,21,24,47,50,60,62,63,72,76],overflow:[18,25],overhead:[15,23],overload:24,overrid:74,oversampl:[2,6],oversampling_ratio:[2,6],oversamplingratio:[2,6],overstai:52,overth:[2,6],overwrit:[46,72,78],own:[3,15,19,22,31,46,48,61,62,63,80],owner:24,p0:46,p0_0:46,p0_1:46,p0_2:46,p0_3:46,p0_5:46,p1:46,p1_0:46,p1_1:46,p1_5:46,p1_6:46,p1_7:46,p1_8:46,p:[2,6,11,14,67,75],pa_0:48,pack:13,packag:65,packet:[61,62,63,65,72],packet_:72,pad:13,padding_bottom:75,padding_left:75,padding_right:75,padding_top:75,page:[24,65,77],pair:[8,65,66],panel:44,param:[1,2,6,8,15,19,22,23,34,39,40,43,44,45,46,48,49,51,61,62,63,66,68,69,70,76,81],paramet:[1,2,3,5,6,7,8,10,11,12,13,15,16,19,20,22,23,24,25,26,28,29,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,61,62,63,65,66,67,68,69,70,72,74,76,77,78,80,81],parent:74,pars:[14,59,72],part:[7,16,33,44,77],parti:73,partit:24,partition_label:24,pass:[2,6,10,16,23,31,52,57],passiv:31,password:[31,65,80,81],pasv:31,pat:65,path:[24,31,72],paul:75,paus:[15,72],payload:[65,66,72],payload_id:66,payload_s:72,pb_7:48,pdf:[2,6,19,34,46,65,66,69,77],pend:62,per:[1,2,3,6,8,19,22],perceiv:12,percent:50,percentag:[7,33,50],perform:[2,3,5,6,12,24,49,76],perhipher:50,period:[10,13,15,19,22,23,36,39,40,45,46,48,59,66,68,70,74,78],peripher:[7,18,33,35,43,50,51,65,69],peripheral_centr:65,peripheral_onli:[65,66],permeabl:75,permiss:24,permitt:75,person:65,phase:[7,8],phase_induct:8,phase_resist:8,phillip:75,phone:[65,66],photo:66,php:65,pick:18,pico:49,pid:[8,33,37],pid_config:67,pin:[1,2,6,7,8,10,13,15,16,34,36,43,46,48,50,69,76,78],pin_bit_mask:2,pin_mask:48,pinout:8,pixel:[15,16,51,72],pixel_buffer_s:[15,16],place:[23,33],placehold:[39,40,43,45,68,70],plai:[34,72,75],plan:77,planck:75,platform:[52,76,78],play_hapt:33,playback:34,pleas:[11,12,14,29,34,74,75],plot:[2,6],pn532:65,point:[12,18,24,25,28,33,37,39,40,44,45,50,53,54,58,62,63,65,66,79,81],pointer:[1,2,6,15,16,19,22,25,28,33,34,44,46,48,49,51,61,62,66,69,72,74,76,81],pokemon:14,pokemon_blu:14,pokemon_r:14,pokemon_yellow:14,polar:48,pole:8,poll:[13,19,22,39,40,43,45,46,48,66,68,70],polling_interv:43,pomax:53,pop:65,popul:63,port0:[46,48],port1:[46,48],port:[8,15,31,36,39,40,43,45,46,48,61,62,63,68,70,72],port_0_direction_mask:[46,48],port_0_interrupt_mask:[46,48],port_1_direction_mask:[46,48],port_1_interrupt_mask:[46,48],port_a:48,port_a_direction_mask:[],port_a_interrupt_mask:[],port_b:48,port_b_direction_mask:[],port_b_interrupt_mask:[],portmax_delai:2,portrait:[15,16],portrait_invert:15,porttick_period_m:[1,2,6,13,19,22,34,46,48,66],pos_typ:24,posit:[8,11,16,18,19,22,33,44,45,49,57],posix:[60,61],possibl:[2,6,7,15,57,65],post:65,post_cb:16,post_transfer_callback:15,poster:65,potenti:[3,25,31,68,70],power:[2,6,7,8,43,51,65],power_ctrl:43,power_st:65,power_supply_voltag:[7,8],pranav:14,pre:[16,67,69],pre_cb:16,precis:69,preconfigur:34,predetermin:[2,6],prefer:65,prefix:[2,6,24],prepend:52,present:[36,45,65,72],preset:34,press:[2,10,11,13,40,43,44,45,68],prevent:[15,67],previou:[11,46,50,78],previous:[7,57],primari:69,primarili:11,primary_data:69,print:[2,3,5,6,11,13,14,18,19,22,23,36,39,40,43,45,46,48,49,50,52,59,62,63,66,67,68,69,70,72,73,74,75,76,77,78,81],printf:[13,19,22,46,48,66],prior:[66,80,81],prioriti:[3,8,10,15,52,59,76,78],privat:11,probe:36,probe_devic:[36,43],process:[50,62,63,76],processor:[2,6,28,76],produc:12,product:[46,58,69,74,77],profil:33,programm:2,programmed_data:66,project:[7,11,31,68,69,70,72,80,81],prompt:11,prompt_fn:11,proper:[12,74],properli:[5,72],proport:67,protocol:[31,51,62,63,69],protocol_examples_common:11,prototyp:[23,44,70],provid:[1,2,3,4,5,6,7,8,9,10,11,12,13,14,15,16,17,18,19,21,22,23,24,25,26,27,28,29,30,32,33,35,36,37,38,40,42,43,44,46,47,48,49,50,51,52,53,54,55,57,58,59,60,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,79,81],prt:61,pseudost:74,psram:75,pub:23,publish:[10,23],pull:[2,6,46,48],pull_up_en:2,pulldown:10,pulldown_en:10,pullup:[10,36],pullup_en:10,puls:[2,6,18,69],pulsed_high:[2,6],pulsed_low:[2,6],pulsing_strong_1:34,pulsing_strong_2:34,pure:[18,74],push:[2,6],push_back:75,push_pul:[2,6,46],push_push:[],put:66,pwm:[7,8,9,34,50],pwmanalog:34,py:49,python:59,q0:72,q0_tabl:72,q1:72,q1_tabl:72,q:[8,28,72],q_current_filt:8,q_factor:28,qt:49,qtpy:36,quadhd_io_num:16,quadratur:18,quadwp_io_num:16,qualiti:28,quantiti:75,quantiz:72,queri:36,question:[11,14,50,66,75],queu:69,queue:[2,10,11,69],queue_siz:16,quickli:74,quit:66,quit_test:[13,19,22,48,66,68],quote_charact:14,qwiic:[36,68],qwiicn:[37,70],r0:77,r1:[2,6,77],r25:77,r2:[2,6,77],r:[12,24,46,51,57,65,69,77],r_0:77,r_bright:46,r_down:46,r_led:46,r_scale:77,r_up:46,race:50,rad:8,radian:[8,18,19,22,58],radio:[65,66],radio_mac_addr:66,radiu:49,rainbow:[51,69],ram:15,ranav:[14,75],random:65,random_valu:65,rang:[1,7,12,19,22,24,26,28,33,35,37,49,55,56,77,80],range_mapp:57,rangemapp:[49,57],rate:[1,3,8,19,22,46,48,52],rate_limit:52,ratio:[2,6],ration:53,raw:[1,2,5,6,8,13,19,22,49,53,61,65,66,68],rb:24,re:[11,13,19,22,34,61,62,63,69,74,77],reach:[34,62,66,74],read:[1,2,3,5,6,8,10,11,13,19,22,24,34,36,38,39,40,42,43,44,45,46,48,49,62,66,68,70,77],read_address:68,read_at_regist:[36,39,68,70],read_at_register_fn:39,read_button_accumul:68,read_current_st:68,read_data:[36,40],read_fn:[1,2,6,19,22,34,38,42,43,45,46,48,66,70],read_gestur:39,read_joystick:[13,49],read_kei:43,read_len:40,read_mv:[5,13,49,77],read_mv_fn:77,read_raw:5,read_siz:36,read_valu:14,readabl:[14,24,75],reader:[3,5,49],readi:[43,78],readm:75,readthedoc:65,real:[23,34],realli:[14,73,74,75],realtim:34,reason:[73,76],receic:23,receiv:[2,16,61,62,63,66,72],receive_callback_fn:[61,62,63],receive_config:63,receiveconfig:63,recent:[2,3,8,13,19,22,49,67],recommend:[19,22,23,49,76],record:[65,66],record_data:66,rectangular:49,recurs:[24,74],recursive_directory_iter:24,recvfrom:[61,63],red:[12,14,51,52,69,75],redraw:[11,15],redrawn:11,reepres:72,refer:37,reference_wrapp:33,refresh:15,reg:66,reg_addr:[19,22,34,36,46,48,66],regard:[19,22],regardless:49,region:[2,6],regist:[2,6,10,19,22,23,34,36,38,39,42,44,46,48,66,68,70,72],register_address:[36,70],registr:23,registri:23,reinit:62,reiniti:62,reistor:46,rel:57,relat:[11,50],releas:[10,75],relev:[24,77],reli:74,reliabl:[19,22,62],remain:52,remot:[37,62,63,65],remote_control:65,remote_info:63,remov:[7,11,23,24],remove_publish:23,remove_subscrib:23,renam:24,render:[15,59],repeat:78,repeatedli:[69,76,78],replac:11,report:66,repres:[12,19,22,31,50,58,65,66,67,68,69,72],represent:[12,65,75],request:[2,6,31,61,62,63,65,66,72],requir:[8,66,75],rescal:12,reserv:65,reset:[2,6,16,18,66,67,69],reset_fn:69,reset_pin:16,reset_st:67,reset_tick:69,reset_valu:16,resist:[8,77],resistor:[10,46,77],resistordividerconfig:77,resiz:[11,24,59,76],resolut:[50,69],resolution_hz:[51,69],resolv:[31,68,70],reson:[34,35],resourc:[5,61,62,63,66,69],respect:[4,72,74],respond:[61,62,63],respons:[15,24,28,31,65,67,72],response_callback_fn:[61,62,63],response_s:[62,63],response_timeout:63,restart:[74,78],restartselect:74,restrict:[19,22],result:[2,3,6,11,12,58,72],resum:15,ret:16,ret_stat:69,retri:[72,81],retriev:[3,13,44,49],return_to_center_with_det:33,return_to_center_with_detents_and_multiple_revolut:33,reusabl:[11,37],revers:[62,63],revolut:[18,19,22,33],rf:66,rf_activ:66,rf_get_msg:66,rf_intterupt:66,rf_put_msg:66,rf_user:66,rf_write:66,rfc:[65,72],rfid:[65,66],rgb:[12,51,68,69,70],rh:[12,58,68,70],right:[8,11,13,31,42,51,66,68,75],rise:[10,34,66,69],rising_edg:10,risk:25,rmdir:24,rmt:[37,51],rmt_bytes_encoder_config_t:69,rmt_channel_handle_t:69,rmt_clk_src_default:69,rmt_clock_source_t:69,rmt_encod:69,rmt_encode_state_t:69,rmt_encoder_handle_t:69,rmt_encoder_t:69,rmt_encoding_complet:69,rmt_encoding_mem_ful:69,rmt_encoding_reset:69,rmt_symbol_word_t:69,rmtencod:[51,69],robust:[11,52],robustli:57,role:65,root:[24,31,74],root_list:24,root_menu:11,root_path:24,rotari:33,rotat:[8,15,16,19,22,33,34,35,51,58,69],round:54,routin:49,row:[14,75],row_index:14,row_t:75,rpm:[8,19,22],rpm_to_rad:8,rstp:65,rt_fmt_str:52,rtc:[37,70],rtcp:72,rtcp_packet:72,rtcp_port:72,rtcppacket:72,rtd:65,rtp:[34,72],rtp_jpeg_packet:72,rtp_packet:72,rtp_port:72,rtpjpegpacket:72,rtppacket:72,rtsp:[37,65],rtsp_client:72,rtsp_path:72,rtsp_port:72,rtsp_server:72,rtsp_session:72,rtspclient:72,rtspserver:72,rtspsession:72,rule:75,run:[3,8,11,15,19,22,23,31,33,43,50,52,59,75,78],runtim:52,s2:[3,16],s3:[3,13,45],s:[2,6,8,9,10,11,12,14,19,22,23,31,33,46,48,49,50,51,52,57,59,63,68,69,73,74,75,76,77],s_isdir:24,safe:[50,67],same:[2,5,6,8,23,65,67,78],sampl:[1,2,3,6,8,11,19,22,25,26,28,29,66,67,77],sample_mv:[1,13],sample_r:1,sample_rate_hz:[3,77],sandbox:24,sar:[2,6],sarch:[19,22],satisfi:74,satur:[12,67],sbu:[],scalar:58,scale:[8,55,58,67,77],scaler:55,scan:[2,6,72,81],scan_data:72,scenario:[80,81],schedul:78,scheme:8,scl:[2,6,36],scl_io_num:[1,2,6,13,19,22,34,36,39,40,43,45,46,48,66,68,70],scl_pullup_en:[1,2,6,13,19,22,34,36,39,45,46,48,66,70],sclk:16,sclk_io_num:16,scope:76,scottbez1:33,screen:[11,16],sda:36,sda_io_num:[1,2,6,13,19,22,34,36,39,40,43,45,46,48,66,68,70],sda_pullup_en:[1,2,6,13,19,22,34,36,39,45,46,48,66,70],sdp:72,search:[19,22],second:[1,2,3,8,19,22,26,27,37,46,48,50,52,58,70,72,76,77,78],secondari:15,seconds_per_minut:[19,22],seconds_since_start:59,section:[12,26,27,37],sectionimpl:29,secur:[65,80,81],security_manager_flag:65,security_manager_tk:65,see:[2,6,8,11,12,14,15,16,18,25,26,29,34,49,53,59,61,62,63,65,66,69,74,75,77,80,81],seek_end:24,seek_set:24,seekg:24,seem:[11,24,72],segment:15,sel:2,select:[2,3,13,31,34,51,65,68,74],select_bit_mask:2,select_librari:34,select_press:2,select_valu:2,self:45,send:[10,15,16,31,36,51,62,63,66,69,72],send_bright:51,send_command:16,send_config:[62,63],send_data:16,send_fram:72,send_request:72,send_rtcp_packet:72,send_rtp_packet:72,sendconfig:63,sender:[61,62,63],sender_info:[61,62,63],sendto:61,sens:[8,45],sensor:[8,19,22,45,77],sensor_direct:8,sensorconcept:8,sensordirect:8,sent:[2,6,16,31,51,62,63,69,72],sentenc:75,separ:[13,14,15,46,59],septemb:75,sequenc:[2,6,23,34,59,65,66,74],seri:[29,72,77],serial:[10,21,23,34,37,43,46,47,48,65,66,72],serializa:73,series_second_order_sect:[25,29],serizalizt:14,server:[32,37,60,61],server_address:[62,63,72],server_config:63,server_port:72,server_socket:[62,63],server_task:62,server_task_config:[62,63],server_task_fn:62,server_uri:72,servic:[2,65],session:[11,31,69,72],session_st:69,set:[1,2,6,7,8,10,11,15,16,19,22,23,34,40,43,45,46,48,49,50,51,54,55,57,59,61,62,63,65,66,68,69,70,72,74,77,78,80,81],set_al:51,set_analog_alert:2,set_ap_mac:81,set_bright:15,set_calibr:49,set_config:67,set_dat:70,set_date_tim:70,set_deadzon:49,set_digital_alert:2,set_digital_output_mod:[2,6],set_digital_output_valu:[2,6],set_direct:[46,48],set_drawing_area:16,set_duti:50,set_encod:[51,69],set_fade_with_tim:50,set_handle_res:11,set_histori:11,set_history_s:11,set_id:[65,66],set_input_polar:48,set_interrupt:46,set_interrupt_mirror:48,set_interrupt_on_chang:48,set_interrupt_on_valu:48,set_interrupt_polar:48,set_label:16,set_log_callback:74,set_log_level:23,set_met:16,set_mod:34,set_motion_control_typ:8,set_offset:16,set_payload:72,set_phase_st:7,set_phase_voltag:8,set_pin:[46,48],set_pixel:51,set_pull_up:48,set_pwm:7,set_receive_timeout:[61,62,63],set_record:66,set_session_log_level:72,set_tag:52,set_text:75,set_tim:70,set_verbos:52,set_vers:72,set_voltag:7,set_waveform:34,setactivechild:74,setcolor:11,setdeephistori:74,sethandleres:11,setinputhistori:11,setinputhistorys:11,setnocolor:11,setparentst:74,setpoint:[8,33],setshallowhistori:74,setter:[58,72],setup:[2,72],sever:[21,27,47],sftp:65,sgn:54,shaft:[8,19,22],shallow:74,shallow_history_st:74,shallowhistoryst:74,shamelessli:75,shape:55,share:65,shared_ptr:8,sharp_click:34,sheet:[2,6],shield:13,shift:[51,55,68],shift_bi:51,shift_left:51,shift_right:51,shifter:55,shop:[46,69],short_local_nam:65,shorten:65,shot:78,should:[7,8,11,12,13,15,16,24,25,28,43,48,49,50,51,58,61,62,63,65,67,68,69,72,74,76,78],shouldn:[24,52],show:[11,51,74,76],showcas:23,shown:52,shut:76,side:[7,32],sign:[18,54,57],signal:[2,13,15,25,26,28,29,34,51,67,69],signatur:[43,45,76],signific:68,similar:69,simpl:[0,5,10,23,24,30,31,36,43,52,65,67,73,76,77],simple_callback_fn:76,simpleconfig:76,simplefoc:8,simpler:[50,69],simpli:[2,3,6,11,19],simplifi:72,simultan:[11,65],sin:59,sinc:[2,8,18,19,22,23,24,43,46,68,69,72,76,77],sine_pwm:[],singl:[2,5,6,18,33,38,51,52],single_unit_1:[3,77],single_unit_2:3,singleton:[23,24],sinusoid:8,sip:65,sixteen:1,size:[10,11,15,23,24,34,43,59,62,63,65,66,69,70,72,73,76,77,78],size_t:[1,2,3,6,8,10,11,13,14,15,16,18,19,22,23,24,25,26,28,29,34,36,39,40,43,45,46,48,50,51,52,59,61,62,63,68,69,70,72,73,75,76,78,81],sizeof:[1,2,6,13,16,19,22,34,46,48,66,69,72],sk6085:69,sk6805:69,sk6805_10mhz_bytes_encoder_config:69,sk6805_freq_hz:51,sk6812:51,sleep:[1,2,3,5,6,8,13,18,19,22,23,34,36,39,40,45,46,48,49,50,51,52,59,67,68,69,70,74,76,77,78],sleep_for:[3,10,16,23,43,50,51,52,59,62,63,67,72,74,76,78,81],sleep_until:76,slope:55,slot:34,slow:5,small:[33,55],smart:65,smartknob:33,smb:65,snap:33,snprintf:76,so:[1,2,5,6,8,11,13,14,16,18,19,22,23,24,27,31,33,34,37,45,46,48,51,57,59,66,67,69,72,74,75,76,77,78],so_recvtimeo:[61,62,63],so_reuseaddr:[61,62,63],so_reuseport:[61,62,63],sockaddr:61,sockaddr_in6:61,sockaddr_in:61,sockaddr_storag:[61,62,63],socket:[31,37,60,72],socket_fd:[61,62,63],soft_bump:34,soft_fuzz:34,softwar:[2,6,15,23],software_rotation_en:[15,16],some:[1,2,6,8,11,13,19,21,22,23,24,27,33,34,46,48,52,54,59,61,65,66,69,74,76],someth:[15,76],sometim:11,somewhat:33,sos_filt:29,sosfilt:[26,29],sourc:[63,69],source_address:61,sp:65,sp_hash_c192:65,sp_hash_c256:65,sp_hash_r256:65,sp_random_r192:65,space:[8,12,24,33,51,69,75],space_vector_pwm:8,sparignli:57,sparkfun:[13,68],spawn:[19,22,31,72,74,76],spawn_endevent_ev:74,spawn_event1_ev:74,spawn_event2_ev:74,spawn_event3_ev:74,spawn_event4_ev:74,specfici:1,special:[20,34,46,69],specif:[12,33,35,38,42,44,72,74,76],specifi:[2,6,19,22,24,33,52,63,72,78],speed:[8,19,22,36,50,62,75],speed_mod:50,spi2_host:16,spi:[16,19,22,48],spi_bus_add_devic:16,spi_bus_config_t:16,spi_bus_initi:16,spi_device_interface_config_t:16,spi_device_polling_transmit:[],spi_dma_ch_auto:16,spi_num:16,spi_queue_s:16,spi_transaction_t:[],spic:16,spics_io_num:16,spike:55,sporad:5,spot:8,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:58,sr:65,ssid:[65,66,80,81],st25dv04k:66,st25dv:[37,64],st25dv_read:66,st25dv_write:66,st7789_defin:16,st7789v_8h_sourc:16,st:[24,66],st_mode:24,st_size:24,sta:[37,79],stabl:65,stack:[10,23,59,76,78],stack_size_byt:[1,2,6,8,13,19,22,23,34,46,48,51,59,62,63,66,69,76,78],stackoverflow:[24,66,75],stand:8,standalon:[21,47],standard:[24,52,57,72],star:34,start:[1,2,3,5,6,8,10,11,13,15,16,18,19,22,23,31,33,34,36,39,40,43,45,46,48,49,50,51,52,58,59,60,62,63,66,67,68,69,70,72,74,76,77],start_fast_transfer_mod:66,start_fram:51,start_receiv:63,startup:[19,22],stat:[24,59],state:[7,10,13,19,22,23,25,26,28,29,34,37,39,40,44,45,46,48,59,65,66,67,68,69,70],state_a:7,state_b:7,state_bas:74,state_c:7,state_machin:74,state_of_charg:23,statebas:74,static_cast:[2,52,69],station:[37,79,80],statist:2,statistics_en:2,statu:[2,66],std:[1,2,3,5,6,8,10,11,13,14,15,16,18,19,22,23,29,31,33,34,36,39,40,43,44,45,46,48,49,50,51,52,53,57,58,59,60,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],stdby:8,stdin:74,stdin_out:11,stdout:74,steinhart:77,step:76,still:49,stop:[1,2,3,5,6,8,13,15,18,19,22,23,31,33,34,36,39,40,43,45,46,48,49,50,51,59,62,63,66,67,68,69,70,72,74,77,78,81],stop_fast_transfer_mod:66,storag:[11,61],store:[11,13,16,24,30,55,65,66,72,77],stori:75,str:14,strcutur:16,stream:[11,14,72],streamer:72,strength:33,strictli:73,string:[10,11,14,23,24,52,59,61,62,63,65,72,73,76,80,81],string_view:[10,16,24,31,52,62,63,65,66,72,74,76,78],strip:[37,69],strong:33,strong_buzz:34,strong_click:34,strongli:73,struct:[1,2,3,5,6,7,8,10,12,13,15,18,19,22,23,24,26,28,30,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,59,61,62,63,65,66,67,68,69,70,72,73,76,77,78,80,81],structur:[1,2,6,8,13,15,16,23,34,38,42,43,44,46,48,49,50,53,55,61,62,63,65,67,70,74,80,81],sub:[11,23],sub_menu:11,sub_sub_menu:11,subclass:[29,61,72,74],subdirectori:24,submenu:11,submodul:11,subscib:23,subscrib:[10,23],subscript:23,subsequ:[2,65],subset:13,substat:74,subsub:11,subsubmenu:11,subsystem:[3,5,15,50],subtract:58,subystem:81,succe:[39,68],success:[1,2,6,19,22,34,36,43,46,48,66,70,72],successfulli:[18,23,61,62,63,69,72,73],suffix:52,suggest:69,suit:12,sulli:75,super_mario_1:14,super_mario_3:14,super_mario_bros_1:14,super_mario_bros_3:14,suppli:[7,77],supply_mv:77,support:[2,6,8,11,12,13,18,20,24,34,39,45,46,51,60,65,66,72],sure:[8,72],swap:44,swap_xi:44,symlink:[2,6,34],symmetr:55,syst_address:66,system:[11,14,23,37,59,66,73,74,75,76,77],sytl:73,t5t:66,t:[1,2,3,5,6,8,13,14,16,18,19,22,23,24,34,36,37,39,40,41,45,46,48,49,50,51,52,53,55,57,58,59,62,63,65,66,67,68,69,70,74,76,77,78],t_0:77,t_keyboard:43,ta:13,tabl:[2,6,24,59,65,72,75,77],tabul:37,tag:[52,65,66],take:[5,24,75],taken:24,talk:[46,51],target:[8,81],task1:23,task2:23,task:[1,2,3,5,6,8,10,13,15,18,19,22,23,31,33,34,36,37,39,40,43,45,46,48,49,50,51,62,63,66,67,68,69,70,72,74,77,78],task_1_fn:23,task_2_fn:23,task_callback:59,task_config:63,task_fn:[3,5,13,18,19,22,34,36,39,40,45,46,48,49,51,59,66,67,68,69,70,74,76,77],task_id:59,task_iter:76,task_monitor:59,task_nam:[59,76],task_prior:3,task_stack_size_byt:[10,59],taskmonitor:59,tb:13,tcp:[37,60,72],tcp_socket:62,tcpclientsess:62,tcpobex:65,tcpserver:62,tcpsocket:[61,62,72],tcptransmitconfig:62,tdata:73,tdk:77,tdown:13,tear:[61,62,63,76],teardown:72,tel:65,tell:[51,69],tellg:24,telnet:65,temp:77,temperatur:77,temperature_celsiu:23,templat:[8,18,20,24,26,29,31,33,52,53,57,58,76],temporari:65,termin:[11,74,75,76],test2:24,test:[3,8],test_dir:24,test_fil:24,test_start:76,texa:[2,6,34],text:65,text_record:[],tflite:16,tft_driver:16,tft_espi:16,tftp:65,th:[15,30],than:[7,11,15,49,52,66,72],thank:11,thei:[11,13,33,72,74,76],them:[2,6,11,12,13,23,55,69,72,74,76],therefor:[3,5,11,12,19,22,34,57,76],thermistor:37,thermistor_ntcg_en:77,thi:[1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,22,23,24,25,31,33,34,36,37,39,40,43,45,46,48,49,50,51,52,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],thin:55,thing:59,think:11,third:73,this_thread:[3,10,16,23,43,50,51,52,59,62,63,67,72,74,76,78,81],those:[23,46,52,59,74],though:[23,76],thread:[23,31,33,50,59,62,63,67,72,76],threshold:[2,6],through:[2,6,8,33,34,51,57,69,74],throughput:3,ti:[2,6,34],tick:74,tickselect:74,time:[2,5,6,7,11,13,19,22,23,24,34,46,48,50,51,52,59,63,66,67,68,69,70,74,76,77,78,81],time_point:24,time_t:[24,31],time_to_l:[61,62,63],timeout:[36,61,62,63,76],timeout_m:36,timer:[37,50],timer_fn:78,tinys3:[8,69],tk:65,tkeyboard:43,tkip:65,tla2528:[4,37],tla:6,tla_read:6,tla_read_task_fn:6,tla_task:6,tla_writ:6,tleft:13,tloz_links_awaken:14,tloz_links_awakening_dx:14,tlv:[],tm:59,tmc6300:8,tname:73,tnf:65,to_str:75,to_time_t:[24,31],todo:[],togeth:[],toggl:43,toi:75,toler:77,tone:51,too:[11,72,75],top:74,topic:[10,23],torqu:8,torque_control:8,torquecontroltyp:8,total:[18,24],total_spac:24,touch:[37,41,44],touchpad:[37,41,45,65],touchpad_input:44,touchpad_read:44,touchpad_read_fn:44,touchpadinput:44,tp:[24,31],tpd_commercial_ntc:77,trace:59,track:67,transact:69,transaction_queue_depth:69,transceiv:37,transfer:[16,27,32,37,66],transfer_funct:30,transferfunct:[29,30],transform:[8,23,62,63],transit:74,transition_click_1:34,transition_hum_1:34,transmiss:[62,69],transmit:[23,51,61,62,63,65],transmit_config:62,transmitt:69,transport:72,trapezoid_120:[],trapezoid_150:[],tree:[63,69,74],tri:11,trigger:[2,5,6,33,34,48,66],tright:13,trim_polici:14,trim_whitespac:14,triple_click:34,truncat:11,ts:34,tselect:13,tstart:13,tt1535109:75,tt1979376:75,tt21100:[37,41],tt3263904:75,ttl:[61,62,63],tup:13,tupl:77,turn:[2,15,52,65],tvalu:73,two:[1,12,13,15,46,48,52,59,69],twothird:1,tx:65,tx_buffer:[],tx_power_level:65,type5tagtyp:[],type:[1,2,4,6,8,10,11,13,15,18,19,21,22,23,24,27,33,34,37,39,40,43,44,45,46,47,48,49,51,52,58,61,62,63,65,66,68,69,70,72,73,76,77,78,81],type_specif:72,typedef:[1,2,6,8,10,11,15,19,22,23,34,39,40,43,44,45,46,48,49,51,61,62,63,66,68,69,70,76,77,78,81],typenam:[24,31,52,53,57,58],typic:42,u:[58,65],ua:7,uart:11,uart_serial_plott:[2,6],ub:7,uc:7,ud:8,udp:[37,60,72],udp_multicast:63,udp_socket:63,udpserv:63,udpsocket:[61,63],uic:[65,66],uint16_t:[1,15,16,31,39,40,44,45,46,48,65,66,69,70],uint32_t:[2,13,15,16,36,50,65,72,73],uint64_t:[65,66],uint8_t:[1,2,6,10,13,15,16,19,22,23,34,36,39,40,43,44,45,46,48,51,52,61,62,63,65,66,68,69,70,72,73,80,81],uint:69,uk:65,unabl:[31,68,70],unbound:33,unbounded_no_det:33,uncalibr:[13,49],uncent:57,unchang:65,under:[18,24],underflow:18,underlin:75,understand:65,unicast:63,unicod:[],uniqu:[62,72,76],unique_lock:[1,2,3,5,6,8,13,18,19,22,23,34,36,39,40,45,46,48,49,50,51,62,66,67,68,69,70,74,76,77],unique_ptr:[59,62,72,76],unit:[0,3,5,8,13,18,24,25,49,58,77],univers:11,universal_const:75,unknown:[8,65,81],unless:23,unlimit:11,unlink:24,unmap:49,unord:[2,6,63],unordered_map:[2,6,72],unregist:[38,42,44],unreli:63,until:[2,6,11,23,24,33,34,50,51,62,63,69,74,76,78],unus:[13,18,33],unweight:53,unwind:74,up:[2,3,11,13,15,18,24,34,39,42,43,45,46,48,55,62,66,67,68,72,74,76,78],upat:15,updat:[7,8,10,13,15,19,22,25,26,28,29,33,40,45,46,48,49,50,52,55,57,58,61,66,67,68,74],update_address:68,update_detent_config:33,update_period:[8,15,19,22],upper:[16,77],uq:8,uri:[65,72],uri_record:[],urn:65,urn_epc:65,urn_epc_id:65,urn_epc_pat:65,urn_epc_raw:65,urn_epc_tag:65,urn_nfc:65,us:[1,2,3,5,6,7,8,9,10,11,12,13,15,16,18,19,20,22,23,24,25,26,31,32,33,34,35,39,40,42,43,45,46,48,49,50,51,52,53,55,57,59,60,61,62,63,65,66,68,69,70,72,73,74,75,76,77,78],usag:[11,14,75],used_spac:24,user:[2,3,5,6,9,10,11,16,18,19,22,31,33,34,46,48,68,69,70,72,76],usernam:31,ust:23,util:[24,49,52,54,58,59,61,65,66],uuid:65,uuids_128_bit_complet:65,uuids_128_bit_parti:65,uuids_16_bit_complet:65,uuids_16_bit_parti:65,uuids_32_bit_complet:65,uuids_32_bit_parti:65,v:[8,12,57,58],v_in:77,vacuum:75,val_mask:48,valid:[31,34,51,61,62,63,72],valu:[1,2,3,5,6,10,12,13,14,15,18,19,22,24,28,33,34,39,40,46,48,49,50,51,52,53,54,55,57,58,65,66,67,68,69,70,72,73,75,76,77],vari:33,variabl:[16,49,52,76],varieti:[2,6],variou:51,ve:[11,24,76],vector2d:[37,53,56],vector2f:[49,68,70],vector:[2,3,5,6,8,10,13,14,23,24,28,49,50,51,58,59,61,62,63,65,66,72,73,76,77],veloc:[8,19,22],velocity_filt:[8,19,22],velocity_filter_fn:[19,22],velocity_limit:8,velocity_openloop:8,velocity_pid_config:8,veloicti:8,veolciti:[19,22],verbos:[1,2,3,5,6,7,8,10,13,15,18,19,22,23,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,62,63,66,67,68,69,70,72,74,76,77,78,80,81],veri:11,version:[6,11,58,65,72],via:[6,24,34,46,48],vibe:34,vibrat:[33,34],video:[15,72],view:[62,63,65],vio:8,virtual:[13,74],visual:59,volt:[2,6,7],voltag:[1,2,3,5,6,7,8,9,23,77],voltage_limit:7,vram0:15,vram1:15,vram:15,vram_size_byt:15,vram_size_px:15,vtaskgetinfo:59,w:[24,34,52,57],wa:[1,2,3,5,6,7,10,11,13,16,18,19,22,23,31,34,39,43,45,48,49,61,62,63,66,68,69,70,72,74,76],wai:[1,2,3,5,6,8,11,13,14,18,19,22,24,33,34,36,39,40,45,46,48,49,51,65,67,68,69,70,73,74,75,76,77],wait:[23,33,43,62,63,76],wait_for:[1,3,5,13,18,19,22,23,34,36,39,40,45,46,48,49,50,51,62,66,67,68,69,70,74,76],wait_for_respons:[62,63],wait_tim:50,wait_until:[2,6,8,76,77],want:[1,2,3,5,6,8,11,13,15,18,19,22,23,33,34,46,48,49,50,51,59,62,63,66,67,69,74,76,77,78],warn:[1,2,3,5,6,7,8,10,13,15,18,19,22,23,24,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,62,63,66,67,68,69,70,72,76,77,78,80,81],warn_rate_limit:52,watch:65,water:59,wave:55,waveform:34,we:[1,2,6,7,8,11,13,19,22,23,24,33,34,39,40,43,45,46,48,50,51,61,62,63,66,68,69,70,74,76,77,78],weak:33,webgm:74,week:70,weekdai:70,weight:53,weightedconfig:53,welcom:52,well:[2,13,21,23,27,29,34,55,59,62,65,66,72,74,76],well_known:65,wep:65,were:[2,6,7,11,45,49,61,62,63,67,74,76],what:[5,6,7,23,69,74],whatev:[46,48],whe:81,when:[1,2,3,5,6,8,11,13,16,18,19,20,22,23,33,34,36,39,40,43,45,46,48,49,51,57,61,62,63,66,67,68,69,70,72,73,74,76,77,78,81],whenev:74,where:[9,18,33,59,63,74,77],whether:[3,10,11,13,15,19,22,24,43,50,51,57,61,62,63,69,72,76,81],which:[1,2,3,5,6,8,9,10,11,12,13,14,15,19,22,23,24,25,26,27,28,33,34,35,38,39,40,42,43,46,47,48,50,51,52,53,54,57,58,59,62,63,65,66,68,69,72,74,75,76,77,80,81],white:75,who:16,whole:[72,74],wi:[80,81],width:[11,15,16,33,72,75],wifi:[37,65],wifi_ap:80,wifi_record:[],wifi_sta:81,wifiap:80,wifiauthenticationtyp:65,wificonfig:65,wifiencryptiontyp:65,wifista:81,wiki:[25,26,29,61,62,63,77],wikipedia:[18,25,26,29,61,62,63,77],wind:67,window_size_byt:[3,77],windup:67,wire:69,wireless:66,wish:[11,13],witdth:18,within:[12,19,21,22,23,33,52,57,63,75,76,77],without:[2,3,11,33,59,66,69,72],word:75,work:[6,8,10,11,24,33,59,72,76],world:11,worri:77,would:[18,23,74,76],wpa2:65,wpa2_enterpris:65,wpa2_person:65,wpa:65,wpa_enterpris:65,wpa_person:65,wpa_wpa2_person:65,wrap:[7,18,23,46,69,75],wrapper:[3,5,10,11,14,15,24,36,38,42,44,49,50,52,53,55,69,73,74,75],write:[1,2,6,8,11,13,15,16,19,22,24,28,34,36,39,40,43,46,48,51,66,68,70],write_data:[36,40],write_fn:[1,2,6,19,22,34,39,40,43,46,48,51,66,68,70],write_len:40,write_read:[36,40,68],write_read_fn:[40,68],write_row:14,write_s:36,written:[51,65,66,74],wrote:[14,24],ws2811:51,ws2812:51,ws2812_10mhz_bytes_encoder_config:69,ws2812_bytes_encoder_config:[],ws2812_freq_hz:69,ws2812b:69,ws2813:51,www:[2,6,25,29,34,65,66],x1:58,x2:58,x:[2,6,11,13,16,25,39,40,44,45,46,48,49,58,59,66,72],x_calibr:[13,49],x_channel:6,x_mv:[1,2,6,13,49],xe:16,xml:[31,68,70],xml_in:[31,68,70],xqueuecreat:2,xqueuerec:2,xs:16,y1:58,y2:58,y:[2,6,13,16,25,39,40,44,45,49,52,55,58,72,80,81],y_calibr:[13,49],y_channel:6,y_mv:[1,2,6,13,49],ye:[16,81],year:70,yellow:[14,52,75],yet:[8,19,22,32,76],yield:69,you:[3,6,8,11,13,14,15,18,23,24,43,50,51,52,55,57,59,66,67,69,72,73,74,75,76,80,81],your:[23,52,59,75],yourself:74,ys:16,z:18,zelda1:14,zelda2:14,zelda:14,zelda_2:14,zero:[8,18,51,57,66,77],zero_electric_offset:8,zoom_in:39,zoom_out:39},titles:["ADC Types","ADS1x15 I2C ADC","ADS7138 I2C ADC","Continuous ADC","ADC APIs","Oneshot ADC","TLA2528 I2C 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","I2C","ESPP Documentation","Encoder Input","FT5x06 Touch Controller","GT911 Touch Controller","Input APIs","Keypad Input","LilyGo T-Keyboard","Touchpad Input","TT21100 Touch Controller","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","QwiicNES","Remote Control Transceiver (RMT)","BM8563","RTC APIs","RTSP APIs","Serialization APIs","State Machine APIs","Tabulate APIs","Task APIs","Thermistor APIs","Timer APIs","WiFi APIs","WiFi Access Point (AP)","WiFi Station (STA)"],titleterms:{"1":[33,51,69,78],"2":33,"class":[1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,22,23,24,25,26,28,29,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],"function":[30,31,68,70],"long":76,Then:78,abi:18,abiencod:18,access:80,adc:[0,1,2,3,4,5,6,49,77],ads1x15:1,ads7138:2,again:78,alpaca:73,analog:13,ap:80,apa102:51,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,35,36,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,69,70,71,72,73,74,75,76,77,78,79,80,81],as5600:19,aw9523:46,basic:[33,52,59,67,76],bench:74,bezier:53,biquad:25,bldc:[7,8,9,33],bm8563:70,bound:[],box:16,breath:50,butterworth:26,button:10,buzz:33,cancel:78,cli:11,click:33,client:[62,63,72],color:12,command:11,complex:[14,67,73,74,75],config:16,continu:3,control:[13,39,40,45,69],csv:14,data:69,de:73,delai:78,detent:[],devic:74,digit:13,displai:[15,16,17],document:37,driver:[7,16,34],drv2605:34,encod:[18,19,20,21,22,38,69],esp32:16,espp:37,event:23,exampl:[1,2,3,5,6,8,10,11,13,14,16,18,19,22,23,24,33,34,36,39,40,43,45,46,48,49,50,51,52,59,62,63,66,67,68,69,70,72,73,74,75,76,77,78,80,81],expand:[46,47,48],fast:54,file:[0,1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,20,22,23,24,25,26,28,29,30,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,54,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],filesystem:24,filter:[25,26,27,28,29],format:52,ft5x06:39,ftp:[31,32],gaussian:55,gener:74,get_latest_info:59,gt911:40,haptic:[33,34,35],header:[0,1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,20,22,23,24,25,26,28,29,30,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,54,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],hfsm:74,i2c:[1,2,6,13,36],i:[46,48],ili9341:16,info:[24,76],input:[38,41,42,44],interfac:11,io:47,itself:78,joystick:49,keyboard:43,keypad:42,kit:16,led:[50,51],lilygo:43,line:11,linear:[18,50],log:52,logger:52,lowpass:28,machin:74,macro:[11,14,73,74,75],magnet:[19,22],manag:23,mani:76,mapper:57,markdown:75,math:[54,56],mcp23x17:48,monitor:59,motor:[8,34],mt6701:22,multicast:63,ndef:65,network:60,newlib:24,nfc:64,o:[46,48],oneshot:[5,11,78],order:29,pid:67,plai:33,point:80,posix:24,qwiicn:68,rang:57,reader:14,real:74,refer:[0,1,2,3,5,6,7,8,10,11,12,13,14,15,16,18,19,20,22,23,24,25,26,28,29,30,31,33,34,36,38,39,40,42,43,44,45,46,48,49,50,51,52,53,54,55,57,58,59,61,62,63,65,66,67,68,69,70,72,73,74,75,76,77,78,80,81],remot:69,request:76,respons:[62,63],rmt:69,rotat:18,rtc:71,rtsp:72,run:[74,76],s3:16,second:29,section:29,serial:73,server:[31,62,63,72],so:29,socket:[61,62,63],spi:51,st25dv:66,st7789:16,sta:81,start:78,state:74,station:81,std:24,stop:76,strip:51,structur:73,system:24,t:43,tabul:75,task:[59,76],tcp:62,test:74,thermistor:77,thread:52,timer:78,tla2528:6,touch:[39,40,45],touchpad:44,transceiv:69,transfer:30,transmit:69,tt21100:45,ttgo:16,type:[0,20],udp:63,union:[65,68],usag:[8,33],valid:77,vector2d:58,verbos:52,via:51,wifi:[79,80,81],writer:14,wrover:16,ws2812:69}}) \ No newline at end of file diff --git a/docs/serialization.html b/docs/serialization.html index 3fa703606..081b2fdde 100644 --- a/docs/serialization.html +++ b/docs/serialization.html @@ -140,7 +140,7 @@
  • »
  • Serialization APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -168,7 +168,7 @@

    API Reference

    Header File

    diff --git a/docs/state_machine.html b/docs/state_machine.html index d4f0191d9..1c977cef4 100644 --- a/docs/state_machine.html +++ b/docs/state_machine.html @@ -144,7 +144,7 @@
  • »
  • State Machine APIs
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -186,7 +186,7 @@

    Classesstate_machine.hpp provides access to all the base classes that the generated code relies on as well as what you would need to subclass yourself for a manually written hfsm. Please see https://github.com/finger563/webgme-hfsm for more information about modeling, generating, and developing HFSMs.

    State Machine / HFSM Example with the generated Complex example hfsm

    -

    @@ -421,7 +421,7 @@

    Classes
    -inline void makeActive(void)
    +inline virtual void makeActive(void)

    Make this state the active substate of its parent and then recurse up through the tree to the root.

    Should only be called on leaf nodes!

    @@ -463,7 +463,7 @@

    Classes

    Header File

    @@ -471,12 +471,12 @@

    Classes
    class espp::state_machine::ShallowHistoryState : public espp::state_machine::StateBase
    -

    Shallow History Pseudostates exist purely to re-implement the makeActive() function to actually call _parentState->setShallowHistory()

    +

    Shallow History Pseudostates exist purely to re-implement the makeActive() function to actually call _parentState->setShallowHistory()

    Public Functions

    -inline void makeActive()
    +inline virtual void makeActive() override

    Calls _parentState->setShallowHistory().

    @@ -594,7 +594,7 @@

    Classes

    Header File

    @@ -602,12 +602,12 @@

    Classes
    class espp::state_machine::DeepHistoryState : public espp::state_machine::StateBase
    -

    Deep History Pseudostates exist purely to re-implement the makeActive() function to actually call _parentState->setDeepHistory()

    +

    Deep History Pseudostates exist purely to re-implement the makeActive() function to actually call _parentState->setDeepHistory()

    Public Functions

    -inline void makeActive()
    +inline virtual void makeActive() override

    Calls _parentState->setDeepHistory()

    diff --git a/docs/tabulate.html b/docs/tabulate.html index 58d2d9684..59a334f8c 100644 --- a/docs/tabulate.html +++ b/docs/tabulate.html @@ -138,7 +138,7 @@
  • »
  • Tabulate APIs
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    diff --git a/docs/task.html b/docs/task.html index 8fb6e0375..1f768d20c 100644 --- a/docs/task.html +++ b/docs/task.html @@ -138,7 +138,7 @@
  • »
  • Task APIs
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -423,8 +423,8 @@

    Task Request Stop Example -
    -inline bool is_started()
    +
    +inline bool is_started() const

    Has the task been started or not?

    Returns
    @@ -434,8 +434,8 @@

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

    Is the task running?

    Returns
    diff --git a/docs/thermistor.html b/docs/thermistor.html index dc371e8dd..f48e97854 100644 --- a/docs/thermistor.html +++ b/docs/thermistor.html @@ -138,7 +138,7 @@
  • »
  • Thermistor APIs
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    diff --git a/docs/timer.html b/docs/timer.html index afdab9f38..d4e8bbd21 100644 --- a/docs/timer.html +++ b/docs/timer.html @@ -138,7 +138,7 @@
  • »
  • Timer APIs
  • - Edit on GitHub + Edit on GitHub

  • @@ -163,7 +163,7 @@

    API Reference

    Header File

    diff --git a/docs/wifi/index.html b/docs/wifi/index.html index ec9688613..24454be85 100644 --- a/docs/wifi/index.html +++ b/docs/wifi/index.html @@ -134,7 +134,7 @@
  • »
  • WiFi APIs
  • - Edit on GitHub + Edit on GitHub

  • diff --git a/docs/wifi/wifi_ap.html b/docs/wifi/wifi_ap.html index f380ff8d0..156f88bea 100644 --- a/docs/wifi/wifi_ap.html +++ b/docs/wifi/wifi_ap.html @@ -141,7 +141,7 @@
  • WiFi APIs »
  • WiFi Access Point (AP)
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -183,7 +183,7 @@

    WiFi Access Point ExamplePublic Functions

    -inline WifiAp(const Config &config)
    +inline explicit WifiAp(const Config &config)

    Initialize the WiFi Access Point (AP)

    Parameters
    diff --git a/docs/wifi/wifi_sta.html b/docs/wifi/wifi_sta.html index 9ebea2d78..5c2fcba73 100644 --- a/docs/wifi/wifi_sta.html +++ b/docs/wifi/wifi_sta.html @@ -142,7 +142,7 @@
  • WiFi APIs »
  • WiFi Station (STA)
  • - Edit on GitHub + Edit on GitHub

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

    API Reference

    Header File

    @@ -221,7 +221,7 @@

    WiFi Station ExamplePublic Functions

    -inline WifiSta(const Config &config)
    +inline explicit WifiSta(const Config &config)

    Initialize the WiFi Station (STA)

    Parameters
    @@ -237,8 +237,8 @@

    WiFi Station Example -
    -inline bool is_connected()
    +
    +inline bool is_connected() const

    Whether the station is connected to an access point.

    Returns
    diff --git a/suppressions.txt b/suppressions.txt new file mode 100644 index 000000000..563d866cf --- /dev/null +++ b/suppressions.txt @@ -0,0 +1,11 @@ +// category of errors to suppress, e.g. unusedFunction +missingInclude +missingIncludeSystem +unusedFunction +unusedStructMember +functionStatic +cstyleCast + +// Specific suppressions of the form: +// [error id]:[filename]:[line] +*:lib/*