diff --git a/.gitignore b/.gitignore index b2a6323..2b2b912 100644 --- a/.gitignore +++ b/.gitignore @@ -1,12 +1,3 @@ -.vs -.vscode -.vscode/* -!.vscode/settings.json -!.vscode/tasks.json -!.vscode/launch.json -!.vscode/extensions.json -!.vscode/*.code-snippets - # Local History for Visual Studio Code .history/ diff --git a/.vscode/arduino.json b/.vscode/arduino.json new file mode 100644 index 0000000..b6596e1 --- /dev/null +++ b/.vscode/arduino.json @@ -0,0 +1,7 @@ +{ + "configuration": "JTAGAdapter=default,PSRAM=disabled,PartitionScheme=default,CPUFreq=240,FlashMode=qio,FlashFreq=80,FlashSize=4M,UploadSpeed=921600,LoopCore=1,EventsCore=1,DebugLevel=none,EraseFlash=all,ZigbeeMode=default", + "board": "esp32:esp32:esp32", + "sketch": "examples/dshot300/dshot300.ino", + "output": "build", + "port": "/dev/ttyUSB0" +} \ No newline at end of file diff --git a/.vscode/c_cpp_properties.json b/.vscode/c_cpp_properties.json new file mode 100644 index 0000000..8add28d --- /dev/null +++ b/.vscode/c_cpp_properties.json @@ -0,0 +1,899 @@ +{ + "version": 4, + "configurations": [ + { + "name": "ESP32", + "compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++", + "compilerArgs": [ + "-MMD", + "-w", + "-Werror=return-type", + "-iprefix" + ], + "intelliSenseMode": "linux-gcc-x64", + "includePath": [ + "~/.arduino15/packages/esp32/hardware/esp32/3.3.0/cores/esp32/**", + "~/.arduino15/packages/esp32/hardware/esp32/3.3.0/variants/esp32/**", + "~/.arduino15/packages/esp32/hardware/esp32/3.3.0/libraries/**", + "~/.arduino15/packages/esp32/hardware/esp32/3.3.0/**", + "~/.arduino15/packages/esp32/tools/**", + "~/.arduino15/packages/esp32/tools/esp-x32/2411/xtensa-esp-elf/include/c++/14.2.0/**", + "~/.arduino15/packages/esp32/tools/esp-x32/2411/xtensa-esp-elf/include/c++/14.2.0/xtensa-esp-elf/esp32/**", + "~/.arduino15/packages/esp32/tools/esp-x32/2411/xtensa-esp-elf/include/c++/14.2.0/backward/**", + "~/.arduino15/packages/esp32/tools/esp-x32/2411/lib/gcc/xtensa-esp-elf/14.2.0/include/**", + "~/.arduino15/packages/esp32/tools/esp-x32/2411/lib/gcc/xtensa-esp-elf/14.2.0/include-fixed/**", + "~/.arduino15/packages/esp32/tools/esp-x32/2411/xtensa-esp-elf/include/**", + "~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.5-b66b5448-v1/esp32/include/**", + "~/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.5-b66b5448-v1/esp32/include/freertos/FreeRTOS-Kernel/portable/xtensa/include/freertos/", + "~/Arduino/libraries/**", + "${workspaceFolder}/**" + ], + "forcedInclude": [ + "~/.arduino15/packages/esp32/hardware/esp32/3.3.0/cores/esp32/Arduino.h" + ], + "cStandard": "c17", + "cppStandard": "c++20", + "defines": [ + "F_CPU=240000000L", + "ESP32", + "ARDUINO=10607", + "ARDUINO_ESP32_DEV", + "ARDUINO_ARCH_ESP32", + "ARDUINO_BOARD=\"ESP32_DEV\"", + "ARDUINO_VARIANT=\"esp32\"", + "ARDUINO_PARTITION_default", + "ARDUINO_HOST_OS=\"linux\"", + "ARDUINO_FQBN=\"esp32:esp32:esp32:JTAGAdapter=default,PSRAM=disabled,PartitionScheme=default,CPUFreq=240,FlashMode=qio,FlashFreq=80,FlashSize=4M,UploadSpeed=921600,LoopCore=1,EventsCore=1,DebugLevel=none,EraseFlash=none,ZigbeeMode=default\"", + "ESP32=ESP32", + "CORE_DEBUG_LEVEL=0", + "ARDUINO_RUNNING_CORE=1", + "ARDUINO_EVENT_RUNNING_CORE=1", + "ARDUINO_USB_CDC_ON_BOOT=0", + "__DBL_MIN_EXP__=(-1021)", + "__XCHAL_HAVE_FP=1", + "__cpp_nontype_template_parameter_auto=201606L", + "__UINT_LEAST16_MAX__=0xffff", + "__ATOMIC_ACQUIRE=2", + "__FLT_MIN__=1.1754943508222875e-38F", + "__GCC_IEC_559_COMPLEX=0", + "__XCHAL_HAVE_PREDICTED_BRANCHES=0", + "__cpp_aggregate_nsdmi=201304L", + "__UINT_LEAST8_TYPE__=unsigned char", + "__INTMAX_C(c)=c ## LL", + "__XCHAL_HAVE_ADDX=1", + "__CHAR_BIT__=8", + "__XCHAL_DCACHE_LINESIZE=16", + "__XTENSA_MARCH_EARLIEST=260003", + "__XCHAL_DCACHE_LINEWIDTH=4", + "__UINT8_MAX__=0xff", + "__WINT_MAX__=0xffffffffU", + "__FLT32_MIN_EXP__=(-125)", + "__cpp_static_assert=201411L", + "__ORDER_LITTLE_ENDIAN__=1234", + "__SIZE_MAX__=0xffffffffU", + "__WCHAR_MAX__=0xffff", + "__GCC_HAVE_SYNC_COMPARE_AND_SWAP_1=1", + "__GCC_HAVE_SYNC_COMPARE_AND_SWAP_2=1", + "__GCC_HAVE_SYNC_COMPARE_AND_SWAP_4=1", + "__DBL_DENORM_MIN__=double(4.9406564584124654e-324L)", + "__GCC_ATOMIC_CHAR_LOCK_FREE=2", + "__GCC_IEC_559=0", + "__FLT32X_DECIMAL_DIG__=17", + "__FLT_EVAL_METHOD__=0", + "__cpp_binary_literals=201304L", + "__FLT64_DECIMAL_DIG__=17", + "__cpp_noexcept_function_type=201510L", + "__GCC_ATOMIC_CHAR32_T_LOCK_FREE=2", + "__cpp_variadic_templates=200704L", + "__UINT_FAST64_MAX__=0xffffffffffffffffULL", + "__SIG_ATOMIC_TYPE__=int", + "__DBL_MIN_10_EXP__=(-307)", + "__FINITE_MATH_ONLY__=0", + "__cpp_variable_templates=201304L", + "__XCHAL_HAVE_L32R=1", + "__FLT32X_MAX_EXP__=1024", + "__GNUC_PATCHLEVEL__=0", + "__FLT32_HAS_DENORM__=1", + "__UINT_FAST8_MAX__=0xffffffffU", + "__cpp_rvalue_reference=200610L", + "__XCHAL_HAVE_LOOPS=1", + "__cpp_nested_namespace_definitions=201411L", + "__XCHAL_DEBUGLEVEL=6", + "__INT8_C(c)=c", + "__XCHAL_HAVE_DFP_RECIP=0", + "__INT_LEAST8_WIDTH__=8", + "__cpp_variadic_using=201611L", + "__UINT_LEAST64_MAX__=0xffffffffffffffffULL", + "__INT_LEAST8_MAX__=0x7f", + "__cpp_attributes=200809L", + "__cpp_capture_star_this=201603L", + "__SHRT_MAX__=0x7fff", + "__LDBL_MAX__=1.7976931348623157e+308L", + "__cpp_if_constexpr=201606L", + "__XCHAL_ICACHE_LINESIZE=16", + "__LDBL_IS_IEC_60559__=1", + "__UINT_LEAST8_MAX__=0xff", + "__GCC_ATOMIC_BOOL_LOCK_FREE=2", + "__UINTMAX_TYPE__=long long unsigned int", + "__cpp_nsdmi=200809L", + "__FLT_EVAL_METHOD_TS_18661_3__=0", + "__UINT32_MAX__=0xffffffffUL", + "__GXX_EXPERIMENTAL_CXX0X__=1", + "__LDBL_MAX_EXP__=1024", + "__WINT_MIN__=0U", + "__FLT32X_IS_IEC_60559__=1", + "__XCHAL_HAVE_THREADPTR=1", + "__INT_LEAST16_WIDTH__=16", + "__SCHAR_MAX__=0x7f", + "__WCHAR_MIN__=0", + "__XCHAL_ICACHE_LINEWIDTH=4", + "__INT64_C(c)=c ## LL", + "__GCC_ATOMIC_POINTER_LOCK_FREE=2", + "__ATOMIC_SEQ_CST=5", + "__SIZEOF_INT__=4", + "__FLT32X_MANT_DIG__=53", + "__GCC_ATOMIC_CHAR16_T_LOCK_FREE=2", + "__cpp_aligned_new=201606L", + "__XCHAL_HAVE_FP_RECIP=1", + "__FLT32_MAX_10_EXP__=38", + "__STDC_HOSTED__=1", + "__XCHAL_HAVE_MUL32=1", + "__XTENSA_EL__=1", + "__cpp_decltype_auto=201304L", + "__DBL_DIG__=15", + "__XCHAL_HAVE_MUL16=1", + "__FLT_EPSILON__=1.1920928955078125e-7F", + "__GXX_WEAK__=1", + "__SHRT_WIDTH__=16", + "__FLT32_IS_IEC_60559__=1", + "__LDBL_MIN__=2.2250738585072014e-308L", + "__DBL_IS_IEC_60559__=1", + "__cpp_threadsafe_static_init=200806L", + "__cpp_enumerator_attributes=201411L", + "__XCHAL_HAVE_MMU=0", + "__FLT32X_HAS_INFINITY__=1", + "__INT32_MAX__=0x7fffffffL", + "__XCHAL_HAVE_DIV32=1", + "__INT_WIDTH__=32", + "__XTENSA_MARCH_LATEST=260003", + "__DECIMAL_DIG__=17", + "__FLT64_EPSILON__=2.2204460492503131e-16F64", + "__INT16_MAX__=0x7fff", + "__FLT64_MIN_EXP__=(-1021)", + "__XCHAL_DCACHE_SIZE=0", + "__LDBL_HAS_QUIET_NAN__=1", + "__cpp_return_type_deduction=201304L", + "__XCHAL_HAVE_BOOLEANS=1", + "__FLT64_MANT_DIG__=53", + "__XTHAL_ABI_WINDOWED=0", + "__GNUC__=14", + "__GXX_RTTI=1", + "__FLT_HAS_DENORM__=1", + "__SIZEOF_LONG_DOUBLE__=8", + "__XCHAL_HAVE_CONST16=0", + "__BIGGEST_ALIGNMENT__=16", + "__STDC_UTF_16__=1", + "__FLT64_MAX_10_EXP__=308", + "__cpp_delegating_constructors=200604L", + "__DBL_MAX__=double(1.7976931348623157e+308L)", + "__cpp_raw_strings=200710L", + "__INT_FAST32_MAX__=0x7fffffff", + "__DBL_HAS_INFINITY__=1", + "__cpp_deduction_guides=201703L", + "__HAVE_SPECULATION_SAFE_VALUE=1", + "__cpp_fold_expressions=201603L", + "__INTPTR_WIDTH__=32", + "__UINT_LEAST32_MAX__=0xffffffffUL", + "__FLT32X_HAS_DENORM__=1", + "__INT_FAST16_TYPE__=int", + "__XCHAL_HAVE_RELEASE_SYNC=1", + "__LDBL_HAS_DENORM__=1", + "__cplusplus=201703L", + "__cpp_ref_qualifiers=200710L", + "__INT_LEAST32_MAX__=0x7fffffffL", + "__DEPRECATED=1", + "__cpp_rvalue_references=200610L", + "__DBL_MAX_EXP__=1024", + "__WCHAR_WIDTH__=16", + "__FLT32_MAX__=3.4028234663852886e+38F32", + "__GCC_ATOMIC_LONG_LOCK_FREE=2", + "__PTRDIFF_MAX__=0x7fffffff", + "__FLT32_HAS_QUIET_NAN__=1", + "__GNUG__=14", + "__LONG_LONG_MAX__=0x7fffffffffffffffLL", + "__SIZEOF_SIZE_T__=4", + "__SIZEOF_WINT_T__=4", + "__FLT32X_DIG__=15", + "__LONG_LONG_WIDTH__=64", + "__cpp_initializer_lists=200806L", + "__FLT32_MAX_EXP__=128", + "__XCHAL_HAVE_MINMAX=1", + "__cpp_hex_float=201603L", + "__XCHAL_NUM_IBREAK=2", + "__GXX_ABI_VERSION=1019", + "__FLT_MIN_EXP__=(-125)", + "__cpp_lambdas=200907L", + "__INT_FAST64_TYPE__=long long int", + "__FP_FAST_FMAF=1", + "__FLT64_DENORM_MIN__=4.9406564584124654e-324F64", + "__DBL_MIN__=double(2.2250738585072014e-308L)", + "__SIZEOF_POINTER__=4", + "__DBL_HAS_QUIET_NAN__=1", + "__FLT32X_EPSILON__=2.2204460492503131e-16F32x", + "__XSHAL_HAVE_TEXT_SECTION_LITERALS=1", + "__FLT64_MIN_10_EXP__=(-307)", + "__REGISTER_PREFIX__", + "__UINT16_MAX__=0xffff", + "__XSHAL_USE_ABSOLUTE_LITERALS=0", + "__LDBL_HAS_INFINITY__=1", + "__FLT32_MIN__=1.1754943508222875e-38F32", + "__UINT8_TYPE__=unsigned char", + "__FLT_DIG__=6", + "__NO_INLINE__=1", + "__DEC_EVAL_METHOD__=2", + "__FLT_MANT_DIG__=24", + "__LDBL_DECIMAL_DIG__=17", + "__VERSION__=\"14.2.0\"", + "__UINT64_C(c)=c ## ULL", + "__XCHAL_NUM_AREGS=64", + "__cpp_unicode_characters=201411L", + "__XCHAL_HAVE_XEA3=0", + "__GCC_ATOMIC_INT_LOCK_FREE=2", + "__XCHAL_HAVE_DENSITY=1", + "__FLT32_MANT_DIG__=24", + "__FLOAT_WORD_ORDER__=__ORDER_LITTLE_ENDIAN__", + "__XCHAL_HAVE_CLAMPS=0", + "__XCHAL_HAVE_DFP_RSQRT=0", + "__cpp_aggregate_bases=201603L", + "__XCHAL_HAVE_NSA=1", + "__XCHAL_HAVE_WINDOWED=1", + "__SCHAR_WIDTH__=8", + "__INT32_C(c)=c ## L", + "__ORDER_PDP_ENDIAN__=3412", + "__INT_FAST32_TYPE__=int", + "__UINT_LEAST16_TYPE__=short unsigned int", + "__DBL_HAS_DENORM__=1", + "__XCHAL_HAVE_DEBUG=1", + "__cpp_rtti=199711L", + "__SIZE_TYPE__=unsigned int", + "__UINT64_MAX__=0xffffffffffffffffULL", + "__FLT_IS_IEC_60559__=1", + "__GNUC_WIDE_EXECUTION_CHARSET_NAME=\"UTF-16LE\"", + "__INT8_TYPE__=signed char", + "__cpp_digit_separators=201309L", + "__ELF__=1", + "__XSHAL_ABI=0", + "__xtensa__=1", + "__FLT_RADIX__=2", + "__INT_LEAST16_TYPE__=short int", + "__LDBL_EPSILON__=2.2204460492503131e-16L", + "__UINTMAX_C(c)=c ## ULL", + "__FLT32X_MIN__=2.2250738585072014e-308F32x", + "__XCHAL_HAVE_DFP_SQRT=0", + "__SIG_ATOMIC_MAX__=0x7fffffff", + "__XCHAL_HAVE_MAC16=1", + "__GCC_ATOMIC_WCHAR_T_LOCK_FREE=2", + "__USER_LABEL_PREFIX__", + "__SIZEOF_PTRDIFF_T__=4", + "__XCHAL_MMU_MIN_PTE_PAGE_SIZE=1", + "__XCHAL_DCACHE_IS_WRITEBACK=0", + "__SIZEOF_LONG__=4", + "__LDBL_DIG__=15", + "__FLT64_IS_IEC_60559__=1", + "__XCHAL_MAX_INSTRUCTION_SIZE=3", + "__FLT32X_MIN_EXP__=(-1021)", + "__INT_FAST16_MAX__=0x7fffffff", + "__GCC_CONSTRUCTIVE_SIZE=32", + "__FLT64_DIG__=15", + "__UINT_FAST32_MAX__=0xffffffffU", + "__UINT_LEAST64_TYPE__=long long unsigned int", + "__FLT_HAS_QUIET_NAN__=1", + "__FLT_MAX_10_EXP__=38", + "__FLT_HAS_INFINITY__=1", + "__GNUC_EXECUTION_CHARSET_NAME=\"UTF-8\"", + "__CHAR_UNSIGNED__=1", + "__cpp_unicode_literals=200710L", + "__UINT_FAST16_TYPE__=unsigned int", + "__INT_FAST32_WIDTH__=32", + "__CHAR16_TYPE__=short unsigned int", + "__PRAGMA_REDEFINE_EXTNAME=1", + "__SIZE_WIDTH__=32", + "__INT_LEAST16_MAX__=0x7fff", + "__INT64_MAX__=0x7fffffffffffffffLL", + "__FLT32_DENORM_MIN__=1.4012984643248171e-45F32", + "__SIG_ATOMIC_WIDTH__=32", + "__INT_LEAST64_TYPE__=long long int", + "__INT16_TYPE__=short int", + "__INT_LEAST8_TYPE__=signed char", + "__cpp_structured_bindings=201606L", + "__INT_FAST8_MAX__=0x7fffffff", + "__INTPTR_MAX__=0x7fffffff", + "__cpp_sized_deallocation=201309L", + "__cpp_guaranteed_copy_elision=201606L", + "__FLT64_HAS_QUIET_NAN__=1", + "__FLT32_MIN_10_EXP__=(-37)", + "__EXCEPTIONS=1", + "__UINT16_C(c)=c", + "__XCHAL_M_STAGE=3", + "__PTRDIFF_WIDTH__=32", + "__LDBL_MANT_DIG__=53", + "__cpp_range_based_for=201603L", + "__FLT64_HAS_INFINITY__=1", + "__STDCPP_DEFAULT_NEW_ALIGNMENT__=8", + "__SIG_ATOMIC_MIN__=(-__SIG_ATOMIC_MAX__ - 1)", + "__XCHAL_ICACHE_SIZE=0", + "__cpp_nontype_template_args=201411L", + "__INTPTR_TYPE__=int", + "__UINT16_TYPE__=short unsigned int", + "__WCHAR_TYPE__=short unsigned int", + "__XCHAL_HAVE_DEPBITS=0", + "__SIZEOF_FLOAT__=4", + "__UINTPTR_MAX__=0xffffffffU", + "__INT_FAST64_WIDTH__=64", + "__cpp_decltype=200707L", + "__FLT32_DECIMAL_DIG__=9", + "__INT_FAST64_MAX__=0x7fffffffffffffffLL", + "__GCC_ATOMIC_TEST_AND_SET_TRUEVAL=1", + "__FLT_NORM_MAX__=3.4028234663852886e+38F", + "__XCHAL_HAVE_DFP=0", + "__FLT32_HAS_INFINITY__=1", + "__UINT_FAST64_TYPE__=long long unsigned int", + "__cpp_inline_variables=201606L", + "__INT_MAX__=0x7fffffff", + "__XCHAL_HAVE_EXCLUSIVE=0", + "__STDCPP_THREADS__=1", + "__INT64_TYPE__=long long int", + "__XCHAL_HAVE_DFP_DIV=0", + "__FLT_MAX_EXP__=128", + "__XCHAL_INST_FETCH_WIDTH=4", + "__DBL_MANT_DIG__=53", + "__cpp_inheriting_constructors=201511L", + "__INT_LEAST64_MAX__=0x7fffffffffffffffLL", + "__FP_FAST_FMAF32=1", + "__WINT_TYPE__=unsigned int", + "__UINT_LEAST32_TYPE__=long unsigned int", + "__SIZEOF_SHORT__=2", + "__FLT32_NORM_MAX__=3.4028234663852886e+38F32", + "__LDBL_MIN_EXP__=(-1021)", + "__XCHAL_HAVE_S32C1I=1", + "__FLT64_MAX__=1.7976931348623157e+308F64", + "__WINT_WIDTH__=32", + "__cpp_template_auto=201606L", + "__INT_LEAST64_WIDTH__=64", + "__FLT32X_MAX_10_EXP__=308", + "__cpp_namespace_attributes=201411L", + "__WCHAR_UNSIGNED__=1", + "__LDBL_MAX_10_EXP__=308", + "__ATOMIC_RELAXED=0", + "__DBL_EPSILON__=double(2.2204460492503131e-16L)", + "__XCHAL_HAVE_SEXT=1", + "__INT_LEAST32_TYPE__=long int", + "__XTENSA_WINDOWED_ABI__=1", + "__UINT8_C(c)=c", + "__FLT64_MAX_EXP__=1024", + "__SIZEOF_WCHAR_T__=2", + "__XCHAL_HAVE_FP_POSTINC=1", + "__FLT64_NORM_MAX__=1.7976931348623157e+308F64", + "__INTMAX_MAX__=0x7fffffffffffffffLL", + "__INT_FAST8_TYPE__=int", + "__XCHAL_HAVE_MUL32_HIGH=1", + "__GNUC_STDC_INLINE__=1", + "__FLT64_HAS_DENORM__=1", + "__FLT32_EPSILON__=1.1920928955078125e-7F32", + "__DBL_DECIMAL_DIG__=17", + "__STDC_UTF_32__=1", + "__XCHAL_HAVE_FP_DIV=1", + "__INT_FAST8_WIDTH__=32", + "__FLT32X_MAX__=1.7976931348623157e+308F32x", + "__DBL_NORM_MAX__=double(1.7976931348623157e+308L)", + "__BYTE_ORDER__=__ORDER_LITTLE_ENDIAN__", + "__GCC_DESTRUCTIVE_SIZE=32", + "__XTENSA__=1", + "__INTMAX_WIDTH__=64", + "__ORDER_BIG_ENDIAN__=4321", + "__XTHAL_ABI_CALL0=1", + "__cpp_runtime_arrays=198712L", + "__FLT32_DIG__=6", + "__UINT64_TYPE__=long long unsigned int", + "__UINT32_C(c)=c ## UL", + "__cpp_alias_templates=200704L", + "__FLT_DENORM_MIN__=1.4012984643248171e-45F", + "__INT8_MAX__=0x7f", + "__LONG_WIDTH__=32", + "__UINT_FAST32_TYPE__=unsigned int", + "__FLT32X_NORM_MAX__=1.7976931348623157e+308F32x", + "__CHAR32_TYPE__=long unsigned int", + "__FLT_MAX__=3.4028234663852886e+38F", + "__cpp_constexpr=201603L", + "__XCHAL_HAVE_FP_RSQRT=1", + "__INT32_TYPE__=long int", + "__SIZEOF_DOUBLE__=8", + "__cpp_exceptions=199711L", + "__FLT_MIN_10_EXP__=(-37)", + "__FLT64_MIN__=2.2250738585072014e-308F64", + "__INT_LEAST32_WIDTH__=32", + "__INTMAX_TYPE__=long long int", + "__XCHAL_HAVE_ABS=1", + "__FLT32X_HAS_QUIET_NAN__=1", + "__ATOMIC_CONSUME=1", + "__XCHAL_NUM_DBREAK=2", + "__XCHAL_HAVE_WIDE_BRANCHES=0", + "__GNUC_MINOR__=2", + "__INT_FAST16_WIDTH__=32", + "__UINTMAX_MAX__=0xffffffffffffffffULL", + "__FLT32X_DENORM_MIN__=4.9406564584124654e-324F32x", + "__cpp_template_template_args=201611L", + "__DBL_MAX_10_EXP__=308", + "__LDBL_DENORM_MIN__=4.9406564584124654e-324L", + "__INT16_C(c)=c", + "__STDC__=1", + "__PTRDIFF_TYPE__=int", + "__LONG_MAX__=0x7fffffffL", + "__XCHAL_HAVE_FP_SQRT=1", + "__UINT32_TYPE__=long unsigned int", + "__FLT32X_MIN_10_EXP__=(-307)", + "__UINTPTR_TYPE__=unsigned int", + "__LDBL_MIN_10_EXP__=(-307)", + "__cpp_generic_lambdas=201304L", + "__SIZEOF_LONG_LONG__=8", + "__cpp_USER_defined_literals=200809L", + "__GCC_ATOMIC_LLONG_LOCK_FREE=1", + "__FLT_DECIMAL_DIG__=9", + "__UINT_FAST16_MAX__=0xffffffffU", + "__LDBL_NORM_MAX__=1.7976931348623157e+308L", + "__GCC_ATOMIC_SHORT_LOCK_FREE=2", + "__XCHAL_HAVE_BE=0", + "__UINT_FAST8_TYPE__=unsigned int", + "__cpp_init_captures=201304L", + "__ATOMIC_ACQ_REL=4", + "__ATOMIC_RELEASE=3", + "RMT_CLK_SRC_DEFAULT = SOC_MOD_CLK_APB", + "USBCON" + ] + }, + { + "name": "Arduino", + "compilerPath": "/home/derdoktor667/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++", + "compilerArgs": [ + "-MMD", + "-w", + "-Werror=return-type", + "-iprefix" + ], + "intelliSenseMode": "gcc-x64", + "includePath": [ + "/home/derdoktor667/Github/DShotRMT/examples/dshot300", + "/home/derdoktor667/.arduino15/packages/esp32/tools/esp32-arduino-libs/idf-release_v5.5-b66b5448-v1/esp32/qio_qspi/include", + "/home/derdoktor667/.arduino15/packages/esp32/hardware/esp32/3.3.0/cores/esp32", + "/home/derdoktor667/.arduino15/packages/esp32/hardware/esp32/3.3.0/variants/esp32", + "/home/derdoktor667/Arduino/libraries/DShotRMT/src", + "/home/derdoktor667/.arduino15/packages/esp32/tools/esp-x32/2411/xtensa-esp-elf/include/c++/14.2.0", + "/home/derdoktor667/.arduino15/packages/esp32/tools/esp-x32/2411/xtensa-esp-elf/include/c++/14.2.0/xtensa-esp-elf/esp32", + "/home/derdoktor667/.arduino15/packages/esp32/tools/esp-x32/2411/xtensa-esp-elf/include/c++/14.2.0/backward", + "/home/derdoktor667/.arduino15/packages/esp32/tools/esp-x32/2411/lib/gcc/xtensa-esp-elf/14.2.0/include", + "/home/derdoktor667/.arduino15/packages/esp32/tools/esp-x32/2411/lib/gcc/xtensa-esp-elf/14.2.0/include-fixed", + "/home/derdoktor667/.arduino15/packages/esp32/tools/esp-x32/2411/xtensa-esp-elf/include" + ], + "forcedInclude": [ + "/home/derdoktor667/.arduino15/packages/esp32/hardware/esp32/3.3.0/cores/esp32/Arduino.h" + ], + "cStandard": "c11", + "cppStandard": "c++11", + "defines": [ + "F_CPU=240000000L", + "ARDUINO=10607", + "ARDUINO_ESP32_DEV", + "ARDUINO_ARCH_ESP32", + "ARDUINO_BOARD=\"ESP32_DEV\"", + "ARDUINO_VARIANT=\"esp32\"", + "ARDUINO_PARTITION_default", + "ARDUINO_HOST_OS=\"linux\"", + "ARDUINO_FQBN=\"esp32:esp32:esp32:JTAGAdapter=default,PSRAM=disabled,PartitionScheme=default,CPUFreq=240,FlashMode=qio,FlashFreq=80,FlashSize=4M,UploadSpeed=921600,LoopCore=1,EventsCore=1,DebugLevel=none,EraseFlash=all,ZigbeeMode=default\"", + "ESP32=ESP32", + "CORE_DEBUG_LEVEL=0", + "ARDUINO_RUNNING_CORE=1", + "ARDUINO_EVENT_RUNNING_CORE=1", + "ARDUINO_USB_CDC_ON_BOOT=0", + "__DBL_MIN_EXP__=(-1021)", + "__XCHAL_HAVE_FP=1", + "__cpp_nontype_template_parameter_auto=201606L", + "__UINT_LEAST16_MAX__=0xffff", + "__ATOMIC_ACQUIRE=2", + "__FLT_MIN__=1.1754943508222875e-38F", + "__GCC_IEC_559_COMPLEX=0", + "__XCHAL_HAVE_PREDICTED_BRANCHES=0", + "__cpp_aggregate_nsdmi=201304L", + "__UINT_LEAST8_TYPE__=unsigned char", + "__INTMAX_C(c)=c ## LL", + "__XCHAL_HAVE_ADDX=1", + "__CHAR_BIT__=8", + "__XCHAL_DCACHE_LINESIZE=16", + "__XTENSA_MARCH_EARLIEST=260003", + "__XCHAL_DCACHE_LINEWIDTH=4", + "__UINT8_MAX__=0xff", + "__WINT_MAX__=0xffffffffU", + "__FLT32_MIN_EXP__=(-125)", + "__cpp_static_assert=201411L", + "__ORDER_LITTLE_ENDIAN__=1234", + "__SIZE_MAX__=0xffffffffU", + "__WCHAR_MAX__=0xffff", + "__GCC_HAVE_SYNC_COMPARE_AND_SWAP_1=1", + "__GCC_HAVE_SYNC_COMPARE_AND_SWAP_2=1", + "__GCC_HAVE_SYNC_COMPARE_AND_SWAP_4=1", + "__DBL_DENORM_MIN__=double(4.9406564584124654e-324L)", + "__GCC_ATOMIC_CHAR_LOCK_FREE=2", + "__GCC_IEC_559=0", + "__FLT32X_DECIMAL_DIG__=17", + "__FLT_EVAL_METHOD__=0", + "__cpp_binary_literals=201304L", + "__FLT64_DECIMAL_DIG__=17", + "__cpp_noexcept_function_type=201510L", + "__GCC_ATOMIC_CHAR32_T_LOCK_FREE=2", + "__cpp_variadic_templates=200704L", + "__UINT_FAST64_MAX__=0xffffffffffffffffULL", + "__SIG_ATOMIC_TYPE__=int", + "__DBL_MIN_10_EXP__=(-307)", + "__FINITE_MATH_ONLY__=0", + "__cpp_variable_templates=201304L", + "__XCHAL_HAVE_L32R=1", + "__FLT32X_MAX_EXP__=1024", + "__GNUC_PATCHLEVEL__=0", + "__FLT32_HAS_DENORM__=1", + "__UINT_FAST8_MAX__=0xffffffffU", + "__cpp_rvalue_reference=200610L", + "__XCHAL_HAVE_LOOPS=1", + "__cpp_nested_namespace_definitions=201411L", + "__XCHAL_DEBUGLEVEL=6", + "__INT8_C(c)=c", + "__XCHAL_HAVE_DFP_RECIP=0", + "__INT_LEAST8_WIDTH__=8", + "__cpp_variadic_using=201611L", + "__UINT_LEAST64_MAX__=0xffffffffffffffffULL", + "__INT_LEAST8_MAX__=0x7f", + "__cpp_attributes=200809L", + "__cpp_capture_star_this=201603L", + "__SHRT_MAX__=0x7fff", + "__LDBL_MAX__=1.7976931348623157e+308L", + "__cpp_if_constexpr=201606L", + "__XCHAL_ICACHE_LINESIZE=16", + "__LDBL_IS_IEC_60559__=1", + "__UINT_LEAST8_MAX__=0xff", + "__GCC_ATOMIC_BOOL_LOCK_FREE=2", + "__UINTMAX_TYPE__=long long unsigned int", + "__cpp_nsdmi=200809L", + "__FLT_EVAL_METHOD_TS_18661_3__=0", + "__UINT32_MAX__=0xffffffffUL", + "__GXX_EXPERIMENTAL_CXX0X__=1", + "__LDBL_MAX_EXP__=1024", + "__WINT_MIN__=0U", + "__FLT32X_IS_IEC_60559__=1", + "__XCHAL_HAVE_THREADPTR=1", + "__INT_LEAST16_WIDTH__=16", + "__SCHAR_MAX__=0x7f", + "__WCHAR_MIN__=0", + "__XCHAL_ICACHE_LINEWIDTH=4", + "__INT64_C(c)=c ## LL", + "__GCC_ATOMIC_POINTER_LOCK_FREE=2", + "__ATOMIC_SEQ_CST=5", + "__SIZEOF_INT__=4", + "__FLT32X_MANT_DIG__=53", + "__GCC_ATOMIC_CHAR16_T_LOCK_FREE=2", + "__cpp_aligned_new=201606L", + "__XCHAL_HAVE_FP_RECIP=1", + "__FLT32_MAX_10_EXP__=38", + "__STDC_HOSTED__=1", + "__XCHAL_HAVE_MUL32=1", + "__XTENSA_EL__=1", + "__cpp_decltype_auto=201304L", + "__DBL_DIG__=15", + "__XCHAL_HAVE_MUL16=1", + "__FLT_EPSILON__=1.1920928955078125e-7F", + "__GXX_WEAK__=1", + "__SHRT_WIDTH__=16", + "__FLT32_IS_IEC_60559__=1", + "__LDBL_MIN__=2.2250738585072014e-308L", + "__DBL_IS_IEC_60559__=1", + "__cpp_threadsafe_static_init=200806L", + "__cpp_enumerator_attributes=201411L", + "__XCHAL_HAVE_MMU=0", + "__FLT32X_HAS_INFINITY__=1", + "__INT32_MAX__=0x7fffffffL", + "__XCHAL_HAVE_DIV32=1", + "__INT_WIDTH__=32", + "__XTENSA_MARCH_LATEST=260003", + "__DECIMAL_DIG__=17", + "__FLT64_EPSILON__=2.2204460492503131e-16F64", + "__INT16_MAX__=0x7fff", + "__FLT64_MIN_EXP__=(-1021)", + "__XCHAL_DCACHE_SIZE=0", + "__LDBL_HAS_QUIET_NAN__=1", + "__cpp_return_type_deduction=201304L", + "__XCHAL_HAVE_BOOLEANS=1", + "__FLT64_MANT_DIG__=53", + "__XTHAL_ABI_WINDOWED=0", + "__GNUC__=14", + "__GXX_RTTI=1", + "__FLT_HAS_DENORM__=1", + "__SIZEOF_LONG_DOUBLE__=8", + "__XCHAL_HAVE_CONST16=0", + "__BIGGEST_ALIGNMENT__=16", + "__STDC_UTF_16__=1", + "__FLT64_MAX_10_EXP__=308", + "__cpp_delegating_constructors=200604L", + "__DBL_MAX__=double(1.7976931348623157e+308L)", + "__cpp_raw_strings=200710L", + "__INT_FAST32_MAX__=0x7fffffff", + "__DBL_HAS_INFINITY__=1", + "__cpp_deduction_guides=201703L", + "__HAVE_SPECULATION_SAFE_VALUE=1", + "__cpp_fold_expressions=201603L", + "__INTPTR_WIDTH__=32", + "__UINT_LEAST32_MAX__=0xffffffffUL", + "__FLT32X_HAS_DENORM__=1", + "__INT_FAST16_TYPE__=int", + "__XCHAL_HAVE_RELEASE_SYNC=1", + "__LDBL_HAS_DENORM__=1", + "__cplusplus=201703L", + "__cpp_ref_qualifiers=200710L", + "__INT_LEAST32_MAX__=0x7fffffffL", + "__DEPRECATED=1", + "__cpp_rvalue_references=200610L", + "__DBL_MAX_EXP__=1024", + "__WCHAR_WIDTH__=16", + "__FLT32_MAX__=3.4028234663852886e+38F32", + "__GCC_ATOMIC_LONG_LOCK_FREE=2", + "__PTRDIFF_MAX__=0x7fffffff", + "__FLT32_HAS_QUIET_NAN__=1", + "__GNUG__=14", + "__LONG_LONG_MAX__=0x7fffffffffffffffLL", + "__SIZEOF_SIZE_T__=4", + "__SIZEOF_WINT_T__=4", + "__FLT32X_DIG__=15", + "__LONG_LONG_WIDTH__=64", + "__cpp_initializer_lists=200806L", + "__FLT32_MAX_EXP__=128", + "__XCHAL_HAVE_MINMAX=1", + "__cpp_hex_float=201603L", + "__XCHAL_NUM_IBREAK=2", + "__GXX_ABI_VERSION=1019", + "__FLT_MIN_EXP__=(-125)", + "__cpp_lambdas=200907L", + "__INT_FAST64_TYPE__=long long int", + "__FP_FAST_FMAF=1", + "__FLT64_DENORM_MIN__=4.9406564584124654e-324F64", + "__DBL_MIN__=double(2.2250738585072014e-308L)", + "__SIZEOF_POINTER__=4", + "__DBL_HAS_QUIET_NAN__=1", + "__FLT32X_EPSILON__=2.2204460492503131e-16F32x", + "__XSHAL_HAVE_TEXT_SECTION_LITERALS=1", + "__FLT64_MIN_10_EXP__=(-307)", + "__REGISTER_PREFIX__", + "__UINT16_MAX__=0xffff", + "__XSHAL_USE_ABSOLUTE_LITERALS=0", + "__LDBL_HAS_INFINITY__=1", + "__FLT32_MIN__=1.1754943508222875e-38F32", + "__UINT8_TYPE__=unsigned char", + "__FLT_DIG__=6", + "__NO_INLINE__=1", + "__DEC_EVAL_METHOD__=2", + "__FLT_MANT_DIG__=24", + "__LDBL_DECIMAL_DIG__=17", + "__VERSION__=\"14.2.0\"", + "__UINT64_C(c)=c ## ULL", + "__XCHAL_NUM_AREGS=64", + "__cpp_unicode_characters=201411L", + "__XCHAL_HAVE_XEA3=0", + "__GCC_ATOMIC_INT_LOCK_FREE=2", + "__XCHAL_HAVE_DENSITY=1", + "__FLT32_MANT_DIG__=24", + "__FLOAT_WORD_ORDER__=__ORDER_LITTLE_ENDIAN__", + "__XCHAL_HAVE_CLAMPS=0", + "__XCHAL_HAVE_DFP_RSQRT=0", + "__cpp_aggregate_bases=201603L", + "__XCHAL_HAVE_NSA=1", + "__XCHAL_HAVE_WINDOWED=1", + "__SCHAR_WIDTH__=8", + "__INT32_C(c)=c ## L", + "__ORDER_PDP_ENDIAN__=3412", + "__INT_FAST32_TYPE__=int", + "__UINT_LEAST16_TYPE__=short unsigned int", + "__DBL_HAS_DENORM__=1", + "__XCHAL_HAVE_DEBUG=1", + "__cpp_rtti=199711L", + "__SIZE_TYPE__=unsigned int", + "__UINT64_MAX__=0xffffffffffffffffULL", + "__FLT_IS_IEC_60559__=1", + "__GNUC_WIDE_EXECUTION_CHARSET_NAME=\"UTF-16LE\"", + "__INT8_TYPE__=signed char", + "__cpp_digit_separators=201309L", + "__ELF__=1", + "__XSHAL_ABI=0", + "__xtensa__=1", + "__FLT_RADIX__=2", + "__INT_LEAST16_TYPE__=short int", + "__LDBL_EPSILON__=2.2204460492503131e-16L", + "__UINTMAX_C(c)=c ## ULL", + "__FLT32X_MIN__=2.2250738585072014e-308F32x", + "__XCHAL_HAVE_DFP_SQRT=0", + "__SIG_ATOMIC_MAX__=0x7fffffff", + "__XCHAL_HAVE_MAC16=1", + "__GCC_ATOMIC_WCHAR_T_LOCK_FREE=2", + "__USER_LABEL_PREFIX__", + "__SIZEOF_PTRDIFF_T__=4", + "__XCHAL_MMU_MIN_PTE_PAGE_SIZE=1", + "__XCHAL_DCACHE_IS_WRITEBACK=0", + "__SIZEOF_LONG__=4", + "__LDBL_DIG__=15", + "__FLT64_IS_IEC_60559__=1", + "__XCHAL_MAX_INSTRUCTION_SIZE=3", + "__FLT32X_MIN_EXP__=(-1021)", + "__INT_FAST16_MAX__=0x7fffffff", + "__GCC_CONSTRUCTIVE_SIZE=32", + "__FLT64_DIG__=15", + "__UINT_FAST32_MAX__=0xffffffffU", + "__UINT_LEAST64_TYPE__=long long unsigned int", + "__FLT_HAS_QUIET_NAN__=1", + "__FLT_MAX_10_EXP__=38", + "__FLT_HAS_INFINITY__=1", + "__GNUC_EXECUTION_CHARSET_NAME=\"UTF-8\"", + "__CHAR_UNSIGNED__=1", + "__cpp_unicode_literals=200710L", + "__UINT_FAST16_TYPE__=unsigned int", + "__INT_FAST32_WIDTH__=32", + "__CHAR16_TYPE__=short unsigned int", + "__PRAGMA_REDEFINE_EXTNAME=1", + "__SIZE_WIDTH__=32", + "__INT_LEAST16_MAX__=0x7fff", + "__INT64_MAX__=0x7fffffffffffffffLL", + "__FLT32_DENORM_MIN__=1.4012984643248171e-45F32", + "__SIG_ATOMIC_WIDTH__=32", + "__INT_LEAST64_TYPE__=long long int", + "__INT16_TYPE__=short int", + "__INT_LEAST8_TYPE__=signed char", + "__cpp_structured_bindings=201606L", + "__INT_FAST8_MAX__=0x7fffffff", + "__INTPTR_MAX__=0x7fffffff", + "__cpp_sized_deallocation=201309L", + "__cpp_guaranteed_copy_elision=201606L", + "__FLT64_HAS_QUIET_NAN__=1", + "__FLT32_MIN_10_EXP__=(-37)", + "__EXCEPTIONS=1", + "__UINT16_C(c)=c", + "__XCHAL_M_STAGE=3", + "__PTRDIFF_WIDTH__=32", + "__LDBL_MANT_DIG__=53", + "__cpp_range_based_for=201603L", + "__FLT64_HAS_INFINITY__=1", + "__STDCPP_DEFAULT_NEW_ALIGNMENT__=8", + "__SIG_ATOMIC_MIN__=(-__SIG_ATOMIC_MAX__ - 1)", + "__XCHAL_ICACHE_SIZE=0", + "__cpp_nontype_template_args=201411L", + "__INTPTR_TYPE__=int", + "__UINT16_TYPE__=short unsigned int", + "__WCHAR_TYPE__=short unsigned int", + "__XCHAL_HAVE_DEPBITS=0", + "__SIZEOF_FLOAT__=4", + "__UINTPTR_MAX__=0xffffffffU", + "__INT_FAST64_WIDTH__=64", + "__cpp_decltype=200707L", + "__FLT32_DECIMAL_DIG__=9", + "__INT_FAST64_MAX__=0x7fffffffffffffffLL", + "__GCC_ATOMIC_TEST_AND_SET_TRUEVAL=1", + "__FLT_NORM_MAX__=3.4028234663852886e+38F", + "__XCHAL_HAVE_DFP=0", + "__FLT32_HAS_INFINITY__=1", + "__UINT_FAST64_TYPE__=long long unsigned int", + "__cpp_inline_variables=201606L", + "__INT_MAX__=0x7fffffff", + "__XCHAL_HAVE_EXCLUSIVE=0", + "__STDCPP_THREADS__=1", + "__INT64_TYPE__=long long int", + "__XCHAL_HAVE_DFP_DIV=0", + "__FLT_MAX_EXP__=128", + "__XCHAL_INST_FETCH_WIDTH=4", + "__DBL_MANT_DIG__=53", + "__cpp_inheriting_constructors=201511L", + "__INT_LEAST64_MAX__=0x7fffffffffffffffLL", + "__FP_FAST_FMAF32=1", + "__WINT_TYPE__=unsigned int", + "__UINT_LEAST32_TYPE__=long unsigned int", + "__SIZEOF_SHORT__=2", + "__FLT32_NORM_MAX__=3.4028234663852886e+38F32", + "__LDBL_MIN_EXP__=(-1021)", + "__XCHAL_HAVE_S32C1I=1", + "__FLT64_MAX__=1.7976931348623157e+308F64", + "__WINT_WIDTH__=32", + "__cpp_template_auto=201606L", + "__INT_LEAST64_WIDTH__=64", + "__FLT32X_MAX_10_EXP__=308", + "__cpp_namespace_attributes=201411L", + "__WCHAR_UNSIGNED__=1", + "__LDBL_MAX_10_EXP__=308", + "__ATOMIC_RELAXED=0", + "__DBL_EPSILON__=double(2.2204460492503131e-16L)", + "__XCHAL_HAVE_SEXT=1", + "__INT_LEAST32_TYPE__=long int", + "__XTENSA_WINDOWED_ABI__=1", + "__UINT8_C(c)=c", + "__FLT64_MAX_EXP__=1024", + "__SIZEOF_WCHAR_T__=2", + "__XCHAL_HAVE_FP_POSTINC=1", + "__FLT64_NORM_MAX__=1.7976931348623157e+308F64", + "__INTMAX_MAX__=0x7fffffffffffffffLL", + "__INT_FAST8_TYPE__=int", + "__XCHAL_HAVE_MUL32_HIGH=1", + "__GNUC_STDC_INLINE__=1", + "__FLT64_HAS_DENORM__=1", + "__FLT32_EPSILON__=1.1920928955078125e-7F32", + "__DBL_DECIMAL_DIG__=17", + "__STDC_UTF_32__=1", + "__XCHAL_HAVE_FP_DIV=1", + "__INT_FAST8_WIDTH__=32", + "__FLT32X_MAX__=1.7976931348623157e+308F32x", + "__DBL_NORM_MAX__=double(1.7976931348623157e+308L)", + "__BYTE_ORDER__=__ORDER_LITTLE_ENDIAN__", + "__GCC_DESTRUCTIVE_SIZE=32", + "__XTENSA__=1", + "__INTMAX_WIDTH__=64", + "__ORDER_BIG_ENDIAN__=4321", + "__XTHAL_ABI_CALL0=1", + "__cpp_runtime_arrays=198712L", + "__FLT32_DIG__=6", + "__UINT64_TYPE__=long long unsigned int", + "__UINT32_C(c)=c ## UL", + "__cpp_alias_templates=200704L", + "__FLT_DENORM_MIN__=1.4012984643248171e-45F", + "__INT8_MAX__=0x7f", + "__LONG_WIDTH__=32", + "__UINT_FAST32_TYPE__=unsigned int", + "__FLT32X_NORM_MAX__=1.7976931348623157e+308F32x", + "__CHAR32_TYPE__=long unsigned int", + "__FLT_MAX__=3.4028234663852886e+38F", + "__cpp_constexpr=201603L", + "__XCHAL_HAVE_FP_RSQRT=1", + "__INT32_TYPE__=long int", + "__SIZEOF_DOUBLE__=8", + "__cpp_exceptions=199711L", + "__FLT_MIN_10_EXP__=(-37)", + "__FLT64_MIN__=2.2250738585072014e-308F64", + "__INT_LEAST32_WIDTH__=32", + "__INTMAX_TYPE__=long long int", + "__XCHAL_HAVE_ABS=1", + "__FLT32X_HAS_QUIET_NAN__=1", + "__ATOMIC_CONSUME=1", + "__XCHAL_NUM_DBREAK=2", + "__XCHAL_HAVE_WIDE_BRANCHES=0", + "__GNUC_MINOR__=2", + "__INT_FAST16_WIDTH__=32", + "__UINTMAX_MAX__=0xffffffffffffffffULL", + "__FLT32X_DENORM_MIN__=4.9406564584124654e-324F32x", + "__cpp_template_template_args=201611L", + "__DBL_MAX_10_EXP__=308", + "__LDBL_DENORM_MIN__=4.9406564584124654e-324L", + "__INT16_C(c)=c", + "__STDC__=1", + "__PTRDIFF_TYPE__=int", + "__LONG_MAX__=0x7fffffffL", + "__XCHAL_HAVE_FP_SQRT=1", + "__UINT32_TYPE__=long unsigned int", + "__FLT32X_MIN_10_EXP__=(-307)", + "__UINTPTR_TYPE__=unsigned int", + "__LDBL_MIN_10_EXP__=(-307)", + "__cpp_generic_lambdas=201304L", + "__SIZEOF_LONG_LONG__=8", + "__cpp_user_defined_literals=200809L", + "__GCC_ATOMIC_LLONG_LOCK_FREE=1", + "__FLT_DECIMAL_DIG__=9", + "__UINT_FAST16_MAX__=0xffffffffU", + "__LDBL_NORM_MAX__=1.7976931348623157e+308L", + "__GCC_ATOMIC_SHORT_LOCK_FREE=2", + "__XCHAL_HAVE_BE=0", + "__UINT_FAST8_TYPE__=unsigned int", + "__cpp_init_captures=201304L", + "__ATOMIC_ACQ_REL=4", + "__ATOMIC_RELEASE=3", + "USBCON" + ] + } + ] +} \ No newline at end of file diff --git a/.vscode/settings.json b/.vscode/settings.json new file mode 100644 index 0000000..b961c02 --- /dev/null +++ b/.vscode/settings.json @@ -0,0 +1,8 @@ +{ + "C_Cpp.errorSquiggles": "enabled", + "C_Cpp.default.compilerPath": "~/.arduino15/packages/esp32/tools/esp-x32/2411/bin/xtensa-esp32-elf-g++", + "files.associations": { + ".fantomasignore": "ignore", + "string_view": "cpp" + } +} \ No newline at end of file diff --git a/README.md b/README.md index fd1382b..44bb558 100644 --- a/README.md +++ b/README.md @@ -57,7 +57,7 @@ The library requires these additional libraries for full functionality: **Core DShotRMT (always required):** - ESP32 Arduino Core -**Web Interface Example (dshot300.ino):** +**Web Interface Example (web_control.ino / web_client.ino):** ```ini lib_deps = https://github.com/derdoktor667/DShotRMT @@ -101,92 +101,6 @@ void loop() { } } ``` - -### Web Control Interface - -```cpp -#include -#include -#include - -DShotRMT motor(17, DSHOT300, false); -AsyncWebServer server(80); -AsyncWebSocket ws("/ws"); - -void setup() { - // Initialize motor - motor.begin(); - - // Create WiFi Access Point - WiFi.softAP("DShotRMT Control", "12345678"); - - // Setup web interface - ws.onEvent(onWsEvent); - server.addHandler(&ws); - server.on("/", HTTP_GET, [](AsyncWebServerRequest *request) { - request->send_P(200, "text/html", index_html); - }); - server.begin(); - - // Access at http://10.10.10.1 -} - -void loop() { - // Handle WebSocket communication and motor control - ws.cleanupClients(); -} -``` - -### Advanced Command Management - -```cpp -#include -#include - -DShotRMT motor(17, DSHOT300, false); -DShotCommandManager cmdManager(motor); - -void setup() { - motor.begin(); - cmdManager.begin(); -} - -void loop() { - // High-level ESC control - cmdManager.stopMotor(); - cmdManager.activateBeacon(1); - cmdManager.setSpinDirection(false); - cmdManager.executeInitSequence(); -} -``` - -### Bidirectional DShot (RPM Telemetry) - -```cpp -#include - -// Enable bidirectional mode for telemetry -DShotRMT motor(17, DSHOT300, true); - -void setup() { - Serial.begin(115200); - motor.begin(); -} - -void loop() { - // Send throttle - motor.sendThrottle(1000); - - // Get telemetry data - dshot_telemetry_result_t telemetry = motor.getTelemetry(14); // 14 magnets - if (telemetry.success) { - Serial.printf("eRPM: %u, Motor RPM: %u\n", - telemetry.erpm, - telemetry.motor_rpm); - } -} -``` - --- ## 🌐 Web Control Interface @@ -228,7 +142,7 @@ Make sure you are using these libraries for [ESPAsyncWebServer](https://github.c The library includes comprehensive examples: -### 1. Basic DShot Control with Web Interface (`dshot300.ino`) +### 1. Basic DShot Control with Web Interface (`web_control.ino`) - **Web Control Interface:** Modern responsive web UI accessible at `http://10.10.10.1` - **WiFi Access Point:** Creates hotspot "DShotRMT Control" for wireless control - **Safety Features:** Arming/disarming system with motor safety lockout @@ -257,8 +171,8 @@ Interactive ESC control with full menu system: 0 - Emergency Stop Advanced Commands: - cmd - Send DShot command (0-47) - throttle - Set throttle (48-2047) + cmd - Send DShot command (0 - 47) + throttle - Set throttle (48 - 2047) repeat cmd count - Repeat command ``` @@ -274,6 +188,8 @@ Advanced Commands: | 300 | 300 kbit/s | 2.50 | 1.25 | 3.33 | ~53.28 | | 600 | 600 kbit/s | 1.25 | 0.625 | 1.67 | ~26.72 | +For DShot, T1H length is always double T0H length. + ### GPIO Configuration ```cpp // Using GPIO number @@ -294,14 +210,14 @@ DShotRMT motor(17, DSHOT300, true); | Command | Value | Description | Usage | |---------|-------|-------------|-------| | MOTOR_STOP | 0 | Stop motor | Always available | -| BEACON1 - 5 | 1 - 5 | Motor beeping | Motor identification | +| BEACON 1 - 5 | 1 - 5 | Motor beeping | Motor identification | | ESC_INFO | 6 | Request ESC info | Get ESC version/settings | | SPIN_DIRECTION_1/2 | 7 - 8 | Set spin direction | Motor configuration | | 3D_MODE_OFF/ON | 9 - 10 | 3D mode control | Bidirectional flight | | SAVE_SETTINGS | 12 | Save to EEPROM | Permanent configuration | | EXTENDED_TELEMETRY_ENABLE/DISABLE | 13 - 14 | Telemetry control | Data transmission | | SPIN_DIRECTION_NORMAL/REVERSED | 20 - 21 | Spin direction | Alias commands | -| LED0-3_ON/OFF | 22 - 29 | LED control | BLHeli32 only | +| LED 0-3_ON/OFF | 22 - 29 | LED control | BLHeli32 only | | AUDIO_STREAM_MODE | 30 | Audio mode toggle | KISS ESCs | | SILENT_MODE | 31 | Silent mode toggle | KISS ESCs | @@ -341,7 +257,7 @@ The library utilizes the ESP32's RMT (Remote Control) peripheral for precise sig ### Advantages - **Hardware Timing:** No CPU intervention during transmission - **Concurrent Operation:** Multiple channels can run simultaneously -- **DMA Support:** Efficient memory-to-peripheral transfers +- **DMA Support:** Efficient, automatic memory-to-peripheral transfers --- diff --git a/examples/command_manager/command_manager.ino b/examples/command_manager/command_manager.ino index 13b2228..4bc7bdd 100644 --- a/examples/command_manager/command_manager.ino +++ b/examples/command_manager/command_manager.ino @@ -308,13 +308,6 @@ void printSystemStatus() USB_SERIAL.println("\n=== System Status ==="); USB_SERIAL.printf("Current throttle: %u\n", throttle_now); USB_SERIAL.printf("Continuous mode: %s\n", throttle_now > 0 ? "ACTIVE" : "INACTIVE"); - USB_SERIAL.printf("GPIO Pin: %d\n", motor01.getGPIO()); - USB_SERIAL.printf("DShot Mode: DSHOT%d\n", - motor01.getMode() == DSHOT150 ? 150 : motor01.getMode() == DSHOT300 ? 300 - : motor01.getMode() == DSHOT600 ? 600 - : motor01.getMode() == DSHOT1200 ? 1200 - : 0); - USB_SERIAL.printf("Bidirectional: %s\n", motor01.is_bidirectional() ? "YES" : "NO"); USB_SERIAL.printf("Free heap: %u bytes\n", ESP.getFreeHeap()); USB_SERIAL.printf("Uptime: %lu seconds\n", millis() / 1000); } diff --git a/src/DShotCommandManager.h b/src/DShotCommandManager.h index 1c7dcff..9b05fc3 100644 --- a/src/DShotCommandManager.h +++ b/src/DShotCommandManager.h @@ -10,7 +10,6 @@ #include #include -#include // Command item typedef struct diff --git a/src/DShotRMT.cpp b/src/DShotRMT.cpp index de34797..0113eae 100644 --- a/src/DShotRMT.cpp +++ b/src/DShotRMT.cpp @@ -10,7 +10,7 @@ // Static Data & Helper Functions // Timing parameters for each DShot mode -// Format: {frame_length_ticks, ticks_per_bit, t1h_ticks, t1l_ticks, t0h_ticks, t0l_ticks} +// Format: {bit_length_us, t1h_length_us} static constexpr dshot_timing_us_t DSHOT_TIMING_US[] = { {0.00, 0.00}, {6.67, 5.00}, @@ -18,7 +18,7 @@ static constexpr dshot_timing_us_t DSHOT_TIMING_US[] = { {1.67, 1.25}, {0.83, 0.67}}; -// Helper function to print DShot results +// Helper function to print DShot results and telemetry void printDShotResult(dshot_result_t &result, Stream &output) { output.printf("Status: %s - %s", result.success ? "SUCCESS" : "FAILED", result.msg); @@ -60,7 +60,7 @@ DShotRMT::DShotRMT(gpio_num_t gpio, dshot_mode_t mode, bool is_bidirectional) _telemetry_ready_flag_atomic(false) { // Configure RMT ticks for DShot timings - _configureRMTTiming(); + _preCalculateRMTTiming(); } // Constructor using pin number @@ -365,7 +365,7 @@ uint16_t DShotRMT::_parseDShotPacket(const dshot_packet_t &packet) } // Calculate CRC -uint16_t DShotRMT::_calculateCRC(const uint16_t data) +uint16_t DShotRMT::_calculateCRC(const uint16_t &data) { // DShot CRC uint16_t crc = (data ^ (data >> 4) ^ (data >> 8)) & DSHOT_CRC_MASK; @@ -380,14 +380,14 @@ uint16_t DShotRMT::_calculateCRC(const uint16_t data) } // Configure RMT ticks for DShot timings -void DShotRMT::_configureRMTTiming() +void DShotRMT::_preCalculateRMTTiming() { // Convert DShot timings (us) to RMT ticks - _rmt_ticks.ticks_per_bit = static_cast(_dshot_timing.bit_length_us * RMT_TICKS_PER_US); + _rmt_ticks.bit_length_ticks = static_cast(_dshot_timing.bit_length_us * RMT_TICKS_PER_US); _rmt_ticks.t1h_ticks = static_cast(_dshot_timing.t1h_lenght_us * RMT_TICKS_PER_US); _rmt_ticks.t0h_ticks = _rmt_ticks.t1h_ticks >> 1; // High time for a 1 is always double that of a 0 - _rmt_ticks.t1l_ticks = _rmt_ticks.ticks_per_bit - _rmt_ticks.t1h_ticks; - _rmt_ticks.t0l_ticks = _rmt_ticks.ticks_per_bit - _rmt_ticks.t0h_ticks; + _rmt_ticks.t1l_ticks = _rmt_ticks.bit_length_ticks - _rmt_ticks.t1h_ticks; + _rmt_ticks.t0l_ticks = _rmt_ticks.bit_length_ticks - _rmt_ticks.t0h_ticks; // Pause between frames is frame time in us, some padding and about 30 us is added by hardware _frame_timer_us = (static_cast(_dshot_timing.bit_length_us * DSHOT_BITS_PER_FRAME) << 1) + DSHOT_PADDING_US; diff --git a/src/DShotRMT.h b/src/DShotRMT.h index ad356b0..6bb665b 100644 --- a/src/DShotRMT.h +++ b/src/DShotRMT.h @@ -23,7 +23,7 @@ static constexpr auto DSHOT_BITS_PER_FRAME = 16; static constexpr auto DEFAULT_MOTOR_MAGNET_COUNT = 14; // DShot Modes -typedef enum +typedef enum dshot_mode { DSHOT_OFF, DSHOT150, @@ -33,7 +33,7 @@ typedef enum } dshot_mode_t; // DShot Packet Structure -typedef struct +typedef struct dshot_packet { uint16_t throttle_value : 11; bool telemetric_request : 1; @@ -41,16 +41,16 @@ typedef struct } dshot_packet_t; // DShot Timing Configuration -typedef struct +typedef struct dshot_timing { double bit_length_us; double t1h_lenght_us; } dshot_timing_us_t; // RMT Timing Configuration -typedef struct +typedef struct rmt_ticks { - uint16_t ticks_per_bit; + uint16_t bit_length_ticks; uint16_t t1h_ticks; uint16_t t1l_ticks; uint16_t t0h_ticks; @@ -58,7 +58,7 @@ typedef struct } rmt_ticks_t; // Unified DShot Result Structure -typedef struct +typedef struct dshot_result { bool success; const char *msg; @@ -80,27 +80,22 @@ public: // Constructors & Destructor explicit DShotRMT(gpio_num_t gpio = GPIO_NUM_16, dshot_mode_t mode = DSHOT300, bool is_bidirectional = false); DShotRMT(uint16_t pin_nr, dshot_mode_t mode, bool is_bidirectional); + ~DShotRMT(); // Public Core Functions // Initialize the RMT module and DShot config dshot_result_t begin(); - // Send throttle value (48-2047) + // Send throttle value (48 - 2047) dshot_result_t sendThrottle(uint16_t throttle); - // Send DShot command (0-47) + // Send DShot command (0 - 47) dshot_result_t sendCommand(uint16_t command); // Get telemetry data (bidirectional mode only) dshot_result_t getTelemetry(uint16_t magnet_count = DEFAULT_MOTOR_MAGNET_COUNT); - // Public Getter Functions - gpio_num_t getGPIO() const { return _gpio; } - uint16_t getDShotPacket() const { return _parsed_packet; } - bool is_bidirectional() const { return _is_bidirectional; } - dshot_mode_t getMode() const { return _mode; } - // Public Info & Debug Functions void printDShotInfo(Stream &output = Serial) const; void printCpuInfo(Stream &output = Serial) const; @@ -140,7 +135,7 @@ private: static constexpr auto const RMT_TICKS_PER_US = DSHOT_RMT_RESOLUTION / (1 * 1000 * 1000); // RMT Ticks per microsecond static constexpr auto const RMT_BUFFER_SIZE = DSHOT_BITS_PER_FRAME; static constexpr auto const DSHOT_RX_TIMEOUT_MS = 2; - static constexpr auto const DSHOT_PADDING_US = 3; + static constexpr auto const DSHOT_PADDING_US = 20; // Add to pause between frames for compatibility static constexpr auto const RMT_BUFFER_SYMBOLS = 64; static constexpr auto const RMT_QUEUE_DEPTH = 1; static constexpr auto const GCR_BITS_PER_FRAME = 21; // Number of GCR bits in a DShot answer frame @@ -160,7 +155,6 @@ private: static constexpr char const *TX_INIT_FAILED = "TX RMT channel init failed!"; static constexpr char const *RX_INIT_SUCCESS = "RX RMT channel initialized successfully"; static constexpr char const *RX_INIT_FAILED = "RX RMT channel init failed!"; - static constexpr char const *RX_BUFFER_FAILED = "RX RMT buffer init failed!"; static constexpr char const *ENCODER_INIT_SUCCESS = "RMT encoder initialized successfully"; static constexpr char const *ENCODER_INIT_FAILED = "RMT encoder init failed!"; static constexpr char const *TRANSMISSION_SUCCESS = "Transmission successfully"; @@ -215,8 +209,8 @@ private: // Private Packet Management Functions dshot_packet_t _buildDShotPacket(const uint16_t &value); uint16_t _parseDShotPacket(const dshot_packet_t &packet); - uint16_t _calculateCRC(const uint16_t data); - void _configureRMTTiming(); + uint16_t _calculateCRC(const uint16_t &data); + void _preCalculateRMTTiming(); void _preCalculateBitPositions(); // Private Frame Processing Functions diff --git a/src/web_content.h b/src/web_content.h index 5a1bf28..2f7459d 100644 --- a/src/web_content.h +++ b/src/web_content.h @@ -6,7 +6,7 @@ * @license MIT */ -#pragma onve +#pragma once // Web Site Content static constexpr char index_html[] = R"rawliteral(